From 94244c1d933a859676a81e3ed241d5a7e74b98a9 Mon Sep 17 00:00:00 2001 From: Jesse S Date: Sat, 12 Sep 2020 19:50:15 -0700 Subject: [PATCH 01/44] Highlight Creality DWIN menu icons (#19368) --- Marlin/src/lcd/dwin/e3v2/dwin.cpp | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/Marlin/src/lcd/dwin/e3v2/dwin.cpp b/Marlin/src/lcd/dwin/e3v2/dwin.cpp index b7e72f09a19a..8aa908e423fd 100644 --- a/Marlin/src/lcd/dwin/e3v2/dwin.cpp +++ b/Marlin/src/lcd/dwin/e3v2/dwin.cpp @@ -227,6 +227,7 @@ void show_plus_or_minus(uint8_t size, uint16_t bColor, uint8_t iNum, uint8_t fNu void ICON_Print() { if (select_page.now == 0) { DWIN_ICON_Show(ICON, ICON_Print_1, 17, 130); + DWIN_Draw_Rectangle(0, White, 17, 130, 126, 229); if (HMI_flag.language_chinese) DWIN_Frame_AreaCopy(1, 1, 447, 271 - 243, 479 - 19, 58, 201); else @@ -244,6 +245,7 @@ void ICON_Print() { void ICON_Prepare() { if (select_page.now == 1) { DWIN_ICON_Show(ICON, ICON_Prepare_1, 145, 130); + DWIN_Draw_Rectangle(0, White, 145, 130, 254, 229); if (HMI_flag.language_chinese) DWIN_Frame_AreaCopy(1, 31, 447, 271 - 213, 479 - 19, 186, 201); else @@ -261,6 +263,7 @@ void ICON_Prepare() { void ICON_Control() { if (select_page.now == 2) { DWIN_ICON_Show(ICON, ICON_Control_1, 17, 246); + DWIN_Draw_Rectangle(0, White, 17, 246, 126, 345); if (HMI_flag.language_chinese) DWIN_Frame_AreaCopy(1, 61, 447, 271 - 183, 479 - 19, 58, 318); else @@ -278,6 +281,7 @@ void ICON_Control() { void ICON_StartInfo(bool show) { if (show) { DWIN_ICON_Show(ICON, ICON_Info_1, 145, 246); + DWIN_Draw_Rectangle(0, White, 145, 246, 254, 345); if (HMI_flag.language_chinese) DWIN_Frame_AreaCopy(1, 91, 447, 271 - 153, 479 - 19, 186, 318); else @@ -295,6 +299,7 @@ void ICON_StartInfo(bool show) { void ICON_Leveling(bool show) { if (show) { DWIN_ICON_Show(ICON, ICON_Leveling_1, 145, 246); + DWIN_Draw_Rectangle(0, White, 145, 246, 254, 345); if (HMI_flag.language_chinese) DWIN_Frame_AreaCopy(1, 211, 447, 238, 479 - 19, 186, 318); else @@ -312,6 +317,7 @@ void ICON_Leveling(bool show) { void ICON_Tune() { if (select_print.now == 0) { DWIN_ICON_Show(ICON, ICON_Setup_1, 8, 252); + DWIN_Draw_Rectangle(0, White, 8, 252, 87, 351); if (HMI_flag.language_chinese) DWIN_Frame_AreaCopy(1, 121, 447, 271 - 123, 479 - 21, 34, 325); else @@ -329,6 +335,7 @@ void ICON_Tune() { void ICON_Pause() { if (select_print.now == 1) { DWIN_ICON_Show(ICON, ICON_Pause_1, 96, 252); + DWIN_Draw_Rectangle(0, White, 96, 252, 175, 351); if (HMI_flag.language_chinese) DWIN_Frame_AreaCopy(1, 181, 447, 271 - 63, 479 - 20, 124, 325); else @@ -346,6 +353,7 @@ void ICON_Pause() { void ICON_Continue() { if (select_print.now == 1) { DWIN_ICON_Show(ICON, ICON_Continue_1, 96, 252); + DWIN_Draw_Rectangle(0, White, 96, 252, 175, 351); if (HMI_flag.language_chinese) DWIN_Frame_AreaCopy(1, 1, 447, 271 - 243, 479 - 19, 124, 325); else @@ -363,6 +371,7 @@ void ICON_Continue() { void ICON_Stop() { if (select_print.now == 2) { DWIN_ICON_Show(ICON, ICON_Stop_1, 184, 252); + DWIN_Draw_Rectangle(0, White, 184, 252, 263, 351); if (HMI_flag.language_chinese) DWIN_Frame_AreaCopy(1, 151, 447, 271 - 93, 479 - 20, 210, 325); else From dcf3587d9ac2a34638de6e3fb8daa2df47f0591a Mon Sep 17 00:00:00 2001 From: Giuliano Zaro <3684609+GMagician@users.noreply.github.com> Date: Sun, 13 Sep 2020 04:51:20 +0200 Subject: [PATCH 02/44] Update Italian language (#19365) --- Marlin/src/lcd/language/language_it.h | 18 ++++++++++++++++++ 1 file changed, 18 insertions(+) diff --git a/Marlin/src/lcd/language/language_it.h b/Marlin/src/lcd/language/language_it.h index 39980b846e4b..27087e5a5562 100644 --- a/Marlin/src/lcd/language/language_it.h +++ b/Marlin/src/lcd/language/language_it.h @@ -46,6 +46,7 @@ namespace Language_it { 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"); @@ -221,6 +222,10 @@ namespace Language_it { 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("Luce #2 Presets"); + 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"); @@ -465,6 +470,8 @@ namespace Language_it { 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_DELTA_CALIBRATE = _UxGT("Calibraz. Delta"); @@ -585,6 +592,17 @@ namespace Language_it { PROGMEM Language_Str MSG_BAD_PAGE = _UxGT("Indice pag. errato"); PROGMEM Language_Str 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"); + // // 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. From d07ce9ef2192267b2f3629581ce90372563b4127 Mon Sep 17 00:00:00 2001 From: Jason Smith Date: Sat, 12 Sep 2020 19:52:46 -0700 Subject: [PATCH 03/44] Fix EXP2 pin define for MKS SGEN_L (#19369) --- Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h index 733751eb0a8e..23558b2e0474 100644 --- a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h +++ b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h @@ -229,7 +229,7 @@ * _____ _____ * (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 | · · | 1.20 (SD_MOSI) + * (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 * ----- ----- @@ -279,7 +279,7 @@ #define DOGLCD_CS P0_18 #define DOGLCD_A0 P0_16 #define DOGLCD_SCK P0_07 - #define DOGLCD_MOSI P1_20 + #define DOGLCD_MOSI P0_09 #define LCD_BACKLIGHT_PIN -1 From c04d5624da568c1069065902373f1abce11e03ba Mon Sep 17 00:00:00 2001 From: ManuelMcLure Date: Sat, 12 Sep 2020 20:59:20 -0700 Subject: [PATCH 04/44] Read from backup TMC StealthChop state (#19364) --- Marlin/src/feature/tmc_util.h | 3 ++ Marlin/src/module/settings.cpp | 64 +++++++++++++++++----------------- 2 files changed, 35 insertions(+), 32 deletions(-) diff --git a/Marlin/src/feature/tmc_util.h b/Marlin/src/feature/tmc_util.h index 2779ae4ef4b4..d96939c91611 100644 --- a/Marlin/src/feature/tmc_util.h +++ b/Marlin/src/feature/tmc_util.h @@ -105,6 +105,7 @@ class TMCMarlin : public TMC, public TMCStorage { #if HAS_STEALTHCHOP inline void refresh_stepping_mode() { this->en_pwm_mode(this->stored.stealthChop_enabled); } inline bool get_stealthChop_status() { return this->en_pwm_mode(); } + inline bool get_stored_stealthChop_status() { return this->stored.stealthChop_enabled; } #endif #if ENABLED(HYBRID_THRESHOLD) @@ -171,6 +172,7 @@ class TMCMarlin : public TMC220 #if HAS_STEALTHCHOP inline void refresh_stepping_mode() { en_spreadCycle(!this->stored.stealthChop_enabled); } inline bool get_stealthChop_status() { return !this->en_spreadCycle(); } + inline bool get_stored_stealthChop_status() { return this->stored.stealthChop_enabled; } #endif #if ENABLED(HYBRID_THRESHOLD) @@ -216,6 +218,7 @@ class TMCMarlin : public TMC220 #if HAS_STEALTHCHOP inline void refresh_stepping_mode() { en_spreadCycle(!this->stored.stealthChop_enabled); } inline bool get_stealthChop_status() { return !this->en_spreadCycle(); } + inline bool get_stored_stealthChop_status() { return this->stored.stealthChop_enabled; } #endif #if ENABLED(HYBRID_THRESHOLD) diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index 8af2071e3600..2c679068b936 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -1191,60 +1191,60 @@ void MarlinSettings::postprocess() { #if HAS_STEALTHCHOP #if AXIS_HAS_STEALTHCHOP(X) - tmc_stealth_enabled.X = stepperX.get_stealthChop_status(); + tmc_stealth_enabled.X = stepperX.get_stored_stealthChop_status(); #endif #if AXIS_HAS_STEALTHCHOP(Y) - tmc_stealth_enabled.Y = stepperY.get_stealthChop_status(); + tmc_stealth_enabled.Y = stepperY.get_stored_stealthChop_status(); #endif #if AXIS_HAS_STEALTHCHOP(Z) - tmc_stealth_enabled.Z = stepperZ.get_stealthChop_status(); + tmc_stealth_enabled.Z = stepperZ.get_stored_stealthChop_status(); #endif #if AXIS_HAS_STEALTHCHOP(X2) - tmc_stealth_enabled.X2 = stepperX2.get_stealthChop_status(); + tmc_stealth_enabled.X2 = stepperX2.get_stored_stealthChop_status(); #endif #if AXIS_HAS_STEALTHCHOP(Y2) - tmc_stealth_enabled.Y2 = stepperY2.get_stealthChop_status(); + tmc_stealth_enabled.Y2 = stepperY2.get_stored_stealthChop_status(); #endif #if AXIS_HAS_STEALTHCHOP(Z2) - tmc_stealth_enabled.Z2 = stepperZ2.get_stealthChop_status(); + tmc_stealth_enabled.Z2 = stepperZ2.get_stored_stealthChop_status(); #endif #if AXIS_HAS_STEALTHCHOP(Z3) - tmc_stealth_enabled.Z3 = stepperZ3.get_stealthChop_status(); + tmc_stealth_enabled.Z3 = stepperZ3.get_stored_stealthChop_status(); #endif #if AXIS_HAS_STEALTHCHOP(Z4) - tmc_stealth_enabled.Z4 = stepperZ4.get_stealthChop_status(); + tmc_stealth_enabled.Z4 = stepperZ4.get_stored_stealthChop_status(); #endif #if MAX_EXTRUDERS #if AXIS_HAS_STEALTHCHOP(E0) - tmc_stealth_enabled.E0 = stepperE0.get_stealthChop_status(); + tmc_stealth_enabled.E0 = stepperE0.get_stored_stealthChop_status(); #endif #if MAX_EXTRUDERS > 1 #if AXIS_HAS_STEALTHCHOP(E1) - tmc_stealth_enabled.E1 = stepperE1.get_stealthChop_status(); + tmc_stealth_enabled.E1 = stepperE1.get_stored_stealthChop_status(); #endif #if MAX_EXTRUDERS > 2 #if AXIS_HAS_STEALTHCHOP(E2) - tmc_stealth_enabled.E2 = stepperE2.get_stealthChop_status(); + tmc_stealth_enabled.E2 = stepperE2.get_stored_stealthChop_status(); #endif #if MAX_EXTRUDERS > 3 #if AXIS_HAS_STEALTHCHOP(E3) - tmc_stealth_enabled.E3 = stepperE3.get_stealthChop_status(); + tmc_stealth_enabled.E3 = stepperE3.get_stored_stealthChop_status(); #endif #if MAX_EXTRUDERS > 4 #if AXIS_HAS_STEALTHCHOP(E4) - tmc_stealth_enabled.E4 = stepperE4.get_stealthChop_status(); + tmc_stealth_enabled.E4 = stepperE4.get_stored_stealthChop_status(); #endif #if MAX_EXTRUDERS > 5 #if AXIS_HAS_STEALTHCHOP(E5) - tmc_stealth_enabled.E5 = stepperE5.get_stealthChop_status(); + tmc_stealth_enabled.E5 = stepperE5.get_stored_stealthChop_status(); #endif #if MAX_EXTRUDERS > 6 #if AXIS_HAS_STEALTHCHOP(E6) - tmc_stealth_enabled.E6 = stepperE6.get_stealthChop_status(); + tmc_stealth_enabled.E6 = stepperE6.get_stored_stealthChop_status(); #endif #if MAX_EXTRUDERS > 7 #if AXIS_HAS_STEALTHCHOP(E7) - tmc_stealth_enabled.E7 = stepperE7.get_stealthChop_status(); + tmc_stealth_enabled.E7 = stepperE7.get_stored_stealthChop_status(); #endif #endif // MAX_EXTRUDERS > 7 #endif // MAX_EXTRUDERS > 6 @@ -3595,17 +3595,17 @@ void MarlinSettings::reset() { #if HAS_STEALTHCHOP CONFIG_ECHO_HEADING("Driver stepping mode:"); #if AXIS_HAS_STEALTHCHOP(X) - const bool chop_x = stepperX.get_stealthChop_status(); + const bool chop_x = stepperX.get_stored_stealthChop_status(); #else constexpr bool chop_x = false; #endif #if AXIS_HAS_STEALTHCHOP(Y) - const bool chop_y = stepperY.get_stealthChop_status(); + const bool chop_y = stepperY.get_stored_stealthChop_status(); #else constexpr bool chop_y = false; #endif #if AXIS_HAS_STEALTHCHOP(Z) - const bool chop_z = stepperZ.get_stealthChop_status(); + const bool chop_z = stepperZ.get_stored_stealthChop_status(); #else constexpr bool chop_z = false; #endif @@ -3619,17 +3619,17 @@ void MarlinSettings::reset() { } #if AXIS_HAS_STEALTHCHOP(X2) - const bool chop_x2 = stepperX2.get_stealthChop_status(); + const bool chop_x2 = stepperX2.get_stored_stealthChop_status(); #else constexpr bool chop_x2 = false; #endif #if AXIS_HAS_STEALTHCHOP(Y2) - const bool chop_y2 = stepperY2.get_stealthChop_status(); + const bool chop_y2 = stepperY2.get_stored_stealthChop_status(); #else constexpr bool chop_y2 = false; #endif #if AXIS_HAS_STEALTHCHOP(Z2) - const bool chop_z2 = stepperZ2.get_stealthChop_status(); + const bool chop_z2 = stepperZ2.get_stored_stealthChop_status(); #else constexpr bool chop_z2 = false; #endif @@ -3643,36 +3643,36 @@ void MarlinSettings::reset() { } #if AXIS_HAS_STEALTHCHOP(Z3) - if (stepperZ3.get_stealthChop_status()) { say_M569(forReplay, PSTR("I2 Z"), true); } + if (stepperZ3.get_stored_stealthChop_status()) { say_M569(forReplay, PSTR("I2 Z"), true); } #endif #if AXIS_HAS_STEALTHCHOP(Z4) - if (stepperZ4.get_stealthChop_status()) { say_M569(forReplay, PSTR("I3 Z"), true); } + if (stepperZ4.get_stored_stealthChop_status()) { say_M569(forReplay, PSTR("I3 Z"), true); } #endif #if AXIS_HAS_STEALTHCHOP(E0) - if (stepperE0.get_stealthChop_status()) { say_M569(forReplay, PSTR("T0 E"), true); } + if (stepperE0.get_stored_stealthChop_status()) { say_M569(forReplay, PSTR("T0 E"), true); } #endif #if AXIS_HAS_STEALTHCHOP(E1) - if (stepperE1.get_stealthChop_status()) { say_M569(forReplay, PSTR("T1 E"), true); } + if (stepperE1.get_stored_stealthChop_status()) { say_M569(forReplay, PSTR("T1 E"), true); } #endif #if AXIS_HAS_STEALTHCHOP(E2) - if (stepperE2.get_stealthChop_status()) { say_M569(forReplay, PSTR("T2 E"), true); } + if (stepperE2.get_stored_stealthChop_status()) { say_M569(forReplay, PSTR("T2 E"), true); } #endif #if AXIS_HAS_STEALTHCHOP(E3) - if (stepperE3.get_stealthChop_status()) { say_M569(forReplay, PSTR("T3 E"), true); } + if (stepperE3.get_stored_stealthChop_status()) { say_M569(forReplay, PSTR("T3 E"), true); } #endif #if AXIS_HAS_STEALTHCHOP(E4) - if (stepperE4.get_stealthChop_status()) { say_M569(forReplay, PSTR("T4 E"), true); } + if (stepperE4.get_stored_stealthChop_status()) { say_M569(forReplay, PSTR("T4 E"), true); } #endif #if AXIS_HAS_STEALTHCHOP(E5) - if (stepperE5.get_stealthChop_status()) { say_M569(forReplay, PSTR("T5 E"), true); } + if (stepperE5.get_stored_stealthChop_status()) { say_M569(forReplay, PSTR("T5 E"), true); } #endif #if AXIS_HAS_STEALTHCHOP(E6) - if (stepperE6.get_stealthChop_status()) { say_M569(forReplay, PSTR("T6 E"), true); } + if (stepperE6.get_stored_stealthChop_status()) { say_M569(forReplay, PSTR("T6 E"), true); } #endif #if AXIS_HAS_STEALTHCHOP(E7) - if (stepperE7.get_stealthChop_status()) { say_M569(forReplay, PSTR("T7 E"), true); } + if (stepperE7.get_stored_stealthChop_status()) { say_M569(forReplay, PSTR("T7 E"), true); } #endif #endif // HAS_STEALTHCHOP From 7c7e663911f859b511eaf5066e7c331f59148704 Mon Sep 17 00:00:00 2001 From: ellensp Date: Sun, 13 Sep 2020 16:01:03 +1200 Subject: [PATCH 05/44] Fix extra string substitution bug (#19351) --- Marlin/src/lcd/lcdprint.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/Marlin/src/lcd/lcdprint.cpp b/Marlin/src/lcd/lcdprint.cpp index 0f7f945a9925..1355dbbf2ddb 100644 --- a/Marlin/src/lcd/lcdprint.cpp +++ b/Marlin/src/lcd/lcdprint.cpp @@ -57,7 +57,10 @@ lcd_uint_t lcd_put_u8str_ind_P(PGM_P const pstr, const int8_t ind, PGM_P const i PGM_P const b = ind == -2 ? GET_TEXT(MSG_CHAMBER) : GET_TEXT(MSG_BED); n -= lcd_put_u8str_max_P(b, n * (MENU_FONT_WIDTH)) / (MENU_FONT_WIDTH); } - if (n) n -= lcd_put_u8str_max_P((PGM_P)p, n * (MENU_FONT_WIDTH)) / (MENU_FONT_WIDTH); + if (n) { + n -= lcd_put_u8str_max_P((PGM_P)p, n * (MENU_FONT_WIDTH)) / (MENU_FONT_WIDTH); + break; + } } else if (ch == '$' && inStr) { n -= lcd_put_u8str_max_P(inStr, n * (MENU_FONT_WIDTH)) / (MENU_FONT_WIDTH); From 872516f9f903157fbd927bf6083996da70ab4e63 Mon Sep 17 00:00:00 2001 From: Marcio T Date: Sat, 12 Sep 2020 22:32:00 -0600 Subject: [PATCH 06/44] Touch UI "Leveling" menu, misc. fixes (#19349) --- Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp | 3 + .../ftdi_eve_lib/extras/poly_ui.h | 41 ++-- .../ftdi_eve_touch_ui/language/language_en.h | 3 +- .../screens/advanced_settings_menu.cpp | 20 +- .../screens/bed_mesh_screen.cpp | 43 +++-- .../screens/bio_status_screen.cpp | 35 ++-- .../screens/filament_menu.cpp | 65 +++---- .../screens/files_screen.cpp | 2 +- .../ftdi_eve_touch_ui/screens/main_menu.cpp | 52 ++--- .../ftdi_eve_touch_ui/screens/screen_data.h | 1 + .../lib/ftdi_eve_touch_ui/screens/screens.cpp | 15 +- .../lib/ftdi_eve_touch_ui/screens/screens.h | 177 ++++++++++-------- .../lib/ftdi_eve_touch_ui/theme/colors.h | 8 +- Marlin/src/lcd/extui/ui_api.cpp | 4 + Marlin/src/lcd/extui/ui_api.h | 7 +- 15 files changed, 258 insertions(+), 218 deletions(-) diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index d13a8c3dc455..9fc9ec099e8b 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -736,6 +736,7 @@ uint8_t count = GRID_MAX_POINTS; mesh_index_pair best; + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(best.pos, ExtUI::MESH_START)); do { if (do_ubl_mesh_map) display_map(g29_map_type); @@ -775,6 +776,8 @@ } while (best.pos.x >= 0 && --count); + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(best.pos, ExtUI::MESH_FINISH)); + // Release UI during stow to allow for PAUSE_BEFORE_DEPLOY_STOW TERN_(HAS_LCD_MENU, ui.release()); probe.stow(); diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extras/poly_ui.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extras/poly_ui.h index 3abc6fca2dc8..450b9c4415e0 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extras/poly_ui.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extras/poly_ui.h @@ -16,7 +16,7 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #pragma once @@ -36,7 +36,7 @@ * * PolyReader r(data, N_ELEMENTS(data)); * - * for(r.start();r.has_more(); r.next()) { + * for (r.start();r.has_more(); r.next()) { * uint16_t x = r.x; * uint16_t y = r.y; * @@ -107,8 +107,8 @@ class PolyReader { } } - bool has_more() {return p != NULL;} - bool end_of_loop() {return start_x == eol;} + bool has_more() { return p != NULL; } + bool end_of_loop() { return start_x == eol; } }; /** @@ -129,7 +129,7 @@ class TransformedPolyReader : public PolyReader { */ static constexpr uint8_t fract_bits = 5; typedef int16_t fix_t; - fix_t makefix(float f) {return f * (1 << fract_bits);} + fix_t makefix(float f) { return f * (1 << fract_bits); } // First two rows of 3x3 transformation matrix fix_t a, b, c; @@ -254,6 +254,13 @@ class GenericPolyUI { draw_mode_t mode; public: + enum ButtonStyle : uint8_t { + FILL = 1, + STROKE = 2, + SHADOW = 4, + REGULAR = 7 + }; + typedef POLY_READER poly_reader_t; GenericPolyUI(CommandProcessor &c, draw_mode_t what = BOTH) : cmd(c), mode(what) {} @@ -276,7 +283,7 @@ class GenericPolyUI { Polygon p(cmd); p.begin_fill(); p.begin_loop(); - for(r.start();r.has_more();r.next()) { + for (r.start();r.has_more();r.next()) { p(r.x * 16, r.y * 16); if (r.end_of_loop()) { p.end_loop(); @@ -306,7 +313,7 @@ class GenericPolyUI { Polygon p(cmd); p.begin_stroke(); p.begin_loop(); - for(r.start();r.has_more(); r.next()) { + for (r.start();r.has_more(); r.next()) { p(r.x * 16, r.y * 16); if (r.end_of_loop()) { p.end_loop(); @@ -323,7 +330,7 @@ class GenericPolyUI { int16_t y_min = INT16_MAX; int16_t x_max = INT16_MIN; int16_t y_max = INT16_MIN; - for(r.start(); r.has_more(); r.next()) { + for (r.start(); r.has_more(); r.next()) { x_min = min(x_min, int16_t(r.x)); x_max = max(x_max, int16_t(r.x)); y_min = min(y_min, int16_t(r.y)); @@ -355,11 +362,11 @@ class GenericPolyUI { btn_shadow_depth = depth; } - void button(const uint8_t tag, poly_reader_t r) { + void button(const uint8_t tag, poly_reader_t r, uint8_t style = REGULAR) { using namespace FTDI; // Draw the shadow #if FTDI_API_LEVEL >= 810 - if (mode & BACKGROUND) { + if (mode & BACKGROUND && style & SHADOW) { cmd.cmd(SAVE_CONTEXT()); cmd.cmd(TAG(tag)); cmd.cmd(VERTEX_TRANSLATE_X(btn_shadow_depth * 16)); @@ -381,11 +388,15 @@ class GenericPolyUI { #endif // Draw the fill and stroke cmd.cmd(TAG(tag)); - cmd.cmd(COLOR_RGB(btn_fill_color)); - fill(r, false); - cmd.cmd(COLOR_RGB(btn_stroke_color)); - cmd.cmd(LINE_WIDTH(btn_stroke_width)); - stroke(r); + if (style & FILL) { + cmd.cmd(COLOR_RGB(btn_fill_color)); + fill(r, false); + } + if (style & STROKE) { + cmd.cmd(COLOR_RGB(btn_stroke_color)); + cmd.cmd(LINE_WIDTH(btn_stroke_width)); + stroke(r); + } cmd.cmd(RESTORE_CONTEXT()); } } diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/language/language_en.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/language/language_en.h index f2971087c160..e465aa0b93a7 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/language/language_en.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/language/language_en.h @@ -145,7 +145,8 @@ namespace Language_en { PROGMEM Language_Str MSG_TOUCH_CALIBRATION_PROMPT = u8"Touch the dots to calibrate"; PROGMEM Language_Str MSG_AUTOLEVEL_X_AXIS = u8"Level X Axis"; PROGMEM Language_Str MSG_BED_MAPPING_DONE = u8"Bed mapping finished"; - PROGMEM Language_Str MSG_RESET_BLTOUCH = u8"Reset BLTouch"; + PROGMEM Language_Str MSG_LEVELING = u8"Leveling"; + PROGMEM Language_Str MSG_SHOW_MESH = u8"Show Bed Mesh"; #ifdef TOUCH_UI_LULZBOT_BIO PROGMEM Language_Str MSG_MOVE_TO_HOME = u8"Move to Home"; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp index 35040734b472..67b077a55323 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp @@ -55,11 +55,11 @@ void AdvancedSettingsMenu::onRedraw(draw_mode_t what) { #define ACCELERATION_POS BTN_POS(2,5), BTN_SIZE(1,1) #define ENDSTOPS_POS BTN_POS(1,6), BTN_SIZE(1,1) #define JERK_POS BTN_POS(2,6), BTN_SIZE(1,1) - #define OFFSETS_POS BTN_POS(1,7), BTN_SIZE(1,1) + #define CASE_LIGHT_POS BTN_POS(1,7), BTN_SIZE(1,1) #define BACKLASH_POS BTN_POS(2,7), BTN_SIZE(1,1) - #define CASE_LIGHT_POS BTN_POS(1,8), BTN_SIZE(1,1) + #define OFFSETS_POS BTN_POS(1,8), BTN_SIZE(1,1) #define TMC_HOMING_THRS_POS BTN_POS(2,8), BTN_SIZE(1,1) - #if EITHER(CASE_LIGHT_ENABLE, SENSORLESS_HOMING) + #if EITHER(HAS_MULTI_HOTEND, SENSORLESS_HOMING) #define BACK_POS BTN_POS(1,9), BTN_SIZE(2,1) #else #define BACK_POS BTN_POS(1,8), BTN_SIZE(2,1) @@ -98,8 +98,8 @@ void AdvancedSettingsMenu::onRedraw(draw_mode_t what) { .tag(13).button( TMC_CURRENT_POS, GET_TEXT_F(MSG_TMC_CURRENT)) .enabled(ENABLED(SENSORLESS_HOMING)) .tag(14).button( TMC_HOMING_THRS_POS, GET_TEXT_F(MSG_TMC_HOMING_THRS)) - .enabled(EITHER(HAS_MULTI_HOTEND, BLTOUCH)) - .tag(4) .button( OFFSETS_POS, GET_TEXT_F(TERN(HAS_MULTI_HOTEND, MSG_OFFSETS_MENU, MSG_RESET_BLTOUCH))) + .enabled(ENABLED(HAS_MULTI_HOTEND)) + .tag(4) .button( OFFSETS_POS, GET_TEXT_F(MSG_OFFSETS_MENU)) .enabled(EITHER(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR)) .tag(11).button( FILAMENT_POS, GET_TEXT_F(MSG_FILAMENT)) .tag(12).button( ENDSTOPS_POS, GET_TEXT_F(MSG_LCD_ENDSTOPS)) @@ -123,13 +123,9 @@ bool AdvancedSettingsMenu::onTouchEnd(uint8_t tag) { case 2: GOTO_SCREEN(ZOffsetScreen); break; #endif case 3: GOTO_SCREEN(StepsScreen); break; - case 4: - #if HAS_MULTI_HOTEND - GOTO_SCREEN(NozzleOffsetScreen); - #elif ENABLED(BLTOUCH) - injectCommands_P(PSTR("M280 P0 S60")); - #endif - break; + #if ENABLED(HAS_MULTI_HOTEND) + case 4: GOTO_SCREEN(NozzleOffsetScreen); break; + #endif case 5: GOTO_SCREEN(MaxVelocityScreen); break; case 6: GOTO_SCREEN(DefaultAccelerationScreen); break; case 7: GOTO_SCREEN(TERN(HAS_JUNCTION_DEVIATION, JunctionDeviationScreen, JerkScreen)); break; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bed_mesh_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bed_mesh_screen.cpp index 663555f05de7..eea2268c5b9c 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bed_mesh_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bed_mesh_screen.cpp @@ -222,7 +222,8 @@ bool BedMeshScreen::tagToPoint(uint8_t tag, uint8_t &x, uint8_t &y) { void BedMeshScreen::onEntry() { screen_data.BedMeshScreen.highlightedTag = 0; - screen_data.BedMeshScreen.count = 0; + screen_data.BedMeshScreen.count = GRID_MAX_POINTS; + screen_data.BedMeshScreen.showMappingDone = false; BaseScreen::onEntry(); } @@ -251,6 +252,10 @@ void BedMeshScreen::drawHighlightedPointValue() { .colors(action_btn) .tag(1).button( OKAY_POS, GET_TEXT_F(MSG_BUTTON_OKAY)) .tag(0); + + if (screen_data.BedMeshScreen.showMappingDone) { + cmd.text(MESSAGE_POS, GET_TEXT_F(MSG_BED_MAPPING_DONE)); + } } void BedMeshScreen::onRedraw(draw_mode_t what) { @@ -270,17 +275,13 @@ void BedMeshScreen::onRedraw(draw_mode_t what) { if (what & FOREGROUND) { constexpr float autoscale_max_amplitude = 0.03; - const bool levelingFinished = screen_data.BedMeshScreen.count >= GRID_MAX_POINTS; - const float levelingProgress = sq(float(screen_data.BedMeshScreen.count) / GRID_MAX_POINTS); - if (levelingFinished) { + const bool gotAllPoints = screen_data.BedMeshScreen.count >= GRID_MAX_POINTS; + if (gotAllPoints) { drawHighlightedPointValue(); - CommandProcessor cmd; - cmd.font(Theme::font_medium) - .text(MESSAGE_POS, GET_TEXT_F(MSG_BED_MAPPING_DONE)); } - + const float levelingProgress = sq(float(screen_data.BedMeshScreen.count) / GRID_MAX_POINTS); BedMeshScreen::drawMesh(INSET_POS(MESH_POS), ExtUI::getMeshArray(), - USE_POINTS | USE_HIGHLIGHT | USE_AUTOSCALE | (levelingFinished ? USE_COLORS : 0), + USE_POINTS | USE_HIGHLIGHT | USE_AUTOSCALE | (gotAllPoints ? USE_COLORS : 0), autoscale_max_amplitude * levelingProgress ); } @@ -307,11 +308,29 @@ void BedMeshScreen::onMeshUpdate(const int8_t, const int8_t, const float) { } void BedMeshScreen::onMeshUpdate(const int8_t x, const int8_t y, const ExtUI::probe_state_t state) { - if (state == ExtUI::PROBE_FINISH) { - screen_data.BedMeshScreen.highlightedTag = pointToTag(x, y); - screen_data.BedMeshScreen.count++; + switch(state) { + case ExtUI::MESH_START: + screen_data.BedMeshScreen.count = 0; + screen_data.BedMeshScreen.showMappingDone = false; + break; + case ExtUI::MESH_FINISH: + screen_data.BedMeshScreen.count = GRID_MAX_POINTS; + screen_data.BedMeshScreen.showMappingDone = true; + break; + case ExtUI::PROBE_START: + screen_data.BedMeshScreen.highlightedTag = pointToTag(x, y); + break; + case ExtUI::PROBE_FINISH: + screen_data.BedMeshScreen.count++; + break; } BedMeshScreen::onMeshUpdate(x, y, 0); } +void BedMeshScreen::startMeshProbe() { + GOTO_SCREEN(BedMeshScreen); + screen_data.BedMeshScreen.count = 0; + injectCommands_P(PSTR(BED_LEVELING_COMMANDS)); +} + #endif // TOUCH_UI_FTDI_EVE && HAS_MESH diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_status_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_status_screen.cpp index 6d72fc92a2e4..cfae53c7245c 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_status_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_status_screen.cpp @@ -29,7 +29,9 @@ #include "../ftdi_eve_lib/extras/poly_ui.h" -#ifdef TOUCH_UI_PORTRAIT +#if ENABLED(TOUCH_UI_COCOA_PRESS) + #include "cocoa_press_ui.h" +#elif ENABLED(TOUCH_UI_PORTRAIT) #include "bio_printer_ui_portrait.h" #else #include "bio_printer_ui_landscape.h" @@ -100,7 +102,7 @@ void StatusScreen::draw_temperature(draw_mode_t what) { // heating zones, but has no bed temperature cmd.cmd(COLOR_RGB(bg_text_enabled)); - cmd.font(font_medium); + cmd.font(font_xsmall); ui.bounds(POLY(h0_label), x, y, h, v); cmd.text(x, y, h, v, GET_TEXT_F(MSG_ZONE_1)); @@ -221,7 +223,7 @@ void StatusScreen::draw_syringe(draw_mode_t what) { ui.color(syringe_rgb); ui.fill(POLY(syringe_outline)); - ui.color(fill_rgb); + ui.color(fluid_rgb); ui.bounds(POLY(syringe_fluid), x, y, h, v); cmd.cmd(SAVE_CONTEXT()); cmd.cmd(SCISSOR_XY(x,y + v * (1.0 - fill_level))); @@ -245,23 +247,25 @@ void StatusScreen::draw_arrows(draw_mode_t what) { ui.button_stroke(stroke_rgb, 28); ui.button_shadow(shadow_rgb, shadow_depth); + constexpr uint8_t style = TERN(TOUCH_UI_COCOA_PRESS, PolyUI::FILL | PolyUI::SHADOW, PolyUI::REGULAR); + if ((what & BACKGROUND) || jog_xy) { - ui.button(1, POLY(x_neg)); - ui.button(2, POLY(x_pos)); - ui.button(3, POLY(y_neg)); - ui.button(4, POLY(y_pos)); + ui.button(1, POLY(x_neg), style); + ui.button(2, POLY(x_pos), style); + ui.button(3, POLY(y_neg), style); + ui.button(4, POLY(y_pos), style); } if ((what & BACKGROUND) || z_homed) { - ui.button(5, POLY(z_neg)); - ui.button(6, POLY(z_pos)); + ui.button(5, POLY(z_neg), style); + ui.button(6, POLY(z_pos), style); } if ((what & BACKGROUND) || e_homed) { #if DISABLED(TOUCH_UI_COCOA_PRESS) - ui.button(7, POLY(e_neg)); + ui.button(7, POLY(e_neg), style); #endif - ui.button(8, POLY(e_pos)); + ui.button(8, POLY(e_pos), style); } } @@ -300,13 +304,14 @@ void StatusScreen::draw_overlay_icons(draw_mode_t what) { PolyUI ui(cmd, what); if (what & FOREGROUND) { - ui.button_fill (fill_rgb); + ui.button_fill (TERN(TOUCH_UI_COCOA_PRESS, stroke_rgb, fill_rgb); ui.button_stroke(stroke_rgb, 28); ui.button_shadow(shadow_rgb, shadow_depth); - if (!jog_xy) ui.button(12, POLY(padlock)); - if (!e_homed) ui.button(13, POLY(home_e)); - if (!z_homed) ui.button(14, POLY(home_z)); + constexpr uint8_t style = TERN(TOUCH_UI_COCOA_PRESS, PolyUI::FILL | PolyUI::SHADOW, PolyUI::REGULAR); + if (!jog_xy) ui.button(12, POLY(padlock), style); + if (!e_homed) ui.button(13, POLY(home_e), style); + if (!z_homed) ui.button(14, POLY(home_z), style); } } diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/filament_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/filament_menu.cpp index 575f75a74e9c..82ee118e4c68 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/filament_menu.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/filament_menu.cpp @@ -30,6 +30,22 @@ using namespace FTDI; using namespace ExtUI; using namespace Theme; +#ifdef TOUCH_UI_PORTRAIT + #define GRID_ROWS 9 + #define GRID_COLS 2 + #define TITLE_POS BTN_POS(1,1), BTN_SIZE(2,1) + #define RUNOUT_SENSOR_POS BTN_POS(1,2), BTN_SIZE(2,1) + #define LIN_ADVANCE_POS BTN_POS(1,3), BTN_SIZE(2,1) + #define BACK_POS BTN_POS(1,9), BTN_SIZE(2,1) +#else + #define GRID_ROWS 6 + #define GRID_COLS 2 + #define TITLE_POS BTN_POS(1,1), BTN_SIZE(2,1) + #define RUNOUT_SENSOR_POS BTN_POS(1,2), BTN_SIZE(2,1) + #define LIN_ADVANCE_POS BTN_POS(1,3), BTN_SIZE(2,1) + #define BACK_POS BTN_POS(1,6), BTN_SIZE(2,1) +#endif + void FilamentMenu::onRedraw(draw_mode_t what) { if (what & BACKGROUND) { CommandProcessor cmd; @@ -41,47 +57,14 @@ void FilamentMenu::onRedraw(draw_mode_t what) { if (what & FOREGROUND) { CommandProcessor cmd; cmd.font(font_large) - #ifdef TOUCH_UI_PORTRAIT - #define GRID_ROWS 9 - #define GRID_COLS 2 - .text ( BTN_POS(1,1), BTN_SIZE(2,1), GET_TEXT_F(MSG_FILAMENT)) - .font(font_medium).colors(normal_btn) - .enabled( - #if ENABLED(FILAMENT_RUNOUT_SENSOR) - 1 - #endif - ) - .tag(2).button( BTN_POS(1,2), BTN_SIZE(2,1), GET_TEXT_F(MSG_RUNOUT_SENSOR)) - .enabled( - #if ENABLED(LIN_ADVANCE) - 1 - #endif - ) - .tag(3).button( BTN_POS(1,3), BTN_SIZE(2,1), GET_TEXT_F(MSG_LINEAR_ADVANCE)) - .colors(action_btn) - .tag(1) .button( BTN_POS(1,9), BTN_SIZE(2,1), GET_TEXT_F(MSG_BACK)); - #undef GRID_COLS - #undef GRID_ROWS - #else - #define GRID_ROWS 6 - #define GRID_COLS 3 - .text ( BTN_POS(1,1), BTN_SIZE(3,1), GET_TEXT_F(MSG_FILAMENT)) - .font(font_medium).colors(normal_btn) - .enabled( - #if ENABLED(FILAMENT_RUNOUT_SENSOR) - 1 - #endif - ) - .tag(2).button( BTN_POS(1,2), BTN_SIZE(3,1), GET_TEXT_F(MSG_RUNOUT_SENSOR)) - .enabled( - #if ENABLED(LIN_ADVANCE) - 1 - #endif - ) - .tag(3).button( BTN_POS(1,3), BTN_SIZE(3,1), GET_TEXT_F(MSG_LINEAR_ADVANCE)) - .colors(action_btn) - .tag(1) .button( BTN_POS(1,6), BTN_SIZE(3,1), GET_TEXT_F(MSG_BACK)); - #endif + .text(TITLE_POS, GET_TEXT_F(MSG_FILAMENT)) + .font(font_medium).colors(normal_btn) + .enabled(ENABLED(FILAMENT_RUNOUT_SENSOR)) + .tag(2).button(RUNOUT_SENSOR_POS, GET_TEXT_F(MSG_RUNOUT_SENSOR)) + .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)); } } diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/files_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/files_screen.cpp index 8d6fb1860394..dd0eb263d5fa 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/files_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/files_screen.cpp @@ -22,7 +22,7 @@ #include "../config.h" -#if ENABLED(TOUCH_UI_FTDI_EVE) +#if BOTH(TOUCH_UI_FTDI_EVE, SDSUPPORT) #include "screens.h" #include "screen_data.h" diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/main_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/main_menu.cpp index dfb23daa528f..53e3ab00c736 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/main_menu.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/main_menu.cpp @@ -44,15 +44,14 @@ void MainMenu::onRedraw(draw_mode_t what) { #define ADVANCED_SETTINGS_POS BTN_POS(1,2), BTN_SIZE(2,1) #define FILAMENTCHANGE_POS BTN_POS(1,3), BTN_SIZE(2,1) #define TEMPERATURE_POS BTN_POS(1,4), BTN_SIZE(2,1) - #define MOVE_AXIS_POS BTN_POS(1,5), BTN_SIZE(1,1) - #define DISABLE_STEPPERS_POS BTN_POS(2,5), BTN_SIZE(1,1) - #define AUTO_HOME_POS BTN_POS(1,6), BTN_SIZE(1,1) - #define CLEAN_NOZZLE_POS BTN_POS(2,6), BTN_SIZE(1,1) - #define LEVEL_BED_POS BTN_POS(1,7), BTN_SIZE(1,1) - #define LEVEL_AXIS_POS BTN_POS(2,7), BTN_SIZE(1,1) + #define DISABLE_STEPPERS_POS BTN_POS(1,5), BTN_SIZE(2,1) + #define MOVE_AXIS_POS BTN_POS(1,6), BTN_SIZE(1,1) + #define LEVELING_POS BTN_POS(2,6), BTN_SIZE(1,1) + #define AUTO_HOME_POS BTN_POS(1,7), BTN_SIZE(1,1) + #define CLEAN_NOZZLE_POS BTN_POS(2,7), BTN_SIZE(1,1) #define BACK_POS BTN_POS(1,8), BTN_SIZE(2,1) #else - #define GRID_ROWS 6 + #define GRID_ROWS 5 #define GRID_COLS 2 #define ADVANCED_SETTINGS_POS BTN_POS(1,1), BTN_SIZE(1,1) #define ABOUT_PRINTER_POS BTN_POS(2,1), BTN_SIZE(1,1) @@ -62,9 +61,8 @@ void MainMenu::onRedraw(draw_mode_t what) { #define DISABLE_STEPPERS_POS BTN_POS(2,3), BTN_SIZE(1,1) #define TEMPERATURE_POS BTN_POS(1,4), BTN_SIZE(1,1) #define FILAMENTCHANGE_POS BTN_POS(2,4), BTN_SIZE(1,1) - #define LEVEL_BED_POS BTN_POS(1,5), BTN_SIZE(1,1) - #define LEVEL_AXIS_POS BTN_POS(2,5), BTN_SIZE(1,1) - #define BACK_POS BTN_POS(1,6), BTN_SIZE(2,1) + #define LEVELING_POS BTN_POS(1,5), BTN_SIZE(1,1) + #define BACK_POS BTN_POS(2,5), BTN_SIZE(1,1) #endif if (what & FOREGROUND) { @@ -100,24 +98,13 @@ void MainMenu::onRedraw(draw_mode_t what) { #endif )) .tag(8).button( ADVANCED_SETTINGS_POS, GET_TEXT_F(MSG_ADVANCED_SETTINGS)) - .enabled( - #ifdef PRINTCOUNTER - 1 - #endif - ) - .enabled( - #ifdef AXIS_LEVELING_COMMANDS - 1 - #endif - ) - .tag(9).button( LEVEL_AXIS_POS, GET_TEXT_F(MSG_AUTOLEVEL_X_AXIS)) .enabled( #ifdef HAS_LEVELING 1 #endif ) - .tag(10).button( LEVEL_BED_POS, GET_TEXT_F(MSG_LEVEL_BED)) - .tag(11).button( ABOUT_PRINTER_POS, GET_TEXT_F(MSG_INFO_MENU)) + .tag(9).button( LEVELING_POS, GET_TEXT_F(MSG_LEVELING)) + .tag(10).button( ABOUT_PRINTER_POS, GET_TEXT_F(MSG_INFO_MENU)) .colors(action_btn) .tag(1).button( BACK_POS, GET_TEXT_F(MSG_BACK)); } @@ -143,23 +130,10 @@ bool MainMenu::onTouchEnd(uint8_t tag) { case 7: GOTO_SCREEN(ChangeFilamentScreen); break; #endif case 8: GOTO_SCREEN(AdvancedSettingsMenu); break; - #ifdef AXIS_LEVELING_COMMANDS - case 9: SpinnerDialogBox::enqueueAndWait_P(F(AXIS_LEVELING_COMMANDS)); break; - #endif - #if HAS_LEVELING - case 10: - #ifndef BED_LEVELING_COMMANDS - #define BED_LEVELING_COMMANDS "G29" - #endif - #if HAS_MESH - GOTO_SCREEN(BedMeshScreen); - injectCommands_P(PSTR(BED_LEVELING_COMMANDS)); - #else - SpinnerDialogBox::enqueueAndWait_P(F(BED_LEVELING_COMMANDS)); - #endif - break; + #ifdef HAS_LEVELING + case 9: GOTO_SCREEN(LevelingMenu); break; #endif - case 11: GOTO_SCREEN(AboutScreen); break; + case 10: GOTO_SCREEN(AboutScreen); break; default: return false; } diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screen_data.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screen_data.h index 207277b824be..39e9ce4bc568 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screen_data.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screen_data.h @@ -62,6 +62,7 @@ union screen_data_t { } MoveAxisScreen; #if HAS_MESH struct { + bool showMappingDone; uint8_t count; uint8_t highlightedTag; } BedMeshScreen; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.cpp index 01438aeb947f..16aa68216842 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.cpp @@ -55,9 +55,6 @@ SCREEN_TABLE { #endif #if ENABLED(BABYSTEPPING) DECL_SCREEN(NudgeNozzleScreen), -#endif -#if HAS_MESH - DECL_SCREEN(BedMeshScreen), #endif DECL_SCREEN(MoveAxisScreen), DECL_SCREEN(StepsScreen), @@ -65,8 +62,14 @@ SCREEN_TABLE { DECL_SCREEN(StepperCurrentScreen), DECL_SCREEN(StepperBumpSensitivityScreen), #endif -#if HAS_BED_PROBE - DECL_SCREEN(ZOffsetScreen), +#if HAS_LEVELING + DECL_SCREEN(LevelingMenu), + #if HAS_BED_PROBE + DECL_SCREEN(ZOffsetScreen), + #endif + #if HAS_MESH + DECL_SCREEN(BedMeshScreen), + #endif #endif #if HAS_MULTI_HOTEND DECL_SCREEN(NozzleOffsetScreen), @@ -100,7 +103,9 @@ SCREEN_TABLE { DECL_SCREEN(InterfaceSettingsScreen), DECL_SCREEN(InterfaceSoundsScreen), DECL_SCREEN(LockScreen), +#if ENABLED(SDSUPPORT) DECL_SCREEN(FilesScreen), +#endif DECL_SCREEN(EndstopStatesScreen), #if ENABLED(TOUCH_UI_LULZBOT_BIO) DECL_SCREEN(BioPrintingDialogBox), diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h index ae48f752406e..ec8df2760789 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h @@ -39,24 +39,37 @@ enum { STATUS_SCREEN_CACHE, MENU_SCREEN_CACHE, TUNE_SCREEN_CACHE, - ADJUST_OFFSETS_SCREEN_CACHE, ALERT_BOX_CACHE, SPINNER_CACHE, ADVANCED_SETTINGS_SCREEN_CACHE, MOVE_AXIS_SCREEN_CACHE, TEMPERATURE_SCREEN_CACHE, STEPS_SCREEN_CACHE, - STEPPER_CURRENT_SCREEN_CACHE, - STEPPER_BUMP_SENSITIVITY_SCREEN_CACHE, - ZOFFSET_SCREEN_CACHE, - NOZZLE_OFFSET_SCREEN_CACHE, - BACKLASH_COMPENSATION_SCREEN_CACHE, MAX_FEEDRATE_SCREEN_CACHE, MAX_VELOCITY_SCREEN_CACHE, MAX_ACCELERATION_SCREEN_CACHE, DEFAULT_ACCELERATION_SCREEN_CACHE, -#if HAS_MESH - BED_MESH_SCREEN_CACHE, +#if HAS_LEVELING + LEVELING_SCREEN_CACHE, + #if HAS_BED_PROBE + ZOFFSET_SCREEN_CACHE, + #endif + #if HAS_MESH + BED_MESH_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, @@ -81,12 +94,14 @@ enum { #if ENABLED(TOUCH_UI_COCOA_PRESS) PREHEAT_MENU_CACHE, PREHEAT_TIMER_SCREEN_CACHE, +#endif +#if ENABLED(SDSUPPORT) + FILES_SCREEN_CACHE, #endif CHANGE_FILAMENT_SCREEN_CACHE, INTERFACE_SETTINGS_SCREEN_CACHE, INTERFACE_SOUNDS_SCREEN_CACHE, LOCK_SCREEN_CACHE, - FILES_SCREEN_CACHE, DISPLAY_TIMINGS_SCREEN_CACHE }; @@ -133,33 +148,6 @@ class AboutScreen : public BaseScreen, public UncachedScreen { static bool onTouchEnd(uint8_t tag); }; -#if HAS_MESH -class BedMeshScreen : public BaseScreen, public CachedScreen { - private: - enum MeshOpts { - USE_POINTS = 0x01, - USE_COLORS = 0x02, - USE_TAGS = 0x04, - USE_HIGHLIGHT = 0x08, - USE_AUTOSCALE = 0x10 - }; - - static uint8_t pointToTag(uint8_t x, uint8_t y); - static bool tagToPoint(uint8_t tag, uint8_t &x, uint8_t &y); - static float getHightlightedValue(); - static void drawHighlightedPointValue(); - static void drawMesh(int16_t x, int16_t y, int16_t w, int16_t h, ExtUI::bed_mesh_t data, uint8_t opts, float autoscale_max = 0.1); - - public: - static void onMeshUpdate(const int8_t x, const int8_t y, const float val); - static void onMeshUpdate(const int8_t x, const int8_t y, const ExtUI::probe_state_t); - static void onEntry(); - static void onRedraw(draw_mode_t); - static bool onTouchStart(uint8_t tag); - static bool onTouchEnd(uint8_t tag); -}; -#endif - #if ENABLED(PRINTCOUNTER) class StatisticsScreen : public BaseScreen, public UncachedScreen { public: @@ -505,21 +493,58 @@ class StepsScreen : public BaseNumericAdjustmentScreen, public CachedScreen { +#if HAS_MULTI_HOTEND + class NozzleOffsetScreen : public BaseNumericAdjustmentScreen, public CachedScreen { public: + static void onEntry(); static void onRedraw(draw_mode_t); static bool onTouchHeld(uint8_t tag); }; #endif -#if HAS_MULTI_HOTEND - class NozzleOffsetScreen : public BaseNumericAdjustmentScreen, public CachedScreen { +#if HAS_LEVELING + class LevelingMenu : public BaseScreen, public CachedScreen { + public: + static void onRedraw(draw_mode_t); + static bool onTouchEnd(uint8_t tag); + }; + + #if HAS_BED_PROBE + class ZOffsetScreen : public BaseNumericAdjustmentScreen, public CachedScreen { + public: + static void onRedraw(draw_mode_t); + static bool onTouchHeld(uint8_t tag); + }; + #endif + + #if HAS_MESH + class BedMeshScreen : public BaseScreen, public CachedScreen { + private: + enum MeshOpts { + USE_POINTS = 0x01, + USE_COLORS = 0x02, + USE_TAGS = 0x04, + USE_HIGHLIGHT = 0x08, + USE_AUTOSCALE = 0x10 + }; + + static uint8_t pointToTag(uint8_t x, uint8_t y); + static bool tagToPoint(uint8_t tag, uint8_t &x, uint8_t &y); + static float getHightlightedValue(); + static void drawHighlightedPointValue(); + static void drawMesh(int16_t x, int16_t y, int16_t w, int16_t h, ExtUI::bed_mesh_t data, uint8_t opts, float autoscale_max = 0.1); + public: + static void onMeshUpdate(const int8_t x, const int8_t y, const float val); + static void onMeshUpdate(const int8_t x, const int8_t y, const ExtUI::probe_state_t); static void onEntry(); static void onRedraw(draw_mode_t); - static bool onTouchHeld(uint8_t tag); + static bool onTouchStart(uint8_t tag); + static bool onTouchEnd(uint8_t tag); + + static void startMeshProbe(); }; + #endif #endif #if ENABLED(BABYSTEPPING) @@ -707,40 +732,42 @@ class LockScreen : public BaseScreen, public CachedScreen { static bool onTouchEnd(uint8_t tag); }; -class FilesScreen : public BaseScreen, public CachedScreen { - private: - #ifdef 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); - static uint16_t getSelectedFileIndex(); - - inline static const char *getSelectedShortFilename() {return getSelectedFilename(false);} - inline static const char *getSelectedLongFilename() {return getSelectedFilename(true);} - static const char *getSelectedFilename(bool longName); - - static void drawFileButton(const char* filename, uint8_t tag, bool is_dir, bool is_highlighted); - static void drawFileList(); - static void drawHeader(); - static void drawFooter(); - static void drawSelectedFile(); - - static void gotoPage(uint8_t); - public: - static void onEntry(); - static void onRedraw(draw_mode_t); - static bool onTouchEnd(uint8_t tag); - static void onIdle(); -}; +#if ENABLED(SDSUPPORT) + class FilesScreen : public BaseScreen, public CachedScreen { + private: + #ifdef 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); + static uint16_t getSelectedFileIndex(); + + inline static const char *getSelectedShortFilename() {return getSelectedFilename(false);} + inline static const char *getSelectedLongFilename() {return getSelectedFilename(true);} + static const char *getSelectedFilename(bool longName); + + static void drawFileButton(const char* filename, uint8_t tag, bool is_dir, bool is_highlighted); + static void drawFileList(); + static void drawHeader(); + static void drawFooter(); + static void drawSelectedFile(); + + static void gotoPage(uint8_t); + public: + static void onEntry(); + static void onRedraw(draw_mode_t); + static bool onTouchEnd(uint8_t tag); + static void onIdle(); + }; +#endif class EndstopStatesScreen : public BaseScreen, public UncachedScreen { public: diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/colors.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/colors.h index f99c0fd3ebcd..84639b59e12c 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/colors.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/colors.h @@ -124,7 +124,13 @@ namespace Theme { constexpr uint32_t shadow_rgb = gray_color_6; constexpr uint32_t stroke_rgb = accent_color_1; constexpr uint32_t fill_rgb = accent_color_3; - constexpr uint32_t syringe_rgb = accent_color_5; + #if ENABLED(TOUCH_UI_COCOA_PRESS) + constexpr uint32_t syringe_rgb = 0xFFFFFF; + constexpr uint32_t fluid_rgb = accent_color_5; + #else + constexpr uint32_t syringe_rgb = accent_color_5; + constexpr uint32_t fluid_rgb = accent_color_3; + #endif #if ENABLED(TOUCH_UI_ROYAL_THEME) constexpr uint32_t x_axis = hsl_to_rgb(0, 1.00, 0.26); diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index c40a86942100..c2eab2ba0604 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -544,11 +544,13 @@ namespace ExtUI { void setAxisSteps_per_mm(const float value, const axis_t axis) { planner.settings.axis_steps_per_mm[axis] = value; + planner.refresh_positioning(); } void setAxisSteps_per_mm(const float value, const extruder_t extruder) { UNUSED_E(extruder); planner.settings.axis_steps_per_mm[E_AXIS_N(extruder - E0)] = value; + planner.refresh_positioning(); } feedRate_t getAxisMaxFeedrate_mm_s(const axis_t axis) { @@ -580,11 +582,13 @@ namespace ExtUI { void setAxisMaxAcceleration_mm_s2(const float value, const axis_t axis) { planner.set_max_acceleration(axis, value); + planner.reset_acceleration_rates(); } void setAxisMaxAcceleration_mm_s2(const float value, const extruder_t extruder) { UNUSED_E(extruder); planner.set_max_acceleration(E_AXIS_N(extruder - E0), value); + planner.reset_acceleration_rates(); } #if HAS_FILAMENT_SENSOR diff --git a/Marlin/src/lcd/extui/ui_api.h b/Marlin/src/lcd/extui/ui_api.h index ca12d79a8bc9..02c4717d77f4 100644 --- a/Marlin/src/lcd/extui/ui_api.h +++ b/Marlin/src/lcd/extui/ui_api.h @@ -143,7 +143,12 @@ namespace ExtUI { void onMeshUpdate(const int8_t xpos, const int8_t ypos, const float zval); inline void onMeshUpdate(const xy_int8_t &pos, const float zval) { onMeshUpdate(pos.x, pos.y, zval); } - typedef enum : unsigned char { PROBE_START, PROBE_FINISH } probe_state_t; + typedef enum : unsigned char { + MESH_START, // Prior to start of probe + MESH_FINISH, // Following probe of all points + PROBE_START, // Beginning probe of grid location + PROBE_FINISH // Finished probe of grid location + } probe_state_t; void onMeshUpdate(const int8_t xpos, const int8_t ypos, probe_state_t state); inline void onMeshUpdate(const xy_int8_t &pos, probe_state_t state) { onMeshUpdate(pos.x, pos.y, state); } #endif From d93471fdad8ebabc460a7eb697c3ac61ea2617eb Mon Sep 17 00:00:00 2001 From: mmajoor Date: Sun, 13 Sep 2020 06:33:55 +0200 Subject: [PATCH 07/44] Allow SWD debug on Robin Nano (#19345) --- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h index d66338b8ad32..c3e8be74e8c2 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h @@ -25,7 +25,7 @@ * MKS Robin nano (STM32F130VET6) board pin assignments */ -#ifndef __STM32F1__ +#if !defined(STM32F1) && !defined(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." @@ -36,7 +36,7 @@ // // Release PB4 (Y_ENABLE_PIN) from JTAG NRST role // -#define DISABLE_DEBUG +#define DISABLE_JTAG // // EEPROM From 49ca16c3fb103e8e29f64107ba664aa82917b9f1 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 13 Sep 2020 18:06:14 -0500 Subject: [PATCH 08/44] heater_ind_t => heater_id_t --- Marlin/src/gcode/temp/M303.cpp | 2 +- Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp | 14 ++-- Marlin/src/lcd/dogm/status_screen_DOGM.cpp | 24 +++---- Marlin/src/lcd/extui/ui_api.cpp | 2 +- Marlin/src/module/temperature.cpp | 72 ++++++++++----------- Marlin/src/module/temperature.h | 14 ++-- 6 files changed, 64 insertions(+), 64 deletions(-) diff --git a/Marlin/src/gcode/temp/M303.cpp b/Marlin/src/gcode/temp/M303.cpp index 3340e4fa49a1..ccce09b4f1ee 100644 --- a/Marlin/src/gcode/temp/M303.cpp +++ b/Marlin/src/gcode/temp/M303.cpp @@ -62,7 +62,7 @@ void GcodeSuite::M303() { #define SI TERN(PIDTEMPBED, H_BED, H_E0) #define EI TERN(PIDTEMP, HOTENDS - 1, H_BED) - const heater_ind_t e = (heater_ind_t)parser.intval('E'); + const heater_id_t e = (heater_id_t)parser.intval('E'); if (!WITHIN(e, SI, EI)) { SERIAL_ECHOLNPGM(STR_PID_BAD_EXTRUDER_NUM); TERN_(EXTENSIBLE_UI, ExtUI::onPidTuning(ExtUI::result_t::PID_BAD_EXTRUDER_NUM)); diff --git a/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp b/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp index 22dd63f68cb0..81ba4653a1a8 100644 --- a/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp +++ b/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp @@ -519,13 +519,13 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const } } -FORCE_INLINE void _draw_heater_status(const heater_ind_t heater, const char prefix, const bool blink) { +FORCE_INLINE void _draw_heater_status(const heater_id_t heater_id, const char prefix, const bool blink) { #if HAS_HEATED_BED - const bool isBed = heater < 0; - const float t1 = (isBed ? thermalManager.degBed() : thermalManager.degHotend(heater)), - t2 = (isBed ? thermalManager.degTargetBed() : thermalManager.degTargetHotend(heater)); + const bool isBed = heater_id < 0; + const float t1 = (isBed ? thermalManager.degBed() : thermalManager.degHotend(heater_id)), + t2 = (isBed ? thermalManager.degTargetBed() : thermalManager.degTargetHotend(heater_id)); #else - const float t1 = thermalManager.degHotend(heater), t2 = thermalManager.degTargetHotend(heater); + const float t1 = thermalManager.degHotend(heater_id), t2 = thermalManager.degTargetHotend(heater_id); #endif if (prefix >= 0) lcd_put_wchar(prefix); @@ -540,7 +540,7 @@ FORCE_INLINE void _draw_heater_status(const heater_ind_t heater, const char pref #if HAS_HEATED_BED isBed ? thermalManager.bed_idle.timed_out : #endif - thermalManager.hotend_idle[heater].timed_out + thermalManager.hotend_idle[heater_id].timed_out ); if (!blink && is_idle) { @@ -990,7 +990,7 @@ void MarlinUI::draw_status_screen() { void MarlinUI::draw_hotend_status(const uint8_t row, const uint8_t extruder) { if (row < LCD_HEIGHT) { lcd_moveto(LCD_WIDTH - 9, row); - _draw_heater_status((heater_ind_t)extruder, LCD_STR_THERMOMETER[0], get_blink()); + _draw_heater_status((heater_id_t)extruder, LCD_STR_THERMOMETER[0], get_blink()); } } diff --git a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp index bdd9f25703ec..f668e453cca8 100644 --- a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp +++ b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp @@ -178,17 +178,17 @@ FORCE_INLINE void _draw_centered_temp(const int16_t temp, const uint8_t tx, cons #if DO_DRAW_HOTENDS // Draw hotend bitmap with current and target temperatures - FORCE_INLINE void _draw_hotend_status(const heater_ind_t heater, const bool blink) { + FORCE_INLINE void _draw_hotend_status(const heater_id_t heater_id, const bool blink) { #if !HEATER_IDLE_HANDLER UNUSED(blink); #endif - const bool isHeat = HOTEND_ALT(heater); + const bool isHeat = HOTEND_ALT(heater_id); - const uint8_t tx = STATUS_HOTEND_TEXT_X(heater); + const uint8_t tx = STATUS_HOTEND_TEXT_X(heater_id); - const float temp = thermalManager.degHotend(heater), - target = thermalManager.degTargetHotend(heater); + const float temp = thermalManager.degHotend(heater_id), + target = thermalManager.degTargetHotend(heater_id); #if DISABLED(STATUS_HOTEND_ANIM) #define STATIC_HOTEND true @@ -237,24 +237,24 @@ FORCE_INLINE void _draw_centered_temp(const int16_t temp, const uint8_t tx, cons #if ANIM_HOTEND // Draw hotend bitmap, either whole or split by the heating percent - const uint8_t hx = STATUS_HOTEND_X(heater), - bw = STATUS_HOTEND_BYTEWIDTH(heater); + 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(heater, false)); - u8g.drawBitmapP(hx, STATUS_HEATERS_Y + ph, bw, tall + 1, HOTEND_BITMAP(heater, true) + ph * bw); + 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); } else #endif - u8g.drawBitmapP(hx, STATUS_HEATERS_Y, bw, STATUS_HEATERS_HEIGHT, HOTEND_BITMAP(heater, isHeat)); + u8g.drawBitmapP(hx, STATUS_HEATERS_Y, bw, STATUS_HEATERS_HEIGHT, HOTEND_BITMAP(heater_id, isHeat)); #endif } // PAGE_CONTAINS if (PAGE_UNDER(7)) { #if HEATER_IDLE_HANDLER - const bool dodraw = (blink || !thermalManager.hotend_idle[heater].timed_out); + const bool dodraw = (blink || !thermalManager.hotend_idle[heater_id].timed_out); #else constexpr bool dodraw = true; #endif @@ -597,7 +597,7 @@ void MarlinUI::draw_status_screen() { // Extruders #if DO_DRAW_HOTENDS LOOP_L_N(e, MAX_HOTEND_DRAW) - _draw_hotend_status((heater_ind_t)e, blink); + _draw_hotend_status((heater_id_t)e, blink); #endif // Laser / Spindle diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index c2eab2ba0604..53b7dc6279c6 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -868,7 +868,7 @@ namespace ExtUI { } void startPIDTune(const float temp, extruder_t tool) { - thermalManager.PID_autotune(temp, (heater_ind_t)tool, 8, true); + thermalManager.PID_autotune(temp, (heater_id_t)tool, 8, true); } #endif diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index fbdd1fd6ec5f..06864c6b97b4 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -377,7 +377,7 @@ volatile bool Temperature::raw_temps_ready = false; * Needs sufficient heater power to make some overshoot at target * temperature to succeed. */ - void Temperature::PID_autotune(const float &target, const heater_ind_t heater, const int8_t ncycles, const bool set_result/*=false*/) { + void Temperature::PID_autotune(const float &target, const heater_id_t heater_id, const int8_t ncycles, const bool set_result/*=false*/) { float current_temp = 0.0; int cycles = 0; bool heating = true; @@ -389,11 +389,11 @@ volatile bool Temperature::raw_temps_ready = false; PID_t tune_pid = { 0, 0, 0 }; float maxT = 0, minT = 10000; - const bool isbed = (heater == H_BED); + const bool isbed = (heater_id == H_BED); #if HAS_PID_FOR_BOTH #define GHV(B,H) (isbed ? (B) : (H)) - #define SHV(B,H) do{ if (isbed) temp_bed.soft_pwm_amount = B; else temp_hotend[heater].soft_pwm_amount = H; }while(0) + #define SHV(B,H) do{ if (isbed) temp_bed.soft_pwm_amount = B; else temp_hotend[heater_id].soft_pwm_amount = H; }while(0) #define ONHEATINGSTART() (isbed ? printerEventLEDs.onBedHeatingStart() : printerEventLEDs.onHotendHeatingStart()) #define ONHEATING(S,C,T) (isbed ? printerEventLEDs.onBedHeating(S,C,T) : printerEventLEDs.onHotendHeating(S,C,T)) #elif ENABLED(PIDTEMPBED) @@ -403,7 +403,7 @@ volatile bool Temperature::raw_temps_ready = false; #define ONHEATING(S,C,T) printerEventLEDs.onBedHeating(S,C,T) #else #define GHV(B,H) H - #define SHV(B,H) (temp_hotend[heater].soft_pwm_amount = H) + #define SHV(B,H) (temp_hotend[heater_id].soft_pwm_amount = H) #define ONHEATINGSTART() printerEventLEDs.onHotendHeatingStart() #define ONHEATING(S,C,T) printerEventLEDs.onHotendHeating(S,C,T) #endif @@ -427,7 +427,7 @@ volatile bool Temperature::raw_temps_ready = false; TERN_(HAS_AUTO_FAN, next_auto_fan_check_ms = next_temp_ms + 2500UL); - if (target > GHV(BED_MAX_TARGET, temp_range[heater].maxtemp - HOTEND_OVERSHOOT)) { + if (target > GHV(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)); return; @@ -441,7 +441,7 @@ volatile bool Temperature::raw_temps_ready = false; SHV(bias = d = (MAX_BED_POWER) >> 1, bias = d = (PID_MAX) >> 1); #if ENABLED(PRINTER_EVENT_LEDS) - const float start_temp = GHV(temp_bed.celsius, temp_hotend[heater].celsius); + const float start_temp = GHV(temp_bed.celsius, temp_hotend[heater_id].celsius); LEDColor color = ONHEATINGSTART(); #endif @@ -457,7 +457,7 @@ volatile bool Temperature::raw_temps_ready = false; updateTemperaturesFromRawValues(); // Get the current temperature and constrain it - current_temp = GHV(temp_bed.celsius, temp_hotend[heater].celsius); + current_temp = GHV(temp_bed.celsius, temp_hotend[heater_id].celsius); NOLESS(maxT, current_temp); NOMORE(minT, current_temp); @@ -549,7 +549,7 @@ volatile bool Temperature::raw_temps_ready = false; // Report heater states every 2 seconds if (ELAPSED(ms, next_temp_ms)) { #if HAS_TEMP_SENSOR - print_heater_states(isbed ? active_extruder : heater); + print_heater_states(isbed ? active_extruder : heater_id); SERIAL_EOL(); #endif next_temp_ms = ms + 2000UL; @@ -564,10 +564,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, str_t_heating_failed, GET_TEXT(MSG_HEATING_FAILED_LCD)); + _temp_error(heater_id, str_t_heating_failed, GET_TEXT(MSG_HEATING_FAILED_LCD)); } else if (current_temp < target - (MAX_OVERSHOOT_PID_AUTOTUNE)) // Heated, then temperature fell too far? - _temp_error(heater, str_t_thermal_runaway, GET_TEXT(MSG_THERMAL_RUNAWAY)); + _temp_error(heater_id, str_t_thermal_runaway, GET_TEXT(MSG_THERMAL_RUNAWAY)); } #endif } // every 2 seconds @@ -608,9 +608,9 @@ volatile bool Temperature::raw_temps_ready = false; }while(0) #define _SET_EXTRUDER_PID() do { \ - PID_PARAM(Kp, heater) = tune_pid.Kp; \ - PID_PARAM(Ki, heater) = scalePID_i(tune_pid.Ki); \ - PID_PARAM(Kd, heater) = scalePID_d(tune_pid.Kd); \ + PID_PARAM(Kp, heater_id) = tune_pid.Kp; \ + PID_PARAM(Ki, heater_id) = scalePID_i(tune_pid.Ki); \ + PID_PARAM(Kd, heater_id) = scalePID_d(tune_pid.Kd); \ updatePID(); }while(0) // Use the result? (As with "M303 U1") @@ -651,7 +651,7 @@ volatile bool Temperature::raw_temps_ready = false; * Class and Instance Methods */ -int16_t Temperature::getHeaterPower(const heater_ind_t heater_id) { +int16_t Temperature::getHeaterPower(const heater_id_t heater_id) { switch (heater_id) { #if HAS_HEATED_BED case H_BED: return temp_bed.soft_pwm_amount; @@ -758,7 +758,7 @@ int16_t Temperature::getHeaterPower(const heater_ind_t heater_id) { // Temperature Error Handlers // -inline void loud_kill(PGM_P const lcd_msg, const heater_ind_t heater) { +inline void loud_kill(PGM_P const lcd_msg, const heater_id_t heater_id) { marlin_state = MF_KILLED; #if USE_BEEPER for (uint8_t i = 20; i--;) { @@ -767,10 +767,10 @@ inline void loud_kill(PGM_P const lcd_msg, const heater_ind_t heater) { } WRITE(BEEPER_PIN, HIGH); #endif - kill(lcd_msg, HEATER_PSTR(heater)); + kill(lcd_msg, HEATER_PSTR(heater_id)); } -void Temperature::_temp_error(const heater_ind_t heater, PGM_P const serial_msg, PGM_P const lcd_msg) { +void Temperature::_temp_error(const heater_id_t heater_id, PGM_P const serial_msg, PGM_P const lcd_msg) { static uint8_t killed = 0; @@ -778,9 +778,9 @@ void Temperature::_temp_error(const heater_ind_t heater, PGM_P const serial_msg, SERIAL_ERROR_START(); serialprintPGM(serial_msg); SERIAL_ECHOPGM(STR_STOPPED_HEATER); - if (heater >= 0) - SERIAL_ECHO((int)heater); - else if (TERN0(HAS_HEATED_CHAMBER, heater == H_CHAMBER)) + if (heater_id >= 0) + SERIAL_ECHO((int)heater_id); + else if (TERN0(HAS_HEATED_CHAMBER, heater_id == H_CHAMBER)) SERIAL_ECHOPGM(STR_HEATER_CHAMBER); else SERIAL_ECHOPGM(STR_HEATER_BED); @@ -801,25 +801,25 @@ void Temperature::_temp_error(const heater_ind_t heater, PGM_P const serial_msg, if (ELAPSED(ms, expire_ms)) ++killed; break; case 2: - loud_kill(lcd_msg, heater); + loud_kill(lcd_msg, heater_id); ++killed; break; } #elif defined(BOGUS_TEMPERATURE_GRACE_PERIOD) UNUSED(killed); #else - if (!killed) { killed = 1; loud_kill(lcd_msg, heater); } + if (!killed) { killed = 1; loud_kill(lcd_msg, heater_id); } #endif } -void Temperature::max_temp_error(const heater_ind_t heater) { +void Temperature::max_temp_error(const heater_id_t heater_id) { TERN_(DWIN_CREALITY_LCD, Popup_Window_Temperature(1)); - _temp_error(heater, PSTR(STR_T_MAXTEMP), GET_TEXT(MSG_ERR_MAXTEMP)); + _temp_error(heater_id, PSTR(STR_T_MAXTEMP), GET_TEXT(MSG_ERR_MAXTEMP)); } -void Temperature::min_temp_error(const heater_ind_t heater) { +void Temperature::min_temp_error(const heater_id_t heater_id) { TERN_(DWIN_CREALITY_LCD, Popup_Window_Temperature(0)); - _temp_error(heater, PSTR(STR_T_MINTEMP), GET_TEXT(MSG_ERR_MINTEMP)); + _temp_error(heater_id, PSTR(STR_T_MINTEMP), GET_TEXT(MSG_ERR_MINTEMP)); } #if HAS_HOTEND @@ -1041,14 +1041,14 @@ void Temperature::manage_heater() { HOTEND_LOOP() { #if ENABLED(THERMAL_PROTECTION_HOTENDS) if (degHotend(e) > temp_range[e].maxtemp) - _temp_error((heater_ind_t)e, str_t_thermal_runaway, GET_TEXT(MSG_THERMAL_RUNAWAY)); + _temp_error((heater_id_t)e, str_t_thermal_runaway, GET_TEXT(MSG_THERMAL_RUNAWAY)); #endif TERN_(HEATER_IDLE_HANDLER, hotend_idle[e].update(ms)); #if ENABLED(THERMAL_PROTECTION_HOTENDS) // Check for thermal runaway - thermal_runaway_protection(tr_state_machine[e], temp_hotend[e].celsius, temp_hotend[e].target, (heater_ind_t)e, THERMAL_PROTECTION_PERIOD, THERMAL_PROTECTION_HYSTERESIS); + thermal_runaway_protection(tr_state_machine[e], temp_hotend[e].celsius, temp_hotend[e].target, (heater_id_t)e, THERMAL_PROTECTION_PERIOD, THERMAL_PROTECTION_HYSTERESIS); #endif temp_hotend[e].soft_pwm_amount = (temp_hotend[e].celsius > temp_range[e].mintemp || is_preheating(e)) && temp_hotend[e].celsius < temp_range[e].maxtemp ? (int)get_pid_output_hotend(e) >> 1 : 0; @@ -1058,7 +1058,7 @@ void Temperature::manage_heater() { 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? TERN_(DWIN_CREALITY_LCD, Popup_Window_Temperature(0)); - _temp_error((heater_ind_t)e, str_t_heating_failed, GET_TEXT(MSG_HEATING_FAILED_LCD)); + _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); @@ -1945,7 +1945,7 @@ void Temperature::init() { Temperature::tr_state_machine_t Temperature::tr_state_machine_chamber; // = { TRInactive, 0 }; #endif - void Temperature::thermal_runaway_protection(Temperature::tr_state_machine_t &sm, const float ¤t, const float &target, const heater_ind_t heater_id, const uint16_t period_seconds, const uint16_t hysteresis_degc) { + void Temperature::thermal_runaway_protection(Temperature::tr_state_machine_t &sm, const float ¤t, const float &target, const heater_id_t heater_id, const uint16_t period_seconds, const uint16_t hysteresis_degc) { static float tr_target_temperature[HOTENDS + 1] = { 0.0 }; @@ -2311,12 +2311,12 @@ void Temperature::readings_ready() { 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_ind_t)e); + if (rawtemp > temp_range[e].raw_max * tdir) max_temp_error((heater_id_t)e); if (heater_on && rawtemp < temp_range[e].raw_min * tdir && !is_preheating(e)) { #ifdef MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED if (++consecutive_low_temperature_error[e] >= MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED) #endif - min_temp_error((heater_ind_t)e); + min_temp_error((heater_id_t)e); } #ifdef MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED else @@ -2883,7 +2883,7 @@ void Temperature::tick() { #if ENABLED(SHOW_TEMP_ADC_VALUES) , const float r #endif - , const heater_ind_t e=INDEX_NONE + , const heater_id_t e=INDEX_NONE ) { char k; switch (e) { @@ -2974,10 +2974,10 @@ void Temperature::tick() { #if ENABLED(SHOW_TEMP_ADC_VALUES) , rawHotendTemp(e) #endif - , (heater_ind_t)e + , (heater_id_t)e ); #endif - SERIAL_ECHOPAIR(" @:", getHeaterPower((heater_ind_t)target_extruder)); + SERIAL_ECHOPAIR(" @:", getHeaterPower((heater_id_t)target_extruder)); #if HAS_HEATED_BED SERIAL_ECHOPAIR(" B@:", getHeaterPower(H_BED)); #endif @@ -2988,7 +2988,7 @@ void Temperature::tick() { HOTEND_LOOP() { SERIAL_ECHOPAIR(" @", e); SERIAL_CHAR(':'); - SERIAL_ECHO(getHeaterPower((heater_ind_t)e)); + SERIAL_ECHO(getHeaterPower((heater_id_t)e)); } #endif } diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index 2148f4cb68ed..37d1140f5e18 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -45,7 +45,7 @@ typedef enum : int8_t { INDEX_NONE = -5, 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_ind_t; +} heater_id_t; // PID storage typedef struct { float Kp, Ki, Kd; } PID_t; @@ -701,7 +701,7 @@ class Temperature { /** * The software PWM power for a heater */ - static int16_t getHeaterPower(const heater_ind_t heater); + static int16_t getHeaterPower(const heater_id_t heater_id); /** * Switch off all heaters, set all target temperatures to 0 @@ -720,7 +720,7 @@ class Temperature { * Perform auto-tuning for hotend or bed in response to M303 */ #if HAS_PID_HEATING - static void PID_autotune(const float &target, const heater_ind_t hotend, const int8_t ncycles, const bool set_result=false); + static void PID_autotune(const float &target, const heater_id_t heater_id, const int8_t ncycles, const bool set_result=false); #if ENABLED(NO_FAN_SLOWING_IN_PID_TUNING) static bool adaptive_fan_slowing; @@ -811,9 +811,9 @@ class Temperature { TERN_(HAS_HEATED_CHAMBER, static float get_pid_output_chamber()); - static void _temp_error(const heater_ind_t e, PGM_P const serial_msg, PGM_P const lcd_msg); - static void min_temp_error(const heater_ind_t e); - static void max_temp_error(const heater_ind_t e); + static void _temp_error(const heater_id_t e, PGM_P const serial_msg, PGM_P const lcd_msg); + static void min_temp_error(const heater_id_t e); + static void max_temp_error(const heater_id_t e); #define HAS_THERMAL_PROTECTION (EITHER(THERMAL_PROTECTION_HOTENDS, THERMAL_PROTECTION_CHAMBER) || HAS_THERMALLY_PROTECTED_BED) @@ -830,7 +830,7 @@ class Temperature { TERN_(HAS_THERMALLY_PROTECTED_BED, static tr_state_machine_t tr_state_machine_bed); TERN_(THERMAL_PROTECTION_CHAMBER, static tr_state_machine_t tr_state_machine_chamber); - static void thermal_runaway_protection(tr_state_machine_t &state, const float ¤t, const float &target, const heater_ind_t heater_id, const uint16_t period_seconds, const uint16_t hysteresis_degc); + static void thermal_runaway_protection(tr_state_machine_t &state, const float ¤t, const float &target, const heater_id_t heater_id, const uint16_t period_seconds, const uint16_t hysteresis_degc); #endif // HAS_THERMAL_PROTECTION }; From cf8316bfbb1c5fea897345d75ddf9de473688d84 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 14 Sep 2020 00:13:25 +0000 Subject: [PATCH 09/44] [cron] Bump distribution date (2020-09-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 0b7879fd95e9..faf816554c9e 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-09-13" + #define STRING_DISTRIBUTION_DATE "2020-09-14" #endif /** From 979876e958e73e642b51eb655461c92947fe1deb Mon Sep 17 00:00:00 2001 From: ellensp Date: Mon, 14 Sep 2020 16:58:39 +1200 Subject: [PATCH 10/44] Improve temperature runaway, idle timeout (#19339) Co-authored-by: Scott Lahteine --- Marlin/src/feature/pause.cpp | 8 +- Marlin/src/inc/Conditionals_adv.h | 9 ++ Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp | 28 +---- Marlin/src/lcd/dogm/status_screen_DOGM.cpp | 4 +- Marlin/src/lcd/dogm/ultralcd_DOGM.cpp | 2 +- Marlin/src/lcd/extui/ui_api.cpp | 6 +- Marlin/src/lcd/language/language_cz.h | 4 - Marlin/src/lcd/language/language_da.h | 2 - Marlin/src/lcd/language/language_de.h | 4 - Marlin/src/lcd/language/language_el.h | 2 - Marlin/src/lcd/language/language_el_gr.h | 2 - Marlin/src/lcd/language/language_en.h | 4 - Marlin/src/lcd/language/language_es.h | 4 - Marlin/src/lcd/language/language_eu.h | 2 - Marlin/src/lcd/language/language_gl.h | 4 - Marlin/src/lcd/language/language_hu.h | 4 - Marlin/src/lcd/language/language_it.h | 4 - Marlin/src/lcd/language/language_jp_kana.h | 2 - Marlin/src/lcd/language/language_nl.h | 2 - Marlin/src/lcd/language/language_pl.h | 4 - Marlin/src/lcd/language/language_pt.h | 2 - Marlin/src/lcd/language/language_pt_br.h | 4 - Marlin/src/lcd/language/language_ro.h | 4 - Marlin/src/lcd/language/language_ru.h | 4 - Marlin/src/lcd/language/language_sk.h | 4 - Marlin/src/lcd/language/language_tr.h | 4 - Marlin/src/lcd/language/language_uk.h | 4 - Marlin/src/lcd/language/language_vi.h | 2 - Marlin/src/lcd/language/language_zh_CN.h | 4 - Marlin/src/lcd/language/language_zh_TW.h | 4 - Marlin/src/lcd/menu/menu.cpp | 4 - Marlin/src/module/temperature.cpp | 125 ++++++++++---------- Marlin/src/module/temperature.h | 88 ++++++++++---- 33 files changed, 153 insertions(+), 201 deletions(-) diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index efc6510756ee..f8a7d83260e2 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -484,7 +484,7 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep // Start the heater idle timers const millis_t nozzle_timeout = SEC_TO_MS(PAUSE_PARK_NOZZLE_TIMEOUT); - HOTEND_LOOP() thermalManager.hotend_idle[e].start(nozzle_timeout); + HOTEND_LOOP() thermalManager.heater_idle[e].start(nozzle_timeout); #if ENABLED(DUAL_X_CARRIAGE) const int8_t saved_ext = active_extruder; @@ -503,7 +503,7 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep // If the nozzle has timed out... if (!nozzle_timed_out) - HOTEND_LOOP() nozzle_timed_out |= thermalManager.hotend_idle[e].timed_out; + HOTEND_LOOP() nozzle_timed_out |= thermalManager.heater_idle[e].timed_out; // Wait for the user to press the button to re-heat the nozzle, then // re-heat the nozzle, re-show the continue prompt, restart idle timers, start over @@ -533,7 +533,7 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep // Start the heater idle timers const millis_t nozzle_timeout = SEC_TO_MS(PAUSE_PARK_NOZZLE_TIMEOUT); - HOTEND_LOOP() thermalManager.hotend_idle[e].start(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."))); wait_for_user = true; @@ -588,7 +588,7 @@ void resume_print(const float &slow_load_length/*=0*/, const float &fast_load_le // Re-enable the heaters if they timed out bool nozzle_timed_out = false; HOTEND_LOOP() { - nozzle_timed_out |= thermalManager.hotend_idle[e].timed_out; + nozzle_timed_out |= thermalManager.heater_idle[e].timed_out; thermalManager.reset_hotend_idle_timer(e); } diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h index 35542f9412ab..9742967a09d9 100644 --- a/Marlin/src/inc/Conditionals_adv.h +++ b/Marlin/src/inc/Conditionals_adv.h @@ -56,6 +56,15 @@ #undef SHOW_TEMP_ADC_VALUES #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 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/lcd/HD44780/ultralcd_HD44780.cpp b/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp index 81ba4653a1a8..0a1177d63ee9 100644 --- a/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp +++ b/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp @@ -521,7 +521,7 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const FORCE_INLINE void _draw_heater_status(const heater_id_t heater_id, const char prefix, const bool blink) { #if HAS_HEATED_BED - const bool isBed = heater_id < 0; + const bool isBed = TERN(HAS_HEATED_CHAMBER, heater_id == H_BED, heater_id < 0); const float t1 = (isBed ? thermalManager.degBed() : thermalManager.degHotend(heater_id)), t2 = (isBed ? thermalManager.degTargetBed() : thermalManager.degTargetHotend(heater_id)); #else @@ -536,14 +536,7 @@ FORCE_INLINE void _draw_heater_status(const heater_id_t heater_id, const char pr #if !HEATER_IDLE_HANDLER UNUSED(blink); #else - const bool is_idle = ( - #if HAS_HEATED_BED - isBed ? thermalManager.bed_idle.timed_out : - #endif - thermalManager.hotend_idle[heater_id].timed_out - ); - - if (!blink && is_idle) { + 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(' '); @@ -560,27 +553,14 @@ FORCE_INLINE void _draw_heater_status(const heater_id_t heater_id, const char pr } FORCE_INLINE void _draw_bed_status(const bool blink) { - _draw_heater_status(H_BED, ( - #if HAS_LEVELING - planner.leveling_active && blink ? '_' : - #endif - LCD_STR_BEDTEMP[0] - ), - blink - ); + _draw_heater_status(H_BED, TERN0(HAS_LEVELING, blink && planner.leveling_active) ? '_' : LCD_STR_BEDTEMP[0], blink); } #if HAS_PRINT_PROGRESS FORCE_INLINE void _draw_print_progress() { const uint8_t progress = ui.get_progress_percent(); - lcd_put_u8str_P(PSTR( - #if ENABLED(SDSUPPORT) - "SD" - #elif ENABLED(LCD_SET_PROGRESS_MANUALLY) - "P:" - #endif - )); + lcd_put_u8str_P(PSTR(TERN(SDSUPPORT, "SD", "P:"))); if (progress) lcd_put_u8str(ui8tostr3rj(progress)); else diff --git a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp index f668e453cca8..4b51c2949b23 100644 --- a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp +++ b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp @@ -254,7 +254,7 @@ FORCE_INLINE void _draw_centered_temp(const int16_t temp, const uint8_t tx, cons if (PAGE_UNDER(7)) { #if HEATER_IDLE_HANDLER - const bool dodraw = (blink || !thermalManager.hotend_idle[heater_id].timed_out); + const bool dodraw = (blink || !thermalManager.heater_idle[heater_id].timed_out); #else constexpr bool dodraw = true; #endif @@ -327,7 +327,7 @@ FORCE_INLINE void _draw_centered_temp(const int16_t temp, const uint8_t tx, cons if (PAGE_UNDER(7)) { #if HEATER_IDLE_HANDLER - const bool dodraw = (blink || !thermalManager.bed_idle.timed_out); + const bool dodraw = (blink || !thermalManager.heater_idle[thermalManager.IDLE_INDEX_BED].timed_out); #else constexpr bool dodraw = true; #endif diff --git a/Marlin/src/lcd/dogm/ultralcd_DOGM.cpp b/Marlin/src/lcd/dogm/ultralcd_DOGM.cpp index bf0edbb8ded2..b4f32d3343a1 100644 --- a/Marlin/src/lcd/dogm/ultralcd_DOGM.cpp +++ b/Marlin/src/lcd/dogm/ultralcd_DOGM.cpp @@ -308,7 +308,7 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop lcd_put_u8str(i16tostr3rj(thermalManager.degHotend(extruder))); lcd_put_wchar('/'); - if (get_blink() || !thermalManager.hotend_idle[extruder].timed_out) + if (get_blink() || !thermalManager.heater_idle[extruder].timed_out) lcd_put_u8str(i16tostr3rj(thermalManager.degTargetHotend(extruder))); } diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index 53b7dc6279c6..4d65429bf1d2 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -223,7 +223,7 @@ namespace ExtUI { bool isHeaterIdle(const extruder_t extruder) { #if HAS_HOTEND && HEATER_IDLE_HANDLER - return thermalManager.hotend_idle[extruder - E0].timed_out; + return thermalManager.heater_idle[extruder - E0].timed_out; #else UNUSED(extruder); return false; @@ -233,10 +233,10 @@ namespace ExtUI { bool isHeaterIdle(const heater_t heater) { #if HEATER_IDLE_HANDLER switch (heater) { - TERN_(HAS_HEATED_BED, case BED: return thermalManager.bed_idle.timed_out); + TERN_(HAS_HEATED_BED, case BED: return thermalManager.heater_idle[thermalManager.IDLE_INDEX_BED].timed_out); TERN_(HAS_HEATED_CHAMBER, case CHAMBER: return false); // Chamber has no idle timer default: - return TERN0(HAS_HOTEND, thermalManager.hotend_idle[heater - H0].timed_out); + return TERN0(HAS_HOTEND, thermalManager.heater_idle[heater - H0].timed_out); } #else UNUSED(heater); diff --git a/Marlin/src/lcd/language/language_cz.h b/Marlin/src/lcd/language/language_cz.h index e7d2611bc413..b11a3686cb46 100644 --- a/Marlin/src/lcd/language/language_cz.h +++ b/Marlin/src/lcd/language/language_cz.h @@ -410,10 +410,6 @@ namespace Language_cz { 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_ERR_MAXTEMP_BED = _UxGT("VYS. TEPL. PODL."); - PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("NÍZ. TEPL. PODL."); - PROGMEM Language_Str MSG_ERR_MAXTEMP_CHAMBER = _UxGT("Err: MAXTEMP KOMORA"); - PROGMEM Language_Str MSG_ERR_MINTEMP_CHAMBER = _UxGT("Err: MINTEMP KOMORA"); 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"); diff --git a/Marlin/src/lcd/language/language_da.h b/Marlin/src/lcd/language/language_da.h index c6f5647d5af6..da282be0b40f 100644 --- a/Marlin/src/lcd/language/language_da.h +++ b/Marlin/src/lcd/language/language_da.h @@ -142,8 +142,6 @@ namespace Language_da { 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_ERR_MAXTEMP_BED = _UxGT("Fejl: Maks Plade temp"); - PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("Fejl: Min Plade 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 diff --git a/Marlin/src/lcd/language/language_de.h b/Marlin/src/lcd/language/language_de.h index e353229daacf..875444c0e7fe 100644 --- a/Marlin/src/lcd/language/language_de.h +++ b/Marlin/src/lcd/language/language_de.h @@ -452,10 +452,6 @@ namespace Language_de { 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_ERR_MAXTEMP_BED = _UxGT("BETT ") LCD_STR_THERMOMETER _UxGT(" ÜBERSCHRITTEN"); - PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("BETT ") LCD_STR_THERMOMETER _UxGT(" UNTERSCHRITTEN"); - PROGMEM Language_Str MSG_ERR_MAXTEMP_CHAMBER = _UxGT("Err:Gehäuse max Temp"); - PROGMEM Language_Str MSG_ERR_MINTEMP_CHAMBER = _UxGT("Err:Gehäuse min Temp"); 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 diff --git a/Marlin/src/lcd/language/language_el.h b/Marlin/src/lcd/language/language_el.h index cee8dd0e55d5..8fe888765331 100644 --- a/Marlin/src/lcd/language/language_el.h +++ b/Marlin/src/lcd/language/language_el.h @@ -180,8 +180,6 @@ namespace Language_el { 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_ERR_MAXTEMP_BED = _UxGT("ΜΕΓΙΣΤΗ ΘΕΡΜΟΚΡΑΣΙΑΣ ΕΠ. ΕΚΤΥΠΩΣΗΣ"); //SHORTEN - PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("ΕΛΑΧΙΣΤΗ ΘΕΡΜΟΚΡΑΣΙΑΣ ΕΠ. ΕΚΤΥΠΩΣΗΣ"); //SHORTEN PROGMEM Language_Str MSG_HALTED = _UxGT("H εκτύπωση διακόπηκε"); PROGMEM Language_Str MSG_HEATING = _UxGT("Θερμαίνεται…"); PROGMEM Language_Str MSG_BED_HEATING = _UxGT("Θέρμανση ΕΠ. Εκτύπωσης"); //SHORTEN diff --git a/Marlin/src/lcd/language/language_el_gr.h b/Marlin/src/lcd/language/language_el_gr.h index d7bead9ea669..ad170a348721 100644 --- a/Marlin/src/lcd/language/language_el_gr.h +++ b/Marlin/src/lcd/language/language_el_gr.h @@ -182,8 +182,6 @@ namespace Language_el_gr { 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_ERR_MAXTEMP_BED = _UxGT("Λάθος: ΜΕΓΙΣΤΗ ΘΕΡΜΟΤΗΤΑ ΚΛΙΝΗΣ"); - PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("Λάθος: ΕΛΑΧΙΣΤΗ ΘΕΡΜΟΤΗΤΑ ΚΛΙΝΗΣ"); PROGMEM Language_Str MSG_HEATING = _UxGT("Θερμαίνεται…"); PROGMEM Language_Str MSG_BED_HEATING = _UxGT("Θέρμανση κλίνης…"); PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Βαθμονόμηση Delta"); diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index f5ba320881c2..fc9e065abe0d 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -457,10 +457,6 @@ namespace Language_en { PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("CHAMBER T. RUNAWAY"); PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Err: MAXTEMP"); PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Err: MINTEMP"); - PROGMEM Language_Str MSG_ERR_MAXTEMP_BED = _UxGT("Err: MAXTEMP BED"); - PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("Err: MINTEMP BED"); - PROGMEM Language_Str MSG_ERR_MAXTEMP_CHAMBER = _UxGT("Err: MAXTEMP CHAMBER"); - PROGMEM Language_Str MSG_ERR_MINTEMP_CHAMBER = _UxGT("Err: MINTEMP CHAMBER"); PROGMEM Language_Str MSG_HALTED = _UxGT("PRINTER HALTED"); PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Please Reset"); PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("d"); // One character only diff --git a/Marlin/src/lcd/language/language_es.h b/Marlin/src/lcd/language/language_es.h index 11cb8cc2a91f..15fa35ac75f5 100644 --- a/Marlin/src/lcd/language/language_es.h +++ b/Marlin/src/lcd/language/language_es.h @@ -421,10 +421,6 @@ namespace Language_es { 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_ERR_MAXTEMP_BED = _UxGT("Err:TEMP. MÁX CAMA"); - PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("Err:TEMP. MIN CAMA"); - PROGMEM Language_Str MSG_ERR_MAXTEMP_CHAMBER = _UxGT("Err:TEMP. MÁX CÁMARA"); - PROGMEM Language_Str MSG_ERR_MINTEMP_CHAMBER = _UxGT("Err:TEMP. MIN CÁMARA"); 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 diff --git a/Marlin/src/lcd/language/language_eu.h b/Marlin/src/lcd/language/language_eu.h index d04b3037ab4e..bee571bbde25 100644 --- a/Marlin/src/lcd/language/language_eu.h +++ b/Marlin/src/lcd/language/language_eu.h @@ -244,8 +244,6 @@ namespace Language_eu { 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_ERR_MAXTEMP_BED = _UxGT("Err: Ohe Tenp Max"); - PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("Err: Ohe Tenp Min"); 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 diff --git a/Marlin/src/lcd/language/language_gl.h b/Marlin/src/lcd/language/language_gl.h index d47ec0b67d36..53b0803518e5 100644 --- a/Marlin/src/lcd/language/language_gl.h +++ b/Marlin/src/lcd/language/language_gl.h @@ -443,10 +443,6 @@ namespace Language_gl { 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_ERR_MAXTEMP_BED = _UxGT("Erro:TEMP MÁX CAMA"); - PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("Erro:TEMP MÍN CAMA"); - PROGMEM Language_Str MSG_ERR_MAXTEMP_CHAMBER = _UxGT("Erro:TEMP MÁX CÁMARA"); - PROGMEM Language_Str MSG_ERR_MINTEMP_CHAMBER = _UxGT("Erro:TEMP MÍN CÁMARA"); 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 diff --git a/Marlin/src/lcd/language/language_hu.h b/Marlin/src/lcd/language/language_hu.h index 962fb17511a8..76aff51d9cc3 100644 --- a/Marlin/src/lcd/language/language_hu.h +++ b/Marlin/src/lcd/language/language_hu.h @@ -445,10 +445,6 @@ namespace Language_hu { PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("KAMRA FÜTÉS KIMARADÁS"); 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_ERR_MAXTEMP_BED = _UxGT("Hiba: MAX ÁGY HÖFOK"); - PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("Hiba: MIN ÁGY HÖFOK"); - PROGMEM Language_Str MSG_ERR_MAXTEMP_CHAMBER = _UxGT("Hiba: MAX KAMRA HÖFOK"); - PROGMEM Language_Str MSG_ERR_MINTEMP_CHAMBER = _UxGT("Hiba: MIN KAMRA HÖFOK"); PROGMEM Language_Str MSG_HALTED = _UxGT("A NYOMTATÓ LEFAGYOTT"); PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Indítsd újra!"); PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("n"); // Csak egy karakter diff --git a/Marlin/src/lcd/language/language_it.h b/Marlin/src/lcd/language/language_it.h index 27087e5a5562..e22e58708f51 100644 --- a/Marlin/src/lcd/language/language_it.h +++ b/Marlin/src/lcd/language/language_it.h @@ -457,10 +457,6 @@ namespace Language_it { PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("T.CAMERA FUORI CTRL"); PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Err: TEMP MASSIMA"); PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Err: TEMP MINIMA"); - PROGMEM Language_Str MSG_ERR_MAXTEMP_BED = _UxGT("Err: TEMP MAX PIATTO"); - PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("Err: TEMP MIN PIATTO"); - PROGMEM Language_Str MSG_ERR_MAXTEMP_CHAMBER = _UxGT("Err: TEMP MAX CAMERA"); - PROGMEM Language_Str MSG_ERR_MINTEMP_CHAMBER = _UxGT("Err: TEMP MIN CAMERA"); 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 diff --git a/Marlin/src/lcd/language/language_jp_kana.h b/Marlin/src/lcd/language/language_jp_kana.h index 5f679dd49d2c..df6ad9b5d98f 100644 --- a/Marlin/src/lcd/language/language_jp_kana.h +++ b/Marlin/src/lcd/language/language_jp_kana.h @@ -184,8 +184,6 @@ namespace Language_jp_kana { 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_ERR_MAXTEMP_BED = _UxGT("エラー:ベッド サイコウオンチョウカ"); // "Err: MAXTEMP BED" - PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("エラー:ベッド サイテイオンミマン"); // "Err: MINTEMP BED" 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 diff --git a/Marlin/src/lcd/language/language_nl.h b/Marlin/src/lcd/language/language_nl.h index c8c79e472add..c1a1a0605b31 100644 --- a/Marlin/src/lcd/language/language_nl.h +++ b/Marlin/src/lcd/language/language_nl.h @@ -164,8 +164,6 @@ namespace Language_nl { 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_ERR_MAXTEMP_BED = _UxGT("Err: Max.tmp bed"); - PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("Err: Min.tmp bed"); 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 diff --git a/Marlin/src/lcd/language/language_pl.h b/Marlin/src/lcd/language/language_pl.h index 7c3f9c1bb100..f6a9e12c8ee5 100644 --- a/Marlin/src/lcd/language/language_pl.h +++ b/Marlin/src/lcd/language/language_pl.h @@ -391,10 +391,6 @@ namespace Language_pl { PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("ZANIK TEMP.KOMORY"); PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Błąd: MAXTEMP"); PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Błąd: MINTEMP"); - PROGMEM Language_Str MSG_ERR_MAXTEMP_BED = _UxGT("Błąd: MAXTEMP STÓŁ"); - PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("Błąd: MINTEMP STÓŁ"); - PROGMEM Language_Str MSG_ERR_MAXTEMP_CHAMBER = _UxGT("Błąd: MAXTEMP KOMORA"); - PROGMEM Language_Str MSG_ERR_MINTEMP_CHAMBER = _UxGT("Błąd: MINTEMP KOMORA"); 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 diff --git a/Marlin/src/lcd/language/language_pt.h b/Marlin/src/lcd/language/language_pt.h index 1180649c989b..8bd94d06e154 100644 --- a/Marlin/src/lcd/language/language_pt.h +++ b/Marlin/src/lcd/language/language_pt.h @@ -150,8 +150,6 @@ namespace Language_pt { 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_ERR_MAXTEMP_BED = _UxGT("Err: T Base Máxima"); - PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("Err: T Base 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"); diff --git a/Marlin/src/lcd/language/language_pt_br.h b/Marlin/src/lcd/language/language_pt_br.h index b9fd91fa293f..eb1e2f9bf32e 100644 --- a/Marlin/src/lcd/language/language_pt_br.h +++ b/Marlin/src/lcd/language/language_pt_br.h @@ -357,10 +357,6 @@ namespace Language_pt_br { 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_ERR_MAXTEMP_BED = _UxGT("Erro:Temp Mesa Máx"); - PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("Erro:Temp Mesa Mín"); - PROGMEM Language_Str MSG_ERR_MAXTEMP_CHAMBER = _UxGT("Erro:Temp Câmara Máx"); - PROGMEM Language_Str MSG_ERR_MINTEMP_CHAMBER = _UxGT("Erro:Temp Câmara Min"); 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"); diff --git a/Marlin/src/lcd/language/language_ro.h b/Marlin/src/lcd/language/language_ro.h index 0d5b1568a71a..d71471a09dfc 100644 --- a/Marlin/src/lcd/language/language_ro.h +++ b/Marlin/src/lcd/language/language_ro.h @@ -448,10 +448,6 @@ namespace Language_ro { PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("CHAMBER T. RUNAWAY"); PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Err: MAXTEMP"); PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Err: MINTEMP"); - PROGMEM Language_Str MSG_ERR_MAXTEMP_BED = _UxGT("Err: MAXTEMP BED"); - PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("Err: MINTEMP BED"); - PROGMEM Language_Str MSG_ERR_MAXTEMP_CHAMBER = _UxGT("Err: MAXTEMP CHAMBER"); - PROGMEM Language_Str MSG_ERR_MINTEMP_CHAMBER = _UxGT("Err: MINTEMP CHAMBER"); PROGMEM Language_Str MSG_HALTED = _UxGT("PRINTER HALTED"); PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Please Reset"); PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("d"); // One character only diff --git a/Marlin/src/lcd/language/language_ru.h b/Marlin/src/lcd/language/language_ru.h index 0e2c63ca139f..b8c146e515e8 100644 --- a/Marlin/src/lcd/language/language_ru.h +++ b/Marlin/src/lcd/language/language_ru.h @@ -536,10 +536,6 @@ namespace Language_ru { PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("УТЕЧКА ТЕПЛА КАМЕРЫ"); PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Ошибка: Т макс."); PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Ошибка: Т мин."); - PROGMEM Language_Str MSG_ERR_MAXTEMP_BED = _UxGT("Ошибка: Т стола макс"); - PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("Ошибка: Т стола мин."); - PROGMEM Language_Str MSG_ERR_MAXTEMP_CHAMBER = _UxGT("Ошибка:Т камеры макс"); - PROGMEM Language_Str MSG_ERR_MINTEMP_CHAMBER = _UxGT("Ошибка:Т камеры мин."); PROGMEM Language_Str MSG_HALTED = _UxGT("ПРИНТЕР ОСТАНОВЛЕН"); PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Сделайте сброс"); PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("д"); // One character only diff --git a/Marlin/src/lcd/language/language_sk.h b/Marlin/src/lcd/language/language_sk.h index ace2ba6da4b3..e936110d0768 100644 --- a/Marlin/src/lcd/language/language_sk.h +++ b/Marlin/src/lcd/language/language_sk.h @@ -441,10 +441,6 @@ namespace Language_sk { PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("TEPLOTNÝ SKOK KOMO."); PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Chyba: MAXTEMP"); PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Chyba: MINTEMP"); - PROGMEM Language_Str MSG_ERR_MAXTEMP_BED = _UxGT("Chyba: MAXTEMP PODL."); - PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("Chyba: MINTEMP PODL."); - PROGMEM Language_Str MSG_ERR_MAXTEMP_CHAMBER = _UxGT("Chyba: MAXTEMP KOMO."); - PROGMEM Language_Str MSG_ERR_MINTEMP_CHAMBER = _UxGT("Chyba: MINTEMP KOMO."); 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"); diff --git a/Marlin/src/lcd/language/language_tr.h b/Marlin/src/lcd/language/language_tr.h index ed11ec87c5a8..95e4fb2a8bad 100644 --- a/Marlin/src/lcd/language/language_tr.h +++ b/Marlin/src/lcd/language/language_tr.h @@ -420,10 +420,6 @@ namespace Language_tr { PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("ODA TERMAL PROBLEM"); PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Hata: MAX.SICAKLIK"); PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Hata: MIN.SICAKLIK"); - PROGMEM Language_Str MSG_ERR_MAXTEMP_BED = _UxGT("Hata: MAX.SIC. TABLA"); - PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("Hata: MIN.SIC. TABLA"); - PROGMEM Language_Str MSG_ERR_MAXTEMP_CHAMBER = _UxGT("Hata: MAX.SIC ODA"); - PROGMEM Language_Str MSG_ERR_MINTEMP_CHAMBER = _UxGT("Hata: MIN.SIC ODA"); PROGMEM Language_Str MSG_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 diff --git a/Marlin/src/lcd/language/language_uk.h b/Marlin/src/lcd/language/language_uk.h index 99d70cc2520e..9041decbb251 100644 --- a/Marlin/src/lcd/language/language_uk.h +++ b/Marlin/src/lcd/language/language_uk.h @@ -530,10 +530,6 @@ namespace Language_uk { PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("ВИТІК ТЕПЛА КАМЕРИ"); PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("ПЕРЕГРІВ"); PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("МІНІМАЛЬНА Т") LCD_STR_DEGREE; - PROGMEM Language_Str MSG_ERR_MAXTEMP_BED = _UxGT("ПЕРЕГРІВ СТОЛУ"); - PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("МІНІМАЛЬНА Т") LCD_STR_DEGREE _UxGT(" СТОЛУ"); - PROGMEM Language_Str MSG_ERR_MAXTEMP_CHAMBER = _UxGT("ПЕРЕГРІВ КАМЕРИ"); - PROGMEM Language_Str MSG_ERR_MINTEMP_CHAMBER = _UxGT("МІНІМАЛЬНА Т") LCD_STR_DEGREE _UxGT(" КАМЕРИ"); PROGMEM Language_Str MSG_HALTED = _UxGT("ПРИНТЕР ЗУПИНЕНО"); PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Перезавантажте"); PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("д"); // One character only diff --git a/Marlin/src/lcd/language/language_vi.h b/Marlin/src/lcd/language/language_vi.h index 507490188308..afd87d379838 100644 --- a/Marlin/src/lcd/language/language_vi.h +++ b/Marlin/src/lcd/language/language_vi.h @@ -335,8 +335,6 @@ namespace Language_vi { 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_ERR_MAXTEMP_BED = _UxGT("Điều sai: nhiệt độ bàn tối đa"); // Err: MAXTEMP BED - PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("Điều sai: nhiệt độ bàn tối thiểu"); // Err: MINTEMP BED 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 diff --git a/Marlin/src/lcd/language/language_zh_CN.h b/Marlin/src/lcd/language/language_zh_CN.h index 2a98d58e819e..d30ee789dd85 100644 --- a/Marlin/src/lcd/language/language_zh_CN.h +++ b/Marlin/src/lcd/language/language_zh_CN.h @@ -447,10 +447,6 @@ namespace Language_zh_CN { 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_ERR_MAXTEMP_BED = _UxGT("错误:最高热床温度"); //"Err: MAXTEMP BED" - PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("错误:最低热床温度"); //"Err: MINTEMP BED" - PROGMEM Language_Str MSG_ERR_MAXTEMP_CHAMBER = _UxGT("错误:最高机箱温度"); - PROGMEM Language_Str MSG_ERR_MINTEMP_CHAMBER = _UxGT("错误:最低机箱温度"); 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 diff --git a/Marlin/src/lcd/language/language_zh_TW.h b/Marlin/src/lcd/language/language_zh_TW.h index 532886d45116..6764af6d73ce 100644 --- a/Marlin/src/lcd/language/language_zh_TW.h +++ b/Marlin/src/lcd/language/language_zh_TW.h @@ -388,10 +388,6 @@ namespace Language_zh_TW { PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("機箱溫度失控"); //"CHAMBER T. RUNAWAY" PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("錯誤:最高溫度"); //"Err: MAXTEMP" PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("錯誤:最低溫度"); //"Err: MINTEMP" - PROGMEM Language_Str MSG_ERR_MAXTEMP_BED = _UxGT("錯誤:最高熱床溫度"); //"Err: MAXTEMP BED" - PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("錯誤:最低熱床溫度"); //"Err: MINTEMP BED" - PROGMEM Language_Str MSG_ERR_MAXTEMP_CHAMBER = _UxGT("錯誤:最高機箱溫度"); //"Err: MAXTEMP CHAMBER" - PROGMEM Language_Str MSG_ERR_MINTEMP_CHAMBER = _UxGT("錯誤:最低機箱溫度"); //"Err: MINTEMP CHAMBER" PROGMEM Language_Str MSG_HALTED = _UxGT("印表機停機"); //"PRINTER HALTED" PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("請重置"); //"Please reset" PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("天"); //"d" // One character only diff --git a/Marlin/src/lcd/menu/menu.cpp b/Marlin/src/lcd/menu/menu.cpp index e6739a135cbf..64923547e8ad 100644 --- a/Marlin/src/lcd/menu/menu.cpp +++ b/Marlin/src/lcd/menu/menu.cpp @@ -34,10 +34,6 @@ #include "../../libs/buzzer.h" #endif -#if WATCH_HOTENDS || WATCH_BED - #include "../../module/temperature.h" -#endif - #if ENABLED(BABYSTEP_ZPROBE_OFFSET) #include "../../module/probe.h" #endif diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 06864c6b97b4..e0fa6fa98f53 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -252,7 +252,7 @@ const char str_t_thermal_runaway[] PROGMEM = STR_T_THERMAL_RUNAWAY, hotend_watch_t Temperature::watch_hotend[HOTENDS]; // = { { 0 } } #endif #if HEATER_IDLE_HANDLER - hotend_idle_t Temperature::hotend_idle[HOTENDS]; // = { { 0 } } + Temperature::heater_idle_t Temperature::heater_idle[NR_HEATER_IDLE]; // = { { 0 } } #endif #if HAS_HEATED_BED @@ -266,7 +266,6 @@ const char str_t_thermal_runaway[] PROGMEM = STR_T_THERMAL_RUNAWAY, #endif TERN_(WATCH_BED, bed_watch_t Temperature::watch_bed); // = { 0 } TERN(PIDTEMPBED,, millis_t Temperature::next_bed_check_ms); - TERN_(HEATER_IDLE_HANDLER, hotend_idle_t Temperature::bed_idle); // = { 0 } #endif // HAS_HEATED_BED #if HAS_TEMP_CHAMBER @@ -841,7 +840,7 @@ void Temperature::min_temp_error(const heater_id_t heater_id) { if (temp_hotend[ee].target == 0 || pid_error < -(PID_FUNCTIONAL_RANGE) - || TERN0(HEATER_IDLE_HANDLER, hotend_idle[ee].timed_out) + || TERN0(HEATER_IDLE_HANDLER, heater_idle[ee].timed_out) ) { pid_output = 0; pid_reset[ee] = true; @@ -926,7 +925,7 @@ void Temperature::min_temp_error(const heater_id_t heater_id) { #else // No PID enabled - const bool is_idling = TERN0(HEATER_IDLE_HANDLER, hotend_idle[ee].timed_out); + const bool is_idling = TERN0(HEATER_IDLE_HANDLER, heater_idle[ee].timed_out); const float pid_output = (!is_idling && temp_hotend[ee].celsius < temp_hotend[ee].target) ? BANG_MAX : 0; #endif @@ -1040,15 +1039,14 @@ void Temperature::manage_heater() { HOTEND_LOOP() { #if ENABLED(THERMAL_PROTECTION_HOTENDS) - if (degHotend(e) > temp_range[e].maxtemp) - _temp_error((heater_id_t)e, str_t_thermal_runaway, GET_TEXT(MSG_THERMAL_RUNAWAY)); + if (degHotend(e) > temp_range[e].maxtemp) max_temp_error((heater_id_t)e); #endif - TERN_(HEATER_IDLE_HANDLER, hotend_idle[e].update(ms)); + TERN_(HEATER_IDLE_HANDLER, heater_idle[e].update(ms)); #if ENABLED(THERMAL_PROTECTION_HOTENDS) // Check for thermal runaway - thermal_runaway_protection(tr_state_machine[e], temp_hotend[e].celsius, temp_hotend[e].target, (heater_id_t)e, THERMAL_PROTECTION_PERIOD, THERMAL_PROTECTION_HYSTERESIS); + tr_state_machine[e].run(temp_hotend[e].celsius, temp_hotend[e].target, (heater_id_t)e, THERMAL_PROTECTION_PERIOD, THERMAL_PROTECTION_HYSTERESIS); #endif temp_hotend[e].soft_pwm_amount = (temp_hotend[e].celsius > temp_range[e].mintemp || is_preheating(e)) && temp_hotend[e].celsius < temp_range[e].maxtemp ? (int)get_pid_output_hotend(e) >> 1 : 0; @@ -1093,8 +1091,7 @@ void Temperature::manage_heater() { #if HAS_HEATED_BED #if ENABLED(THERMAL_PROTECTION_BED) - if (degBed() > BED_MAXTEMP) - _temp_error(H_BED, str_t_thermal_runaway, GET_TEXT(MSG_THERMAL_RUNAWAY)); + if (degBed() > BED_MAXTEMP) max_temp_error(H_BED); #endif #if WATCH_BED @@ -1127,12 +1124,14 @@ void Temperature::manage_heater() { TERN_(PAUSE_CHANGE_REQD, last_pause_state = paused); #endif - TERN_(HEATER_IDLE_HANDLER, bed_idle.update(ms)); + TERN_(HEATER_IDLE_HANDLER, heater_idle[IDLE_INDEX_BED].update(ms)); - TERN_(HAS_THERMALLY_PROTECTED_BED, thermal_runaway_protection(tr_state_machine_bed, temp_bed.celsius, temp_bed.target, H_BED, THERMAL_PROTECTION_BED_PERIOD, THERMAL_PROTECTION_BED_HYSTERESIS)); + #if HAS_THERMALLY_PROTECTED_BED + tr_state_machine[RUNAWAY_IND_BED].run(temp_bed.celsius, temp_bed.target, H_BED, THERMAL_PROTECTION_BED_PERIOD, THERMAL_PROTECTION_BED_HYSTERESIS); + #endif #if HEATER_IDLE_HANDLER - if (bed_idle.timed_out) { + if (heater_idle[IDLE_INDEX_BED].timed_out) { temp_bed.soft_pwm_amount = 0; #if DISABLED(PIDTEMPBED) WRITE_HEATER_BED(LOW); @@ -1173,8 +1172,7 @@ void Temperature::manage_heater() { #endif #if ENABLED(THERMAL_PROTECTION_CHAMBER) - if (degChamber() > CHAMBER_MAXTEMP) - _temp_error(H_CHAMBER, str_t_thermal_runaway, GET_TEXT(MSG_THERMAL_RUNAWAY)); + if (degChamber() > CHAMBER_MAXTEMP) max_temp_error(H_CHAMBER); #endif #if WATCH_CHAMBER @@ -1205,7 +1203,9 @@ void Temperature::manage_heater() { WRITE_HEATER_CHAMBER(LOW); } - TERN_(THERMAL_PROTECTION_CHAMBER, thermal_runaway_protection(tr_state_machine_chamber, temp_chamber.celsius, temp_chamber.target, H_CHAMBER, THERMAL_PROTECTION_CHAMBER_PERIOD, THERMAL_PROTECTION_CHAMBER_HYSTERESIS)); + #if ENABLED(THERMAL_PROTECTION_CHAMBER) + tr_state_machine[RUNAWAY_IND_CHAMBER].run(temp_chamber.celsius, temp_chamber.target, H_CHAMBER, THERMAL_PROTECTION_CHAMBER_PERIOD, THERMAL_PROTECTION_CHAMBER_HYSTERESIS); + #endif } // TODO: Implement true PID pwm @@ -1935,61 +1935,66 @@ void Temperature::init() { #if HAS_THERMAL_PROTECTION - #if ENABLED(THERMAL_PROTECTION_HOTENDS) - Temperature::tr_state_machine_t Temperature::tr_state_machine[HOTENDS]; // = { { TRInactive, 0 } }; - #endif - #if HAS_THERMALLY_PROTECTED_BED - Temperature::tr_state_machine_t Temperature::tr_state_machine_bed; // = { TRInactive, 0 }; - #endif - #if ENABLED(THERMAL_PROTECTION_CHAMBER) - Temperature::tr_state_machine_t Temperature::tr_state_machine_chamber; // = { TRInactive, 0 }; - #endif + Temperature::tr_state_machine_t Temperature::tr_state_machine[NR_HEATER_RUNAWAY]; // = { { TRInactive, 0 } }; - void Temperature::thermal_runaway_protection(Temperature::tr_state_machine_t &sm, const float ¤t, const float &target, const heater_id_t heater_id, const uint16_t period_seconds, const uint16_t hysteresis_degc) { + /** + * @brief Thermal Runaway state machine for a single heater + * @param current current measured temperature + * @param target current target temperature + * @param heater_id extruder index + * @param period_seconds missed temperature allowed time + * @param hysteresis_degc allowed distance from target + * + * TODO: Embed the last 3 parameters during init, if not less optimal + */ + void Temperature::tr_state_machine_t::run(const float ¤t, const float &target, const heater_id_t heater_id, const uint16_t period_seconds, const uint16_t hysteresis_degc) { - static float tr_target_temperature[HOTENDS + 1] = { 0.0 }; + #if HEATER_IDLE_HANDLER + // Convert the given heater_id_t to an idle array index + const IdleIndex idle_index = idle_index_for_id(heater_id); + #endif /** SERIAL_ECHO_START(); SERIAL_ECHOPGM("Thermal Runaway Running. Heater ID: "); - if (heater_id == H_CHAMBER) SERIAL_ECHOPGM("chamber"); - if (heater_id < 0) SERIAL_ECHOPGM("bed"); else SERIAL_ECHO(heater_id); - SERIAL_ECHOPAIR(" ; State:", sm.state, " ; Timer:", sm.timer, " ; Temperature:", current, " ; Target Temp:", target); - if (heater_id >= 0) - SERIAL_ECHOPAIR(" ; Idle Timeout:", hotend_idle[heater_id].timed_out); - else - SERIAL_ECHOPAIR(" ; Idle Timeout:", bed_idle.timed_out); - SERIAL_EOL(); + switch (heater_id) { + case H_BED: SERIAL_ECHOPGM("bed"); break; + case H_CHAMBER: SERIAL_ECHOPGM("chamber"); break; + default: SERIAL_ECHO(heater_id); + } + SERIAL_ECHOLNPAIR( + " ; sizeof(running_temp):", sizeof(running_temp), + " ; State:", state, " ; Timer:", timer, " ; Temperature:", current, " ; Target Temp:", target + #if HEATER_IDLE_HANDLER + , " ; Idle Timeout:", heater_idle[idle_index].timed_out + #endif + ); //*/ - const int heater_index = heater_id >= 0 ? heater_id : HOTENDS; - #if HEATER_IDLE_HANDLER // If the heater idle timeout expires, restart - if ((heater_id >= 0 && hotend_idle[heater_id].timed_out) - || TERN0(HAS_HEATED_BED, (heater_id < 0 && bed_idle.timed_out)) - ) { - sm.state = TRInactive; - tr_target_temperature[heater_index] = 0; + if (heater_idle[idle_index].timed_out) { + state = TRInactive; + running_temp = 0; } else #endif { // If the target temperature changes, restart - if (tr_target_temperature[heater_index] != target) { - tr_target_temperature[heater_index] = target; - sm.state = target > 0 ? TRFirstHeating : TRInactive; + if (running_temp != target) { + running_temp = target; + state = target > 0 ? TRFirstHeating : TRInactive; } } - switch (sm.state) { + switch (state) { // Inactive state waits for a target temperature to be set case TRInactive: break; // When first heating, wait for the temperature to be reached then go to Stable state case TRFirstHeating: - if (current < tr_target_temperature[heater_index]) break; - sm.state = TRStable; + if (current < running_temp) break; + state = TRStable; // While the temperature is stable watch for a bad temperature case TRStable: @@ -1997,25 +2002,25 @@ void Temperature::init() { #if ENABLED(ADAPTIVE_FAN_SLOWING) if (adaptive_fan_slowing && heater_id >= 0) { const int fan_index = _MIN(heater_id, FAN_COUNT - 1); - if (fan_speed[fan_index] == 0 || current >= tr_target_temperature[heater_id] - (hysteresis_degc * 0.25f)) + if (fan_speed[fan_index] == 0 || current >= running_temp - (hysteresis_degc * 0.25f)) fan_speed_scaler[fan_index] = 128; - else if (current >= tr_target_temperature[heater_id] - (hysteresis_degc * 0.3335f)) + else if (current >= running_temp - (hysteresis_degc * 0.3335f)) fan_speed_scaler[fan_index] = 96; - else if (current >= tr_target_temperature[heater_id] - (hysteresis_degc * 0.5f)) + else if (current >= running_temp - (hysteresis_degc * 0.5f)) fan_speed_scaler[fan_index] = 64; - else if (current >= tr_target_temperature[heater_id] - (hysteresis_degc * 0.8f)) + else if (current >= running_temp - (hysteresis_degc * 0.8f)) fan_speed_scaler[fan_index] = 32; else fan_speed_scaler[fan_index] = 0; } #endif - if (current >= tr_target_temperature[heater_index] - hysteresis_degc) { - sm.timer = millis() + SEC_TO_MS(period_seconds); + if (current >= running_temp - hysteresis_degc) { + timer = millis() + SEC_TO_MS(period_seconds); break; } - else if (PENDING(millis(), sm.timer)) break; - sm.state = TRRunaway; + else if (PENDING(millis(), timer)) break; + state = TRRunaway; case TRRunaway: TERN_(DWIN_CREALITY_LCD, Popup_Window_Temperature(0)); @@ -2086,8 +2091,8 @@ void Temperature::disable_all_heaters() { if (p != paused) { paused = p; if (p) { - HOTEND_LOOP() hotend_idle[e].expire(); // Timeout immediately - TERN_(HAS_HEATED_BED, bed_idle.expire()); // Timeout immediately + HOTEND_LOOP() heater_idle[e].expire(); // Timeout immediately + TERN_(HAS_HEATED_BED, heater_idle[IDLE_INDEX_BED].expire()); // Timeout immediately } else { HOTEND_LOOP() reset_hotend_idle_timer(e); @@ -2333,9 +2338,7 @@ void Temperature::readings_ready() { #else #define BEDCMP(A,B) ((A)>(B)) #endif - const bool bed_on = temp_bed.target > 0 - || TERN0(PIDTEMPBED, temp_bed.soft_pwm_amount) > 0 - ; + 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 diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index 37d1140f5e18..57b0fecbcc99 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -40,7 +40,7 @@ #define HOTEND_INDEX TERN(HAS_MULTI_HOTEND, e, 0) #define E_NAME TERN_(HAS_MULTI_HOTEND, e) -// Identifiers for other heaters +// Heater identifiers. Positive values are hotends. Negative values are other heaters. typedef enum : int8_t { INDEX_NONE = -5, H_PROBE, H_REDUNDANT, H_CHAMBER, H_BED, @@ -211,16 +211,6 @@ struct PIDHeaterInfo : public HeaterInfo { typedef temp_info_t chamber_info_t; #endif -// Heater idle handling -typedef struct { - millis_t timeout_ms; - bool timed_out; - inline void update(const millis_t &ms) { if (!timed_out && timeout_ms && ELAPSED(ms, timeout_ms)) timed_out = true; } - inline void start(const millis_t &ms) { timeout_ms = millis() + ms; timed_out = false; } - inline void reset() { timeout_ms = 0; timed_out = false; } - inline void expire() { start(0); } -} hotend_idle_t; - // Heater watch handling template struct HeaterWatch { @@ -346,9 +336,38 @@ class Temperature { FORCE_INLINE static bool targetHotEnoughToExtrude(const uint8_t e) { return !targetTooColdToExtrude(e); } #if HEATER_IDLE_HANDLER - static hotend_idle_t hotend_idle[HOTENDS]; - TERN_(HAS_HEATED_BED, static hotend_idle_t bed_idle); - TERN_(HAS_HEATED_CHAMBER, static hotend_idle_t chamber_idle); + + // Heater idle handling. Marlin creates one per hotend and one for the heated bed. + typedef struct { + millis_t timeout_ms; + bool timed_out; + inline void update(const millis_t &ms) { if (!timed_out && timeout_ms && ELAPSED(ms, timeout_ms)) timed_out = true; } + inline void start(const millis_t &ms) { timeout_ms = millis() + ms; timed_out = false; } + inline void reset() { timeout_ms = 0; timed_out = false; } + inline void expire() { start(0); } + } 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 + }; + #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 + return (IdleIndex)_MAX(heater_id, 0); + } + + static heater_idle_t heater_idle[NR_HEATER_IDLE]; + #endif private: @@ -747,13 +766,13 @@ class Temperature { #if HEATER_IDLE_HANDLER static void reset_hotend_idle_timer(const uint8_t E_NAME) { - hotend_idle[HOTEND_INDEX].reset(); + heater_idle[HOTEND_INDEX].reset(); start_watching_hotend(HOTEND_INDEX); } #if HAS_HEATED_BED static void reset_bed_idle_timer() { - bed_idle.reset(); + heater_idle[IDLE_INDEX_BED].reset(); start_watching_bed(); } #endif @@ -815,22 +834,47 @@ class Temperature { static void min_temp_error(const heater_id_t e); static void max_temp_error(const heater_id_t e); - #define HAS_THERMAL_PROTECTION (EITHER(THERMAL_PROTECTION_HOTENDS, THERMAL_PROTECTION_CHAMBER) || HAS_THERMALLY_PROTECTED_BED) + #define HAS_THERMAL_PROTECTION ANY(THERMAL_PROTECTION_HOTENDS, THERMAL_PROTECTION_CHAMBER, HAS_THERMALLY_PROTECTED_BED) #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 { + #if ENABLED(THERMAL_PROTECTION_HOTENDS) + REPEAT(HOTENDS, _ENUM_FOR_E) + #endif + #if ENABLED(HAS_THERMALLY_PROTECTED_BED) + RUNAWAY_IND_BED, + #endif + #if ENABLED(THERMAL_PROTECTION_CHAMBER) + RUNAWAY_IND_CHAMBER, + #endif + 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_BED + if (heater_id == H_BED) return RUNAWAY_IND_BED; + #endif + return (RunawayIndex)_MAX(heater_id, 0); + } + enum TRState : char { TRInactive, TRFirstHeating, TRStable, TRRunaway }; typedef struct { millis_t timer = 0; TRState state = TRInactive; + float running_temp; + void run(const float ¤t, const float &target, const heater_id_t heater_id, const uint16_t period_seconds, const uint16_t hysteresis_degc); } tr_state_machine_t; - TERN_(THERMAL_PROTECTION_HOTENDS, static tr_state_machine_t tr_state_machine[HOTENDS]); - TERN_(HAS_THERMALLY_PROTECTED_BED, static tr_state_machine_t tr_state_machine_bed); - TERN_(THERMAL_PROTECTION_CHAMBER, static tr_state_machine_t tr_state_machine_chamber); - - static void thermal_runaway_protection(tr_state_machine_t &state, const float ¤t, const float &target, const heater_id_t heater_id, const uint16_t period_seconds, const uint16_t hysteresis_degc); + static tr_state_machine_t tr_state_machine[NR_HEATER_RUNAWAY]; #endif // HAS_THERMAL_PROTECTION }; From cd85fa3abecd1a24de0fdbdb21a0ed2a2074af91 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 11 Sep 2020 23:05:27 -0500 Subject: [PATCH 11/44] Better choice of code Followup to #19344 --- .../gcode/calibrate/{G76_M871-M872.cpp => G76_M192_M871.cpp} | 4 ++-- Marlin/src/gcode/gcode.cpp | 2 +- Marlin/src/gcode/gcode.h | 4 ++-- 3 files changed, 5 insertions(+), 5 deletions(-) rename Marlin/src/gcode/calibrate/{G76_M871-M872.cpp => G76_M192_M871.cpp} (99%) diff --git a/Marlin/src/gcode/calibrate/G76_M871-M872.cpp b/Marlin/src/gcode/calibrate/G76_M192_M871.cpp similarity index 99% rename from Marlin/src/gcode/calibrate/G76_M871-M872.cpp rename to Marlin/src/gcode/calibrate/G76_M192_M871.cpp index 4f7c2874b17f..89393b4582c1 100644 --- a/Marlin/src/gcode/calibrate/G76_M871-M872.cpp +++ b/Marlin/src/gcode/calibrate/G76_M192_M871.cpp @@ -334,13 +334,13 @@ void GcodeSuite::M871() { } /** - * M872: Wait for probe temperature sensor to reach a target + * M192: Wait for probe temperature sensor to reach a target * * Select only one of these flags: * R - Wait for heating or cooling * S - Wait only for heating */ -void GcodeSuite::M872() { +void GcodeSuite::M192() { if (DEBUGGING(DRYRUN)) return; const bool no_wait_for_cooling = parser.seenval('S'); diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index bace7adc7501..c1b6deeadda8 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -818,8 +818,8 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { #endif #if ENABLED(PROBE_TEMP_COMPENSATION) + case 192: M192(); break; // M192: Wait for probe temp case 871: M871(); break; // M871: Print/reset/clear first layer temperature offset values - case 872: M872(); break; // M872: Wait for probe temp #endif #if ENABLED(LIN_ADVANCE) diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index 72a2d0966f22..24273012629f 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -253,7 +253,7 @@ * M868 - Report or set position encoder module error correction threshold. * M869 - Report position encoder module error. * M871 - Print/reset/clear first layer temperature offset values. (Requires PROBE_TEMP_COMPENSATION) - * M872 - Wait for probe temp (Requires PROBE_TEMP_COMPENSATION) + * M192 - Wait for probe temp (Requires PROBE_TEMP_COMPENSATION) * M876 - Handle Prompt Response. (Requires HOST_PROMPT_SUPPORT and not EMERGENCY_PARSER) * M900 - Get or Set Linear Advance K-factor. (Requires LIN_ADVANCE) * M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given. (Requires at least one _DRIVER_TYPE defined as TMC2130/2160/5130/5160/2208/2209/2660 or L6470) @@ -822,8 +822,8 @@ class GcodeSuite { #endif #if ENABLED(PROBE_TEMP_COMPENSATION) + static void M192(); static void M871(); - static void M872(); #endif TERN_(LIN_ADVANCE, static void M900()); From 3a89d34e7f2b69ad59246e80a66c375f862e984f Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 10 Sep 2020 20:44:13 -0500 Subject: [PATCH 12/44] Always show Compiled: --- Marlin/src/MarlinCore.cpp | 12 ++++-------- Marlin/src/core/language.h | 2 -- 2 files changed, 4 insertions(+), 10 deletions(-) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 89791c90820b..2927a3e40b28 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -977,18 +977,14 @@ void setup() { SERIAL_CHAR(' '); SERIAL_ECHOLNPGM(SHORT_BUILD_VERSION); SERIAL_EOL(); - #if defined(STRING_DISTRIBUTION_DATE) && defined(STRING_CONFIG_H_AUTHOR) SERIAL_ECHO_MSG( - STR_CONFIGURATION_VER - STRING_DISTRIBUTION_DATE - STR_AUTHOR STRING_CONFIG_H_AUTHOR + " Last Updated: " STRING_DISTRIBUTION_DATE + " | Author: " STRING_CONFIG_H_AUTHOR ); - SERIAL_ECHO_MSG("Compiled: " __DATE__); #endif - - SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR(STR_FREE_MEMORY, freeMemory(), STR_PLANNER_BUFFER_BYTES, (int)sizeof(block_t) * (BLOCK_BUFFER_SIZE)); + SERIAL_ECHO_MSG("Compiled: " __DATE__); + SERIAL_ECHO_MSG(STR_FREE_MEMORY, freeMemory(), STR_PLANNER_BUFFER_BYTES, (int)sizeof(block_t) * (BLOCK_BUFFER_SIZE)); // Set up LEDs early #if HAS_COLOR_LEDS diff --git a/Marlin/src/core/language.h b/Marlin/src/core/language.h index 1d81ee61fb6d..0f932f9d3ff0 100644 --- a/Marlin/src/core/language.h +++ b/Marlin/src/core/language.h @@ -108,8 +108,6 @@ #define STR_BROWNOUT_RESET " Brown out Reset" #define STR_WATCHDOG_RESET " Watchdog Reset" #define STR_SOFTWARE_RESET " Software Reset" -#define STR_AUTHOR " | Author: " -#define STR_CONFIGURATION_VER " Last Updated: " #define STR_FREE_MEMORY " Free Memory: " #define STR_PLANNER_BUFFER_BYTES " PlannerBufferBytes: " #define STR_OK "ok" From 0473f7ee5831691c372970c2d33cbf947f5e5612 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 10 Sep 2020 22:02:18 -0500 Subject: [PATCH 13/44] M115 strings --- Marlin/src/core/language.h | 1 - Marlin/src/gcode/host/M115.cpp | 12 ++++++++++-- 2 files changed, 10 insertions(+), 3 deletions(-) diff --git a/Marlin/src/core/language.h b/Marlin/src/core/language.h index 0f932f9d3ff0..0bcf799ac31d 100644 --- a/Marlin/src/core/language.h +++ b/Marlin/src/core/language.h @@ -125,7 +125,6 @@ #define STR_INVALID_E_STEPPER "Invalid E stepper" #define STR_E_STEPPER_NOT_SPECIFIED "E stepper not specified" #define STR_INVALID_SOLENOID "Invalid solenoid" -#define STR_M115_REPORT "FIRMWARE_NAME:Marlin " DETAILED_BUILD_VERSION " (" __DATE__ " " __TIME__ ") SOURCE_CODE_URL:" SOURCE_CODE_URL " PROTOCOL_VERSION:" PROTOCOL_VERSION " MACHINE_TYPE:" MACHINE_NAME " EXTRUDER_COUNT:" STRINGIFY(EXTRUDERS) " UUID:" MACHINE_UUID #define STR_COUNT_X " Count X:" #define STR_COUNT_A " Count A:" #define STR_WATCHDOG_FIRED "Watchdog timeout. Reset required." diff --git a/Marlin/src/gcode/host/M115.cpp b/Marlin/src/gcode/host/M115.cpp index cd64c563f9fb..53c5163bbaf6 100644 --- a/Marlin/src/gcode/host/M115.cpp +++ b/Marlin/src/gcode/host/M115.cpp @@ -42,8 +42,16 @@ * the capability is not present. */ void GcodeSuite::M115() { - - SERIAL_ECHOLNPGM(STR_M115_REPORT); + SERIAL_ECHOLNPGM( + "FIRMWARE_NAME:Marlin " DETAILED_BUILD_VERSION " (" __DATE__ " " __TIME__ ") " + "SOURCE_CODE_URL:" SOURCE_CODE_URL " " + "PROTOCOL_VERSION:" PROTOCOL_VERSION " " + "MACHINE_TYPE:" MACHINE_NAME " " + "EXTRUDER_COUNT:" STRINGIFY(EXTRUDERS) " " + #ifdef MACHINE_UUID + "UUID:" MACHINE_UUID + #endif + ); #if ENABLED(EXTENDED_CAPABILITIES_REPORT) From 0f9eb480aa7309e6b876e2643cd26a9425f5fd88 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 14 Sep 2020 02:48:45 -0500 Subject: [PATCH 14/44] Allow E3 V2 DWIN without EEPROM, POWER_LOSS_RECOVERY --- Marlin/src/lcd/dwin/e3v2/dwin.cpp | 310 ++++++++++++++++-------------- Marlin/src/lcd/dwin/e3v2/dwin.h | 2 +- Marlin/src/lcd/extui/ui_api.cpp | 2 +- 3 files changed, 165 insertions(+), 149 deletions(-) diff --git a/Marlin/src/lcd/dwin/e3v2/dwin.cpp b/Marlin/src/lcd/dwin/e3v2/dwin.cpp index 8aa908e423fd..ccd5f2bc2055 100644 --- a/Marlin/src/lcd/dwin/e3v2/dwin.cpp +++ b/Marlin/src/lcd/dwin/e3v2/dwin.cpp @@ -48,15 +48,17 @@ #include "../../../core/macros.h" #include "../../../gcode/queue.h" -#include "../../../feature/powerloss.h" #include "../../../feature/babystep.h" -#include "../../../module/settings.h" #include "../../../module/temperature.h" #include "../../../module/printcounter.h" #include "../../../module/motion.h" #include "../../../module/planner.h" +#if ENABLED(EEPROM_SETTINGS) + #include "../../../module/settings.h" +#endif + #if ENABLED(HOST_ACTION_COMMANDS) #include "../../../feature/host_actions.h" #endif @@ -69,6 +71,10 @@ #include "../../../module/probe.h" #endif +#if ENABLED(POWER_LOSS_RECOVERY) + #include "../../../feature/powerloss.h" +#endif + #ifndef MACHINE_SIZE #define MACHINE_SIZE "220x220x250" #endif @@ -130,7 +136,7 @@ constexpr uint16_t TROWS = 6, MROWS = TROWS - 1, // Total rows, and other #define MBASE(L) (49 + (L)*MLINE) -#define BABY_Z_VAR TERN(HAS_BED_PROBE, probe.offset.z, zprobe_zoffset) +#define BABY_Z_VAR TERN(HAS_BED_PROBE, probe.offset.z, dwin_zoffset) /* Value Init */ HMI_value_t HMI_ValueStruct; @@ -188,8 +194,8 @@ float last_E_scale = 0; bool DWIN_lcd_sd_status = 0; bool pause_action_flag = 0; int temphot = 0, tempbed = 0; -float zprobe_zoffset = 0; -float last_zoffset = 0, last_probe_zoffset = 0; +float dwin_zoffset = 0; +float last_zoffset = 0; #define DWIN_LANGUAGE_EEPROM_ADDRESS 0x01 // Between 0x01 and 0x63 (EEPROM_OFFSET-1) // BL24CXX::check() uses 0x00 @@ -213,7 +219,7 @@ void HMI_SetAndSaveLanguageChinese(void) { BL24CXX::write(DWIN_LANGUAGE_EEPROM_ADDRESS, (uint8_t*)&HMI_flag.language_chinese, sizeof(HMI_flag.language_chinese)); } -void show_plus_or_minus(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, long value) { if (value < 0) { DWIN_Draw_String(false, true, size, White, bColor, x - 6, y, F("-")); DWIN_Draw_FloatValue(true, true, 0, size, White, bColor, iNum, fNum, x, y, -value); @@ -517,7 +523,7 @@ inline void Prepare_Item_Offset(const uint8_t row) { if (HMI_flag.language_chinese) { #if HAS_BED_PROBE DWIN_Frame_AreaCopy(1, 174, 164, 271 - 48, 479 - 302, LBLX, MBASE(row)); - show_plus_or_minus(font8x16, Background_black, 2, 2, 202, MBASE(row), probe.offset.z * 100); + DWIN_Draw_Signed_Float(font8x16, Background_black, 2, 2, 202, MBASE(row), probe.offset.z * 100); #else DWIN_Frame_AreaCopy(1, 43, 89, 271 - 173, 479 - 378, LBLX, MBASE(row)); #endif @@ -525,7 +531,7 @@ inline void Prepare_Item_Offset(const uint8_t row) { else { #if HAS_BED_PROBE DWIN_Frame_AreaCopy(1, 93, 179, 271 - 130, 479 - 290, LBLX, MBASE(row)); // "Z-Offset" - show_plus_or_minus(font8x16, Background_black, 2, 2, 202, MBASE(row), probe.offset.z * 100); + DWIN_Draw_Signed_Float(font8x16, Background_black, 2, 2, 202, MBASE(row), probe.offset.z * 100); #else DWIN_Frame_AreaCopy(1, 1, 76, 271 - 165, 479 - 393, LBLX, MBASE(row)); // "..." #endif @@ -633,22 +639,28 @@ inline void Draw_Control_Menu() { Draw_Title(GET_TEXT_F(MSG_CONTROL)); DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 0), GET_TEXT_F(MSG_TEMPERATURE)); DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 1), GET_TEXT_F(MSG_MOTION)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 2), GET_TEXT_F(MSG_STORE_EEPROM)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 3), GET_TEXT_F(MSG_LOAD_EEPROM)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 4), GET_TEXT_F(MSG_RESTORE_DEFAULTS)); - if (CVISI(6)) - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 5), F("Info")); + #if ENABLED(EEPROM_SETTINGS) + DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 2), GET_TEXT_F(MSG_STORE_EEPROM)); + DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 3), GET_TEXT_F(MSG_LOAD_EEPROM)); + DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 4), GET_TEXT_F(MSG_RESTORE_DEFAULTS)); + if (CVISI(6)) DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 5), F("Info")); + #else + if (CVISI(3)) DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 2), F("Info")); + #endif #else DWIN_Frame_AreaCopy(1, 128, 2, 271 - 95, 479 - 467, 14, 8); DWIN_Frame_AreaCopy(1, 1, 89, 271 - 188, 479 - 377 - 1, LBLX, CLINE(1));// Temperature > DWIN_Frame_AreaCopy(1, 84, 89, 271 - 143, 479 - 380, LBLX, CLINE(2));// Motion > - DWIN_Frame_AreaCopy(1, 131 + 17, 89, 271 - 3, 479 - 377 - 1, LBLX, CLINE(3));// "Store Configuration" - DWIN_Frame_AreaCopy(1, 26, 104, 271 - 214, 479 - 365, LBLX, CLINE(4)); // "Read" - DWIN_Frame_AreaCopy(1, 131 + 51, 89, 271 - 3, 479 - 377 - 1, LBLX + 31 + 3, CLINE(4)); // "Configuration" - DWIN_Frame_AreaCopy(1, 59, 104, 271 - 178, 479 - 365, LBLX, CLINE(5)); // "Reset" - DWIN_Frame_AreaCopy(1, 131 + 51, 89, 271 - 3, 479 - 377 - 1, LBLX + 34 + 3, CLINE(5)); // "Configuration" - if (CVISI(6)) - DWIN_Frame_AreaCopy(1, 0, 104, 25, 115, LBLX, CLINE(6)); // Info > + #if ENABLED(EEPROM_SETTINGS) + DWIN_Frame_AreaCopy(1, 131 + 17, 89, 271 - 3, 479 - 377 - 1, LBLX, CLINE(3));// "Store Configuration" + DWIN_Frame_AreaCopy(1, 26, 104, 271 - 214, 479 - 365, LBLX, CLINE(4)); // "Read" + DWIN_Frame_AreaCopy(1, 131 + 51, 89, 271 - 3, 479 - 377 - 1, LBLX + 31 + 3, CLINE(4)); // "Configuration" + DWIN_Frame_AreaCopy(1, 59, 104, 271 - 178, 479 - 365, LBLX, CLINE(5)); // "Reset" + DWIN_Frame_AreaCopy(1, 131 + 51, 89, 271 - 3, 479 - 377 - 1, LBLX + 34 + 3, CLINE(5)); // "Configuration" + if (CVISI(6)) DWIN_Frame_AreaCopy(1, 0, 104, 25, 115, LBLX, CLINE(6)); // Info > + #else + if (CVISI(3)) DWIN_Frame_AreaCopy(1, 0, 104, 25, 115, LBLX, CLINE(3)); // Info > + #endif #endif } @@ -708,7 +720,7 @@ inline void Draw_Tune_Menu() { DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(2), thermalManager.temp_hotend[0].target); DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(3), thermalManager.temp_bed.target); DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(4), thermalManager.fan_speed[0]); - show_plus_or_minus(font8x16, Background_black, 2, 2, 202, MBASE(5), BABY_Z_VAR * 100); + DWIN_Draw_Signed_Float(font8x16, Background_black, 2, 2, 202, MBASE(5), BABY_Z_VAR * 100); } inline void draw_max_en(const uint16_t line) { @@ -1102,7 +1114,7 @@ void HMI_Move_Z(void) { checkkey = AxisMove; EncoderRate.encoderRateEnabled = 0; last_E_scale = HMI_ValueStruct.Move_E_scale; - show_plus_or_minus(font8x16, Background_black, 3, 1, 216, MBASE(4), HMI_ValueStruct.Move_E_scale); + DWIN_Draw_Signed_Float(font8x16, Background_black, 3, 1, 216, MBASE(4), HMI_ValueStruct.Move_E_scale); if (!planner.is_full()) { planner.synchronize(); // Wait for planner moves to finish! planner.buffer_line(current_position, MMM_TO_MMS(FEEDRATE_E), active_extruder); @@ -1115,7 +1127,7 @@ void HMI_Move_Z(void) { else if ((last_E_scale - HMI_ValueStruct.Move_E_scale) > (EXTRUDE_MAXLENGTH) * MINUNITMULT) HMI_ValueStruct.Move_E_scale = last_E_scale - (EXTRUDE_MAXLENGTH) * MINUNITMULT; current_position.e = HMI_ValueStruct.Move_E_scale / 10; - show_plus_or_minus(font8x16, Select_Color, 3, 1, 216, MBASE(4), HMI_ValueStruct.Move_E_scale); + DWIN_Draw_Signed_Float(font8x16, Select_Color, 3, 1, 216, MBASE(4), HMI_ValueStruct.Move_E_scale); DWIN_UpdateLCD(); } } @@ -1125,7 +1137,7 @@ void HMI_Move_Z(void) { void HMI_Zoffset(void) { ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); if (encoder_diffState != ENCODER_DIFF_NO) { - last_zoffset = zprobe_zoffset; + last_zoffset = dwin_zoffset; if (encoder_diffState == ENCODER_DIFF_CW) { HMI_ValueStruct.offset_value += EncoderRate.encoderMoveValue; } @@ -1134,24 +1146,22 @@ void HMI_Zoffset(void) { } else if (encoder_diffState == ENCODER_DIFF_ENTER) { EncoderRate.encoderRateEnabled = 0; - zprobe_zoffset = HMI_ValueStruct.offset_value / 100; + dwin_zoffset = HMI_ValueStruct.offset_value / 100; #if HAS_BED_PROBE - if (WITHIN(zprobe_zoffset - last_zoffset, Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX)) - probe.offset.z = zprobe_zoffset; - settings.save(); + if (WITHIN(dwin_zoffset - last_zoffset, Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX)) + probe.offset.z = dwin_zoffset; + TERN_(EEPROM_SETTINGS, settings.save()); #elif ENABLED(BABYSTEPPING) - babystep.add_mm(Z_AXIS, (zprobe_zoffset - last_zoffset)); - #else - UNUSED(zprobe_zoffset - last_zoffset); + babystep.add_mm(Z_AXIS, dwin_zoffset - last_zoffset); #endif if (HMI_ValueStruct.show_mode == -4) { checkkey = Prepare; - show_plus_or_minus(font8x16, Background_black, 2, 2, 202, MBASE(4 + MROWS - index_prepare), TERN(HAS_BED_PROBE, probe.offset.z * 100, HMI_ValueStruct.offset_value)); + DWIN_Draw_Signed_Float(font8x16, Background_black, 2, 2, 202, MBASE(4 + MROWS - index_prepare), TERN(HAS_BED_PROBE, probe.offset.z * 100, HMI_ValueStruct.offset_value)); } else { checkkey = Tune; - show_plus_or_minus(font8x16, Background_black, 2, 2, 202, MBASE(5 + MROWS - index_tune), TERN(HAS_BED_PROBE, probe.offset.z * 100, HMI_ValueStruct.offset_value)); + DWIN_Draw_Signed_Float(font8x16, Background_black, 2, 2, 202, MBASE(5 + MROWS - index_tune), TERN(HAS_BED_PROBE, probe.offset.z * 100, HMI_ValueStruct.offset_value)); } DWIN_UpdateLCD(); return; @@ -1159,9 +1169,9 @@ void HMI_Zoffset(void) { NOLESS(HMI_ValueStruct.offset_value, (Z_PROBE_OFFSET_RANGE_MIN) * 100); NOMORE(HMI_ValueStruct.offset_value, (Z_PROBE_OFFSET_RANGE_MAX) * 100); if (HMI_ValueStruct.show_mode == -4) - show_plus_or_minus(font8x16, Select_Color, 2, 2, 202, MBASE(4 + MROWS - index_prepare), HMI_ValueStruct.offset_value); + DWIN_Draw_Signed_Float(font8x16, Select_Color, 2, 2, 202, MBASE(4 + MROWS - index_prepare), HMI_ValueStruct.offset_value); else - show_plus_or_minus(font8x16, Select_Color, 2, 2, 202, MBASE(5 + MROWS - index_tune), HMI_ValueStruct.offset_value); + DWIN_Draw_Signed_Float(font8x16, Select_Color, 2, 2, 202, MBASE(5 + MROWS - index_tune), HMI_ValueStruct.offset_value); DWIN_UpdateLCD(); } } @@ -1213,7 +1223,7 @@ void HMI_Zoffset(void) { } } -#endif // if HAS_HOTEND +#endif // HAS_HOTEND #if HAS_HEATED_BED @@ -1262,7 +1272,7 @@ void HMI_Zoffset(void) { } } -#endif // if HAS_HEATED_BED +#endif // HAS_HEATED_BED #if HAS_FAN @@ -1311,7 +1321,7 @@ void HMI_Zoffset(void) { } } -#endif // if HAS_FAN +#endif // HAS_FAN void HMI_PrintSpeed(void) { ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); @@ -1515,27 +1525,20 @@ void update_variable(void) { DWIN_Draw_IntValue(true, true, 0, STAT_FONT, White, Background_black, 3, 33 + 2 * STAT_CHR_W, 429, feedrate_percentage); last_speed = feedrate_percentage; } - #if HAS_BED_PROBE - if (last_probe_zoffset != probe.offset.z) { - show_plus_or_minus(STAT_FONT, Background_black, 2, 2, 178 + STAT_CHR_W, 429, probe.offset.z * 100); - last_probe_zoffset = probe.offset.z; - } - #else - if (last_zoffset != zprobe_zoffset) { - show_plus_or_minus(STAT_FONT, Background_black, 2, 2, 178 + STAT_CHR_W, 429, zprobe_zoffset * 100); - last_zoffset = zprobe_zoffset; - } - #endif + if (last_zoffset != BABY_Z_VAR) { + DWIN_Draw_Signed_Float(STAT_FONT, Background_black, 2, 2, 178 + STAT_CHR_W, 429, BABY_Z_VAR * 100); + last_zoffset = BABY_Z_VAR; + } } /** -* 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. -* -*/ + * 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)) @@ -1723,7 +1726,7 @@ void HMI_StartFrame(const bool with_update) { DWIN_Draw_IntValue(true, true, 0, STAT_FONT, White, Background_black, 3, 33 + 2 * STAT_CHR_W, 429, feedrate_percentage); DWIN_Draw_String(false, false, STAT_FONT, White, Background_black, 33 + (2 + 3) * STAT_CHR_W + 2, 429, F("%")); - show_plus_or_minus(STAT_FONT, Background_black, 2, 2, 178, 429, BABY_Z_VAR * 100); + DWIN_Draw_Signed_Float(STAT_FONT, Background_black, 2, 2, 178, 429, BABY_Z_VAR * 100); DWIN_Draw_String(false, false, STAT_FONT, White, Background_black, 33 + 3 * STAT_CHR_W + 5, 383, F("/")); DWIN_Draw_String(false, false, STAT_FONT, White, Background_black, 178 + 3 * STAT_CHR_W + 5, 383, F("/")); @@ -2223,7 +2226,7 @@ void HMI_Prepare(void) { DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 216, MBASE(1), current_position[X_AXIS] * MINUNITMULT); DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 216, MBASE(2), current_position[Y_AXIS] * MINUNITMULT); DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 216, MBASE(3), current_position[Z_AXIS] * MINUNITMULT); - show_plus_or_minus(font8x16, Background_black, 3, 1, 216, MBASE(4), current_position.e * MINUNITMULT); + DWIN_Draw_Signed_Float(font8x16, Background_black, 3, 1, 216, MBASE(4), current_position.e * MINUNITMULT); break; case 2: // close motion queue.inject_P(PSTR("M84")); @@ -2237,9 +2240,9 @@ void HMI_Prepare(void) { case 4: // Z-offset #if HAS_BED_PROBE checkkey = Homeoffset; - HMI_ValueStruct.show_mode = -4; + HMI_ValueStruct.show_mode = -4; HMI_ValueStruct.offset_value = probe.offset.z * 100; - show_plus_or_minus(font8x16, Select_Color, 2, 2, 202, MBASE(4 + MROWS - index_prepare), HMI_ValueStruct.offset_value); + DWIN_Draw_Signed_Float(font8x16, Select_Color, 2, 2, 202, MBASE(4 + MROWS - index_prepare), HMI_ValueStruct.offset_value); EncoderRate.encoderRateEnabled = 1; #else // Apply workspace offset, making the current position 0,0,0 @@ -2392,19 +2395,22 @@ void HMI_Control(void) { select_motion.reset(); Draw_Motion_Menu(); break; - case 3: { // write EEPROM - const bool success = settings.save(); - HMI_AudioFeedback(success); - } break; - case 4: { // read EEPROM - const bool success = settings.load(); - HMI_AudioFeedback(success); - } break; - case 5: // resume EEPROM - settings.reset(); - HMI_AudioFeedback(); - break; - case 6: // info + case 3: + #if ENABLED(EEPROM_SETTINGS) + { // write EEPROM + const bool success = settings.save(); + HMI_AudioFeedback(success); + } break; + case 4: { // read EEPROM + const bool success = settings.load(); + HMI_AudioFeedback(success); + } break; + case 5: // resume EEPROM + settings.reset(); + HMI_AudioFeedback(); + break; + case 6: // info + #endif checkkey = Info; Draw_Info_Menu(); break; @@ -2442,7 +2448,7 @@ void HMI_AxisMove(void) { DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 216, MBASE(1), HMI_ValueStruct.Move_X_scale); DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 216, MBASE(2), HMI_ValueStruct.Move_Y_scale); DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 216, MBASE(3), HMI_ValueStruct.Move_Z_scale); - show_plus_or_minus(font8x16, Background_black, 3, 1, 216, MBASE(4), HMI_ValueStruct.Move_E_scale); + DWIN_Draw_Signed_Float(font8x16, Background_black, 3, 1, 216, MBASE(4), HMI_ValueStruct.Move_E_scale); DWIN_UpdateLCD(); } return; @@ -2495,7 +2501,7 @@ void HMI_AxisMove(void) { #endif checkkey = Extruder; HMI_ValueStruct.Move_E_scale = current_position.e * MINUNITMULT; - show_plus_or_minus(font8x16, Select_Color, 3, 1, 216, MBASE(4), HMI_ValueStruct.Move_E_scale); + DWIN_Draw_Signed_Float(font8x16, Select_Color, 3, 1, 216, MBASE(4), HMI_ValueStruct.Move_E_scale); EncoderRate.encoderRateEnabled = 1; break; #endif @@ -2593,7 +2599,9 @@ void HMI_Temperature(void) { Draw_Menu_Line(1, ICON_SetEndTemp); Draw_Menu_Line(2, ICON_SetBedTemp); Draw_Menu_Line(3, ICON_FanSpeed); - Draw_Menu_Line(4, ICON_WriteEEPROM); + #if ENABLED(EEPROM_SETTINGS) + Draw_Menu_Line(4, ICON_WriteEEPROM); + #endif DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(1), ui.material_preset[0].hotend_temp); DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(2), ui.material_preset[0].bed_temp); @@ -2647,14 +2655,16 @@ void HMI_Temperature(void) { Draw_Menu_Line(1, ICON_SetEndTemp); Draw_Menu_Line(2, ICON_SetBedTemp); Draw_Menu_Line(3, ICON_FanSpeed); - Draw_Menu_Line(4, ICON_WriteEEPROM); + #if ENABLED(EEPROM_SETTINGS) + Draw_Menu_Line(4, ICON_WriteEEPROM); + #endif DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(1), ui.material_preset[1].hotend_temp); DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(2), ui.material_preset[1].bed_temp); DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(3), ui.material_preset[1].fan_speed); break; - #endif // if HAS_HOTEND + #endif // HAS_HOTEND } } DWIN_UpdateLCD(); @@ -2996,7 +3006,7 @@ void HMI_Tune(void) { case 5: // Z-offset checkkey = Homeoffset; HMI_ValueStruct.offset_value = BABY_Z_VAR * 100; - show_plus_or_minus(font8x16, Select_Color, 2, 2, 202, MBASE(5 + MROWS - index_tune), HMI_ValueStruct.offset_value); + DWIN_Draw_Signed_Float(font8x16, Select_Color, 2, 2, 202, MBASE(5 + MROWS - index_tune), HMI_ValueStruct.offset_value); EncoderRate.encoderRateEnabled = 1; break; case 6: // Language @@ -3067,10 +3077,12 @@ void HMI_PLAPreheatSetting(void) { EncoderRate.encoderRateEnabled = 1; break; #endif - case 4: { // save PLA configuration - const bool success = settings.save(); - HMI_AudioFeedback(success); - } break; + #if ENABLED(EEPROM_SETTINGS) + case 4: { // save PLA configuration + const bool success = settings.save(); + HMI_AudioFeedback(success); + } break; + #endif default: break; } } @@ -3121,10 +3133,12 @@ void HMI_ABSPreheatSetting(void) { EncoderRate.encoderRateEnabled = 1; break; #endif - case 4: { // save ABS configuration - const bool success = settings.save(); - HMI_AudioFeedback(success); - } break; + #if ENABLED(EEPROM_SETTINGS) + case 4: { // save ABS configuration + const bool success = settings.save(); + HMI_AudioFeedback(success); + } break; + #endif default: break; } @@ -3441,7 +3455,7 @@ void EachMomentUpdate(void) { else if (abort_flag && !HMI_flag.home_flag) { // Print Stop abort_flag = 0; HMI_ValueStruct.print_speed = feedrate_percentage = 100; - zprobe_zoffset = TERN(HAS_BED_PROBE, probe.offset.z, 0); + dwin_zoffset = TERN0(HAS_BED_PROBE, probe.offset.z); planner.finish_and_disable(); @@ -3452,70 +3466,72 @@ void EachMomentUpdate(void) { select_page.set(0); Goto_MainMenu(); } - else if (DWIN_lcd_sd_status && recovery.dwin_flag) { // resume print before power off - recovery.dwin_flag = false; - - recovery.load(); - if (!recovery.valid()) return recovery.purge(); - - auto draw_first_option = [](const bool sel) { - const uint16_t c1 = sel ? Background_window : Select_Color; - DWIN_Draw_Rectangle(0, c1, 25, 306, 126, 345); - DWIN_Draw_Rectangle(0, c1, 24, 305, 127, 346); - }; - - auto update_selection = [&](const bool sel) { - HMI_flag.select_flag = sel; - draw_first_option(sel); - const uint16_t c2 = sel ? Select_Color : Background_window; - DWIN_Draw_Rectangle(0, c2, 145, 306, 246, 345); - DWIN_Draw_Rectangle(0, c2, 144, 305, 247, 346); - }; - - const uint16_t fileCnt = card.get_num_Files(); - for (uint16_t i = 0; i < fileCnt; i++) { - // TODO: Resume print via M1000 then update the UI - // with the active filename which can come from CardReader. - card.getfilename_sorted(SD_ORDER(i, fileCnt)); - if (!strcmp(card.filename, &recovery.info.sd_filename[1])) { // Resume print before power failure while have the same file - recovery_flag = 1; - HMI_flag.select_flag = 1; - Popup_Window_Resume(); - draw_first_option(false); - char * const name = card.longest_filename(); - const int8_t npos = _MAX(0, DWIN_WIDTH - strlen(name) * (MENU_CHR_W)) / 2; - DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, npos, 252, name); - DWIN_UpdateLCD(); - break; + #if ENABLED(POWER_LOSS_RECOVERY) + else if (DWIN_lcd_sd_status && recovery.dwin_flag) { // resume print before power off + recovery.dwin_flag = false; + + recovery.load(); + if (!recovery.valid()) return recovery.purge(); + + auto draw_first_option = [](const bool sel) { + const uint16_t c1 = sel ? Background_window : Select_Color; + DWIN_Draw_Rectangle(0, c1, 25, 306, 126, 345); + DWIN_Draw_Rectangle(0, c1, 24, 305, 127, 346); + }; + + auto update_selection = [&](const bool sel) { + HMI_flag.select_flag = sel; + draw_first_option(sel); + const uint16_t c2 = sel ? Select_Color : Background_window; + DWIN_Draw_Rectangle(0, c2, 145, 306, 246, 345); + DWIN_Draw_Rectangle(0, c2, 144, 305, 247, 346); + }; + + const uint16_t fileCnt = card.get_num_Files(); + for (uint16_t i = 0; i < fileCnt; i++) { + // TODO: Resume print via M1000 then update the UI + // with the active filename which can come from CardReader. + card.getfilename_sorted(SD_ORDER(i, fileCnt)); + if (!strcmp(card.filename, &recovery.info.sd_filename[1])) { // Resume print before power failure while have the same file + recovery_flag = 1; + HMI_flag.select_flag = 1; + Popup_Window_Resume(); + draw_first_option(false); + char * const name = card.longest_filename(); + const int8_t npos = _MAX(0, DWIN_WIDTH - strlen(name) * (MENU_CHR_W)) / 2; + DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, npos, 252, name); + DWIN_UpdateLCD(); + break; + } } - } - // if hasn't resumable G-code file - if (!recovery_flag) return; + // if hasn't resumable G-code file + if (!recovery_flag) return; + + while (recovery_flag) { + ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState != ENCODER_DIFF_NO) { + if (encoder_diffState == ENCODER_DIFF_ENTER) { + recovery_flag = 0; + if (HMI_flag.select_flag) break; + TERN_(POWER_LOSS_RECOVERY, recovery.cancel()); + HMI_StartFrame(true); + return; + } + else + update_selection(encoder_diffState == ENCODER_DIFF_CCW); - while (recovery_flag) { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - if (encoder_diffState == ENCODER_DIFF_ENTER) { - recovery_flag = 0; - if (HMI_flag.select_flag) break; - TERN_(POWER_LOSS_RECOVERY, recovery.cancel()); - HMI_StartFrame(true); - return; + DWIN_UpdateLCD(); } - else - update_selection(encoder_diffState == ENCODER_DIFF_CCW); - - DWIN_UpdateLCD(); } - } - select_print.set(0); - HMI_ValueStruct.show_mode = 0; - HMI_StartFrame(false); - recovery.resume(); - return; - } + select_print.set(0); + HMI_ValueStruct.show_mode = 0; + HMI_StartFrame(false); + recovery.resume(); + return; + } + #endif DWIN_UpdateLCD(); } @@ -3572,7 +3588,7 @@ void DWIN_CompletedHoming(void) { } else if (checkkey == Back_Main) { HMI_ValueStruct.print_speed = feedrate_percentage = 100; - zprobe_zoffset = TERN0(BLTOUCH, probe.offset.z); + dwin_zoffset = TERN0(HAS_BED_PROBE, probe.offset.z); planner.finish_and_disable(); Goto_MainMenu(); } diff --git a/Marlin/src/lcd/dwin/e3v2/dwin.h b/Marlin/src/lcd/dwin/e3v2/dwin.h index dffd40bd03fb..e5d95f61661c 100644 --- a/Marlin/src/lcd/dwin/e3v2/dwin.h +++ b/Marlin/src/lcd/dwin/e3v2/dwin.h @@ -318,7 +318,7 @@ void HMI_MaxCornerXYZE(void); void HMI_StepXYZE(void); void update_variable(void); -void show_plus_or_minus(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, long value); // SD Card void HMI_SDCardInit(void); diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index 4d65429bf1d2..1637d32877e4 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -759,7 +759,7 @@ namespace ExtUI { if (WITHIN(value, Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX)) probe.offset.z = value; #elif ENABLED(BABYSTEP_DISPLAY_TOTAL) - babystep.add_mm(Z_AXIS, (value - getZOffset_mm())); + babystep.add_mm(Z_AXIS, value - getZOffset_mm()); #else UNUSED(value); #endif From 941b8908818b1e2004f54ab6d7ecda50e2b17c77 Mon Sep 17 00:00:00 2001 From: Marcio T Date: Mon, 14 Sep 2020 02:25:20 -0600 Subject: [PATCH 15/44] Add missing FTDI EVE menu source (#19382) --- .../ftdi_eve_lib/extended/text_ellipsis.cpp | 4 +- .../lib/ftdi_eve_touch_ui/marlin_events.cpp | 4 +- .../screens/bio_status_screen.cpp | 2 +- .../screens/leveling_menu.cpp | 121 ++++++++++++++++++ .../screens/status_screen.cpp | 4 +- 5 files changed, 130 insertions(+), 5 deletions(-) create mode 100644 Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/leveling_menu.cpp diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.cpp index 3746f1cde0f5..266b6efdab1e 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.cpp @@ -30,12 +30,12 @@ namespace FTDI { */ 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 uint16_t ellipsisWidth = fm.get_char_width('.') * 3; + const int16_t ellipsisWidth = 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. - uint16_t lineWidth = 0; + int16_t lineWidth = 0; char *breakPoint = str; for(char* c = str; *c; c++) { lineWidth += fm.get_char_width(*c); diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/marlin_events.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/marlin_events.cpp index 270ec5581905..fe68faefee44 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/marlin_events.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/marlin_events.cpp @@ -61,7 +61,9 @@ namespace ExtUI { if (AT_SCREEN(StatusScreen) || isPrintingFromMedia()) StatusScreen::setStatusMessage(GET_TEXT_F(MSG_MEDIA_REMOVED)); - if (AT_SCREEN(FilesScreen)) GOTO_SCREEN(StatusScreen); + #if ENABLED(SDSUPPORT) + if (AT_SCREEN(FilesScreen)) GOTO_SCREEN(StatusScreen); + #endif } void onMediaError() { diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_status_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_status_screen.cpp index cfae53c7245c..e881995f2e69 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_status_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_status_screen.cpp @@ -304,7 +304,7 @@ void StatusScreen::draw_overlay_icons(draw_mode_t what) { PolyUI ui(cmd, what); if (what & FOREGROUND) { - ui.button_fill (TERN(TOUCH_UI_COCOA_PRESS, stroke_rgb, fill_rgb); + ui.button_fill (TERN(TOUCH_UI_COCOA_PRESS, stroke_rgb, fill_rgb)); ui.button_stroke(stroke_rgb, 28); ui.button_shadow(shadow_rgb, shadow_depth); diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/leveling_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/leveling_menu.cpp new file mode 100644 index 000000000000..2eab27c6086b --- /dev/null +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/leveling_menu.cpp @@ -0,0 +1,121 @@ +/********************* + * 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" + +#if BOTH(TOUCH_UI_FTDI_EVE,HAS_LEVELING) + +#include "screens.h" + +#if BOTH(HAS_BED_PROBE,BLTOUCH) + #include "../../../../../feature/bltouch.h" +#endif + +using namespace FTDI; +using namespace ExtUI; +using namespace Theme; + +#ifdef TOUCH_UI_PORTRAIT + #define GRID_ROWS 9 + #define GRID_COLS 2 + #define TITLE_POS BTN_POS(1,1), BTN_SIZE(2,1) + #define LEVEL_BED_POS BTN_POS(1,2), BTN_SIZE(2,1) + #define LEVEL_AXIS_POS BTN_POS(1,3), BTN_SIZE(2,1) + #define SHOW_MESH_POS BTN_POS(1,4), BTN_SIZE(2,1) + #define BLTOUCH_TITLE_POS BTN_POS(1,6), BTN_SIZE(2,1) + #define BLTOUCH_RESET_POS BTN_POS(1,7), BTN_SIZE(1,1) + #define BLTOUCH_TEST_POS BTN_POS(2,7), BTN_SIZE(1,1) + #define BACK_POS BTN_POS(1,9), BTN_SIZE(2,1) +#else + #define GRID_ROWS 7 + #define GRID_COLS 2 + #define TITLE_POS BTN_POS(1,1), BTN_SIZE(2,1) + #define LEVEL_BED_POS BTN_POS(1,2), BTN_SIZE(2,1) + #define LEVEL_AXIS_POS BTN_POS(1,3), BTN_SIZE(2,1) + #define SHOW_MESH_POS BTN_POS(1,4), BTN_SIZE(2,1) + #define BLTOUCH_TITLE_POS BTN_POS(1,5), BTN_SIZE(2,1) + #define BLTOUCH_RESET_POS BTN_POS(1,6), BTN_SIZE(1,1) + #define BLTOUCH_TEST_POS BTN_POS(2,6), BTN_SIZE(1,1) + #define BACK_POS BTN_POS(1,7), BTN_SIZE(2,1) +#endif + +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) + .text(TITLE_POS, GET_TEXT_F(MSG_LEVELING)) + .font(font_medium).colors(normal_btn) + .tag(2).button(LEVEL_BED_POS, GET_TEXT_F(MSG_LEVEL_BED)) + .enabled( + #ifdef AXIS_LEVELING_COMMANDS + 1 + #endif + ) + .tag(3).button(LEVEL_AXIS_POS, GET_TEXT_F(MSG_AUTOLEVEL_X_AXIS)) + .enabled(ENABLED(HAS_MESH)) + .tag(4).button(SHOW_MESH_POS, GET_TEXT_F(MSG_SHOW_MESH)); + #if ENABLED(BLTOUCH) + cmd.text(BLTOUCH_TITLE_POS, GET_TEXT_F(MSG_BLTOUCH)) + .tag(5).button(BLTOUCH_RESET_POS, GET_TEXT_F(MSG_BLTOUCH_RESET)) + .tag(6).button(BLTOUCH_TEST_POS, GET_TEXT_F(MSG_BLTOUCH_SELFTEST)); + #endif + cmd.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: + #ifndef BED_LEVELING_COMMANDS + #define BED_LEVELING_COMMANDS "G29" + #endif + #if HAS_MESH + BedMeshScreen::startMeshProbe(); + #else + SpinnerDialogBox::enqueueAndWait_P(F(BED_LEVELING_COMMANDS)); + #endif + break; + #ifdef AXIS_LEVELING_COMMANDS + case 3: SpinnerDialogBox::enqueueAndWait_P(F(AXIS_LEVELING_COMMANDS)); break; + #endif + #if HAS_MESH + case 4: GOTO_SCREEN(BedMeshScreen); break; + #endif + #if ENABLED(BLTOUCH) + case 5: injectCommands_P(PSTR("M280 P0 S60")); break; + case 6: SpinnerDialogBox::enqueueAndWait_P(F("M280 P0 S90\nG4 P100\nM280 P0 S120")); break; + #endif + default: return false; + } + return true; +} + +#endif // BOTH(TOUCH_UI_FTDI_EVE,HAS_LEVELING) diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/status_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/status_screen.cpp index f2524c7982f1..6b258b53893b 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/status_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/status_screen.cpp @@ -376,7 +376,9 @@ bool StatusScreen::onTouchEnd(uint8_t tag) { using namespace ExtUI; switch (tag) { - case 3: GOTO_SCREEN(FilesScreen); break; + #if ENABLED(SDSUPPORT) + case 3: GOTO_SCREEN(FilesScreen); break; + #endif case 4: if (isPrinting()) { GOTO_SCREEN(TuneMenu); From 648e7f73a528783b31014cf4719009b0d69deff4 Mon Sep 17 00:00:00 2001 From: Zachary Annand Date: Mon, 14 Sep 2020 03:28:21 -0500 Subject: [PATCH 16/44] More strict STATIC_ITEM_N (#19378) --- Marlin/src/lcd/menu/menu_item.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/lcd/menu/menu_item.h b/Marlin/src/lcd/menu/menu_item.h index a92f917f9f38..755135d14dec 100644 --- a/Marlin/src/lcd/menu/menu_item.h +++ b/Marlin/src/lcd/menu/menu_item.h @@ -342,8 +342,8 @@ class MenuItem_bool : public MenuEditItemBase { #define PSTRING_ITEM(LABEL, V...) PSTRING_ITEM_P(GET_TEXT(LABEL), ##V) -#define STATIC_ITEM(LABEL, V...) STATIC_ITEM_P(GET_TEXT(LABEL), ##V) -#define STATIC_ITEM_N(LABEL, V...) STATIC_ITEM_N_P(GET_TEXT(LABEL), ##V) +#define STATIC_ITEM(LABEL, V...) STATIC_ITEM_P(GET_TEXT(LABEL), ##V) +#define STATIC_ITEM_N(LABEL, N, V...) STATIC_ITEM_N_P(GET_TEXT(LABEL), N, ##V) #define MENU_ITEM_N_S_P(TYPE, N, S, PLABEL, V...) _MENU_ITEM_N_S_P(TYPE, N, S, false, PLABEL, ##V) #define MENU_ITEM_N_S(TYPE, N, S, LABEL, V...) MENU_ITEM_N_S_P(TYPE, N, S, GET_TEXT(LABEL), ##V) From 79d41233191094e66d955c88e850cc4126af81fa Mon Sep 17 00:00:00 2001 From: Victor Oliveira Date: Mon, 14 Sep 2020 19:16:19 -0300 Subject: [PATCH 17/44] Only set up SPI pins as needed (#19372) --- Marlin/src/HAL/LPC1768/HAL_SPI.cpp | 102 +++++++++++++++-------------- 1 file changed, 53 insertions(+), 49 deletions(-) diff --git a/Marlin/src/HAL/LPC1768/HAL_SPI.cpp b/Marlin/src/HAL/LPC1768/HAL_SPI.cpp index e13f2d98cbb9..b3d2908ac93e 100644 --- a/Marlin/src/HAL/LPC1768/HAL_SPI.cpp +++ b/Marlin/src/HAL/LPC1768/HAL_SPI.cpp @@ -39,10 +39,10 @@ * Some of the LCD interfaces/adapters result in the LCD SPI and the SD card * SPI sharing pins. The SCK, MOSI & MISO pins can NOT be set/cleared with * WRITE nor digitalWrite when the hardware SPI module within the LPC17xx is - * active. If any of these pins are shared then the software SPI must be used. + * active. If any of these pins are shared then the software SPI must be used. * - * A more sophisticated hardware SPI can be found at the following link. This - * implementation has not been fully debugged. + * A more sophisticated hardware SPI can be found at the following link. + * This implementation has not been fully debugged. * https://github.com/MarlinFirmware/Marlin/tree/071c7a78f27078fd4aee9a3ef365fcf5e143531e */ @@ -170,34 +170,20 @@ static inline void waitSpiTxEnd(LPC_SSP_TypeDef *spi_d) { while (SSP_GetStatus(spi_d, SSP_STAT_BUSY) == SET) { /* nada */ } // wait until BSY=0 } +// Retain the pin init state of the SPI, to avoid init more than once, +// even if more instances of SPIClass exist +static bool spiInitialised[BOARD_NR_SPI] = { false }; + SPIClass::SPIClass(uint8_t device) { // Init things specific to each SPI device // clock divider setup is a bit of hack, and needs to be improved at a later date. - PINSEL_CFG_Type PinCfg; // data structure to hold init values #if BOARD_NR_SPI >= 1 _settings[0].spi_d = LPC_SSP0; _settings[0].dataMode = SPI_MODE0; _settings[0].dataSize = DATA_SIZE_8BIT; _settings[0].clock = SPI_CLOCK_MAX; - // _settings[0].clockDivider = determine_baud_rate(_settings[0].spi_d, _settings[0].clock); - PinCfg.Funcnum = 2; - PinCfg.OpenDrain = 0; - PinCfg.Pinmode = 0; - PinCfg.Pinnum = LPC176x::pin_bit(BOARD_SPI1_SCK_PIN); - PinCfg.Portnum = LPC176x::pin_port(BOARD_SPI1_SCK_PIN); - PINSEL_ConfigPin(&PinCfg); - SET_OUTPUT(BOARD_SPI1_SCK_PIN); - - PinCfg.Pinnum = LPC176x::pin_bit(BOARD_SPI1_MISO_PIN); - PinCfg.Portnum = LPC176x::pin_port(BOARD_SPI1_MISO_PIN); - PINSEL_ConfigPin(&PinCfg); - SET_INPUT(BOARD_SPI1_MISO_PIN); - - PinCfg.Pinnum = LPC176x::pin_bit(BOARD_SPI1_MOSI_PIN); - PinCfg.Portnum = LPC176x::pin_port(BOARD_SPI1_MOSI_PIN); - PINSEL_ConfigPin(&PinCfg); - SET_OUTPUT(BOARD_SPI1_MOSI_PIN); + //_settings[0].clockDivider = determine_baud_rate(_settings[0].spi_d, _settings[0].clock); #endif #if BOARD_NR_SPI >= 2 @@ -205,34 +191,53 @@ SPIClass::SPIClass(uint8_t device) { _settings[1].dataMode = SPI_MODE0; _settings[1].dataSize = DATA_SIZE_8BIT; _settings[1].clock = SPI_CLOCK_MAX; - // _settings[1].clockDivider = determine_baud_rate(_settings[1].spi_d, _settings[1].clock); + //_settings[1].clockDivider = determine_baud_rate(_settings[1].spi_d, _settings[1].clock); + #endif + + setModule(device); + + // Init the GPDMA controller + // TODO: call once in the constructor? or each time? + GPDMA_Init(); +} + +void SPIClass::begin() { + // Init the SPI pins in the first begin call + if ((_currentSetting->spi_d == LPC_SSP0 && spiInitialised[0] == false) || + (_currentSetting->spi_d == LPC_SSP1 && spiInitialised[1] == false)) { + pin_t sck, miso, mosi; + if (_currentSetting->spi_d == LPC_SSP0) { + sck = BOARD_SPI1_SCK_PIN; + miso = BOARD_SPI1_MISO_PIN; + mosi = BOARD_SPI1_MOSI_PIN; + spiInitialised[0] = true; + } + else if (_currentSetting->spi_d == LPC_SSP1) { + sck = BOARD_SPI2_SCK_PIN; + miso = BOARD_SPI2_MISO_PIN; + mosi = BOARD_SPI2_MOSI_PIN; + spiInitialised[1] = true; + } + PINSEL_CFG_Type PinCfg; // data structure to hold init values PinCfg.Funcnum = 2; PinCfg.OpenDrain = 0; PinCfg.Pinmode = 0; - PinCfg.Pinnum = LPC176x::pin_bit(BOARD_SPI2_SCK_PIN); - PinCfg.Portnum = LPC176x::pin_port(BOARD_SPI2_SCK_PIN); + PinCfg.Pinnum = LPC176x::pin_bit(sck); + PinCfg.Portnum = LPC176x::pin_port(sck); PINSEL_ConfigPin(&PinCfg); - SET_OUTPUT(BOARD_SPI2_SCK_PIN); + SET_OUTPUT(sck); - PinCfg.Pinnum = LPC176x::pin_bit(BOARD_SPI2_MISO_PIN); - PinCfg.Portnum = LPC176x::pin_port(BOARD_SPI2_MISO_PIN); + PinCfg.Pinnum = LPC176x::pin_bit(miso); + PinCfg.Portnum = LPC176x::pin_port(miso); PINSEL_ConfigPin(&PinCfg); - SET_INPUT(BOARD_SPI2_MISO_PIN); + SET_INPUT(miso); - PinCfg.Pinnum = LPC176x::pin_bit(BOARD_SPI2_MOSI_PIN); - PinCfg.Portnum = LPC176x::pin_port(BOARD_SPI2_MOSI_PIN); + PinCfg.Pinnum = LPC176x::pin_bit(mosi); + PinCfg.Portnum = LPC176x::pin_port(mosi); PINSEL_ConfigPin(&PinCfg); - SET_OUTPUT(BOARD_SPI2_MOSI_PIN); - #endif - - setModule(device); - - /* Initialize GPDMA controller */ - //TODO: call once in the constructor? or each time? - GPDMA_Init(); -} + SET_OUTPUT(mosi); + } -void SPIClass::begin() { updateSettings(); SSP_Cmd(_currentSetting->spi_d, ENABLE); // start SSP running } @@ -246,7 +251,7 @@ void SPIClass::beginTransaction(const SPISettings &cfg) { } uint8_t SPIClass::transfer(const uint16_t b) { - /* send and receive a single byte */ + // Send and receive a single byte SSP_ReceiveData(_currentSetting->spi_d); // read any previous data SSP_SendData(_currentSetting->spi_d, b); waitSpiTxEnd(_currentSetting->spi_d); // wait for it to finish @@ -254,8 +259,7 @@ uint8_t SPIClass::transfer(const uint16_t b) { } uint16_t SPIClass::transfer16(const uint16_t data) { - return (transfer((data >> 8) & 0xFF) << 8) - | (transfer(data & 0xFF) & 0xFF); + return (transfer((data >> 8) & 0xFF) << 8) | (transfer(data & 0xFF) & 0xFF); } void SPIClass::end() { @@ -294,23 +298,23 @@ void SPIClass::dmaSend(void *buf, uint16_t length, bool minc) { // Enable dma on SPI SSP_DMACmd(_currentSetting->spi_d, SSP_DMA_TX, ENABLE); - // only increase memory if minc is true + // Only increase memory if minc is true GPDMACfg.MemoryIncrease = (minc ? GPDMA_DMACCxControl_SI : 0); // Setup channel with given parameter GPDMA_Setup(&GPDMACfg); - // enabled dma + // Enable DMA GPDMA_ChannelCmd(0, ENABLE); - // wait data transfer + // Wait for data transfer while (!GPDMA_IntGetStatus(GPDMA_STAT_RAWINTTC, 0) && !GPDMA_IntGetStatus(GPDMA_STAT_RAWINTERR, 0)) { } - // clear err and int + // Clear err and int GPDMA_ClearIntPending (GPDMA_STATCLR_INTTC, 0); GPDMA_ClearIntPending (GPDMA_STATCLR_INTERR, 0); - // dma disable + // Disable DMA GPDMA_ChannelCmd(0, DISABLE); waitSpiTxEnd(_currentSetting->spi_d); From 0b7d69d06ff58e01adace95bc08c69322c815639 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 15 Sep 2020 00:13:01 +0000 Subject: [PATCH 18/44] [cron] Bump distribution date (2020-09-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 faf816554c9e..55f303a2a1cc 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-09-14" + #define STRING_DISTRIBUTION_DATE "2020-09-15" #endif /** From 57a87a278bc2acd958cd64b1434ebc2211063c6e Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 16 Sep 2020 00:12:57 +0000 Subject: [PATCH 19/44] [cron] Bump distribution date (2020-09-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 55f303a2a1cc..63f117b932d1 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-09-15" + #define STRING_DISTRIBUTION_DATE "2020-09-16" #endif /** From 250bfac0ccbadbd40f3d6f3fe83c33aa96d09a52 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 16 Sep 2020 04:35:30 -0500 Subject: [PATCH 20/44] E3 V2 DWIN cleanup --- Marlin/src/lcd/dwin/e3v2/dwin.cpp | 757 +++++++++++++++--------------- Marlin/src/lcd/dwin/e3v2/dwin.h | 52 +- 2 files changed, 400 insertions(+), 409 deletions(-) diff --git a/Marlin/src/lcd/dwin/e3v2/dwin.cpp b/Marlin/src/lcd/dwin/e3v2/dwin.cpp index ccd5f2bc2055..1bef8f14088b 100644 --- a/Marlin/src/lcd/dwin/e3v2/dwin.cpp +++ b/Marlin/src/lcd/dwin/e3v2/dwin.cpp @@ -162,7 +162,7 @@ select_t select_page{0}, select_file{0}, select_print{0}, select_prepare{0} , select_PLA{0}, select_ABS{0} , select_speed{0} , select_acc{0} - , select_corner{0} + , select_jerk{0} , select_step{0} // , select_leveling{0} ; @@ -235,16 +235,16 @@ void ICON_Print() { DWIN_ICON_Show(ICON, ICON_Print_1, 17, 130); DWIN_Draw_Rectangle(0, White, 17, 130, 126, 229); if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 1, 447, 271 - 243, 479 - 19, 58, 201); + DWIN_Frame_AreaCopy(1, 1, 447, 28, 460, 58, 201); else - DWIN_Frame_AreaCopy(1, 1, 451, 271 - 240, 479 - 16, 72 - 15, 201); + DWIN_Frame_AreaCopy(1, 1, 451, 31, 463, 57, 201); } else { DWIN_ICON_Show(ICON, ICON_Print_0, 17, 130); if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 1, 405, 271 - 243, 420, 58, 201); + DWIN_Frame_AreaCopy(1, 1, 405, 28, 420, 58, 201); else - DWIN_Frame_AreaCopy(1, 1, 423, 271 - 240, 423 + 12, 72 - 15, 201); + DWIN_Frame_AreaCopy(1, 1, 423, 31, 435, 57, 201); } } @@ -253,16 +253,16 @@ void ICON_Prepare() { DWIN_ICON_Show(ICON, ICON_Prepare_1, 145, 130); DWIN_Draw_Rectangle(0, White, 145, 130, 254, 229); if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 31, 447, 271 - 213, 479 - 19, 186, 201); + DWIN_Frame_AreaCopy(1, 31, 447, 58, 460, 186, 201); else - DWIN_Frame_AreaCopy(1, 33, 451, 271 - 189, 479 - 13, 200 - 25, 201); + DWIN_Frame_AreaCopy(1, 33, 451, 82, 466, 175, 201); } else { DWIN_ICON_Show(ICON, ICON_Prepare_0, 145, 130); if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 31, 405, 271 - 213, 420, 186, 201); + DWIN_Frame_AreaCopy(1, 31, 405, 58, 420, 186, 201); else - DWIN_Frame_AreaCopy(1, 33, 423, 271 - 189, 423 + 15, 200 - 25, 201); + DWIN_Frame_AreaCopy(1, 33, 423, 82, 438, 175, 201); } } @@ -271,16 +271,16 @@ void ICON_Control() { DWIN_ICON_Show(ICON, ICON_Control_1, 17, 246); DWIN_Draw_Rectangle(0, White, 17, 246, 126, 345); if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 61, 447, 271 - 183, 479 - 19, 58, 318); + DWIN_Frame_AreaCopy(1, 61, 447, 88, 460, 58, 318); else - DWIN_Frame_AreaCopy(1, 85, 451, 271 - 139, 479 - 16, 72 - 24, 318); + DWIN_Frame_AreaCopy(1, 85, 451, 132, 463, 48, 318); } else { DWIN_ICON_Show(ICON, ICON_Control_0, 17, 246); if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 61, 405, 271 - 183, 420, 58, 318); + DWIN_Frame_AreaCopy(1, 61, 405, 88, 420, 58, 318); else - DWIN_Frame_AreaCopy(1, 85, 423, 271 - 139, 479 - 45, 72 - 24, 318); + DWIN_Frame_AreaCopy(1, 85, 423, 132, 434, 48, 318); } } @@ -289,16 +289,16 @@ void ICON_StartInfo(bool show) { DWIN_ICON_Show(ICON, ICON_Info_1, 145, 246); DWIN_Draw_Rectangle(0, White, 145, 246, 254, 345); if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 91, 447, 271 - 153, 479 - 19, 186, 318); + DWIN_Frame_AreaCopy(1, 91, 447, 118, 460, 186, 318); else - DWIN_Frame_AreaCopy(1, 132, 451, 159, 479 - 13, 186, 318); + DWIN_Frame_AreaCopy(1, 132, 451, 159, 466, 186, 318); } else { DWIN_ICON_Show(ICON, ICON_Info_0, 145, 246); if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 91, 405, 271 - 153, 420, 186, 318); + DWIN_Frame_AreaCopy(1, 91, 405, 118, 420, 186, 318); else - DWIN_Frame_AreaCopy(1, 132, 423, 159, 423 + 12, 186, 318); + DWIN_Frame_AreaCopy(1, 132, 423, 159, 435, 186, 318); } } @@ -307,16 +307,16 @@ void ICON_Leveling(bool show) { DWIN_ICON_Show(ICON, ICON_Leveling_1, 145, 246); DWIN_Draw_Rectangle(0, White, 145, 246, 254, 345); if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 211, 447, 238, 479 - 19, 186, 318); + DWIN_Frame_AreaCopy(1, 211, 447, 238, 460, 186, 318); else - DWIN_Frame_AreaCopy(1, 84, 437, 120, 449, 200 - 18, 318); + DWIN_Frame_AreaCopy(1, 84, 437, 120, 449, 182, 318); } else { DWIN_ICON_Show(ICON, ICON_Leveling_0, 145, 246); if (HMI_flag.language_chinese) DWIN_Frame_AreaCopy(1, 211, 405, 238, 420, 186, 318); else - DWIN_Frame_AreaCopy(1, 84, 465, 120, 478, 200 - 18, 318); + DWIN_Frame_AreaCopy(1, 84, 465, 120, 478, 182, 318); } } @@ -325,16 +325,16 @@ void ICON_Tune() { DWIN_ICON_Show(ICON, ICON_Setup_1, 8, 252); DWIN_Draw_Rectangle(0, White, 8, 252, 87, 351); if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 121, 447, 271 - 123, 479 - 21, 34, 325); + DWIN_Frame_AreaCopy(1, 121, 447, 148, 458, 34, 325); else - DWIN_Frame_AreaCopy(1, 1, 465, 271 - 237, 479 - 2, 48 - 17, 325); + DWIN_Frame_AreaCopy(1, 1, 465, 34, 477, 31, 325); } else { DWIN_ICON_Show(ICON, ICON_Setup_0, 8, 252); if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 121, 405, 271 - 123, 420, 34, 325); + DWIN_Frame_AreaCopy(1, 121, 405, 148, 420, 34, 325); else - DWIN_Frame_AreaCopy(1, 1, 438, 271 - 239, 479 - 31, 48 - 17, 325); + DWIN_Frame_AreaCopy(1, 1, 438, 32, 448, 31, 325); } } @@ -343,16 +343,16 @@ void ICON_Pause() { DWIN_ICON_Show(ICON, ICON_Pause_1, 96, 252); DWIN_Draw_Rectangle(0, White, 96, 252, 175, 351); if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 181, 447, 271 - 63, 479 - 20, 124, 325); + DWIN_Frame_AreaCopy(1, 181, 447, 208, 459, 124, 325); else - DWIN_Frame_AreaCopy(1, 177, 451, 271 - 55, 479 - 17, 136 - 20, 325); + DWIN_Frame_AreaCopy(1, 177, 451, 216, 462, 116, 325); } else { DWIN_ICON_Show(ICON, ICON_Pause_0, 96, 252); if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 181, 405, 271 - 63, 420, 124, 325); + DWIN_Frame_AreaCopy(1, 181, 405, 208, 420, 124, 325); else - DWIN_Frame_AreaCopy(1, 177, 423, 271 - 56, 479 - 46, 136 - 20, 325); + DWIN_Frame_AreaCopy(1, 177, 423, 215, 433, 116, 325); } } @@ -361,16 +361,16 @@ void ICON_Continue() { DWIN_ICON_Show(ICON, ICON_Continue_1, 96, 252); DWIN_Draw_Rectangle(0, White, 96, 252, 175, 351); if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 1, 447, 271 - 243, 479 - 19, 124, 325); + DWIN_Frame_AreaCopy(1, 1, 447, 28, 460, 124, 325); else - DWIN_Frame_AreaCopy(1, 1, 451, 271 - 239, 479 - 16, 136 - 15, 325); + DWIN_Frame_AreaCopy(1, 1, 451, 32, 463, 121, 325); } else { DWIN_ICON_Show(ICON, ICON_Continue_0, 96, 252); if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 1, 405, 271 - 243, 420, 124, 325); + DWIN_Frame_AreaCopy(1, 1, 405, 28, 420, 124, 325); else - DWIN_Frame_AreaCopy(1, 1, 424, 271 - 240, 479 - 45, 136 - 15, 325); + DWIN_Frame_AreaCopy(1, 1, 424, 31, 434, 121, 325); } } @@ -379,16 +379,16 @@ void ICON_Stop() { DWIN_ICON_Show(ICON, ICON_Stop_1, 184, 252); DWIN_Draw_Rectangle(0, White, 184, 252, 263, 351); if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 151, 447, 271 - 93, 479 - 20, 210, 325); + DWIN_Frame_AreaCopy(1, 151, 447, 178, 459, 210, 325); else - DWIN_Frame_AreaCopy(1, 218, 451, 271 - 22, 479 - 14, 224 - 15, 325); + DWIN_Frame_AreaCopy(1, 218, 451, 249, 465, 209, 325); } else { DWIN_ICON_Show(ICON, ICON_Stop_0, 184, 252); if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 151, 405, 271 - 93, 420, 210, 325); + DWIN_Frame_AreaCopy(1, 151, 405, 178, 420, 210, 325); else - DWIN_Frame_AreaCopy(1, 218, 423, 271 - 24, 479 - 43, 224 - 15, 325); + DWIN_Frame_AreaCopy(1, 218, 423, 247, 436, 209, 325); } } @@ -405,7 +405,7 @@ inline void Draw_Title(const __FlashStringHelper * title) { } inline void Clear_Menu_Area(void) { - DWIN_Draw_Rectangle(1, Background_black, 0, 31, 272, 360); + DWIN_Draw_Rectangle(1, Background_black, 0, 31, DWIN_WIDTH, 360); } inline void Clear_Main_Window(void) { @@ -415,11 +415,11 @@ inline void Clear_Main_Window(void) { inline void Clear_Popup_Area(void) { Clear_Title_Bar(); - DWIN_Draw_Rectangle(1, Background_black, 0, 31, 272, 480); + DWIN_Draw_Rectangle(1, Background_black, 0, 31, DWIN_WIDTH, DWIN_HEIGHT); } void Draw_Popup_Bkgd_105(void) { - DWIN_Draw_Rectangle(1, Background_window, 14, 105, 271 - 13, 479 - 105); + DWIN_Draw_Rectangle(1, Background_window, 14, 105, 258, 374); } inline void Draw_More_Icon(const uint8_t line) { @@ -446,7 +446,7 @@ inline void Add_Menu_Line() { } inline void Scroll_Menu(const uint8_t dir) { - DWIN_Frame_AreaMove(1, dir, MLINE, Background_black, 0, 31, 272, 349); + DWIN_Frame_AreaMove(1, dir, MLINE, Background_black, 0, 31, DWIN_WIDTH, 349); switch (dir) { case DWIN_SCROLL_DOWN: Move_Highlight(-1, 0); break; case DWIN_SCROLL_UP: Add_Menu_Line(); break; @@ -474,9 +474,9 @@ inline void Draw_Menu_Line(const uint8_t line, const uint8_t icon=0, const char // The "Back" label is always on the first line inline void Draw_Back_Label(void) { if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 129, 72, 271 - 115, 479 - 395, LBLX, MBASE(0)); + DWIN_Frame_AreaCopy(1, 129, 72, 156, 84, LBLX, MBASE(0)); else - DWIN_Frame_AreaCopy(1, 226, 179, 271 - 15, 479 - 290, LBLX, MBASE(0)); + DWIN_Frame_AreaCopy(1, 226, 179, 256, 189, LBLX, MBASE(0)); } // Draw "Back" line at the top @@ -491,12 +491,12 @@ inline void Draw_Back_First(const bool is_sel=true) { // inline void draw_move_en(const uint16_t line) { - DWIN_Frame_AreaCopy(1, 69, 61, 271 - 169, 479 - 408, LBLX, line); // "Move" + DWIN_Frame_AreaCopy(1, 69, 61, 102, 71, LBLX, line); // "Move" } inline void Prepare_Item_Move(const uint8_t row) { if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 159, 70, 271 - 71, 479 - 395, LBLX, MBASE(row)); + DWIN_Frame_AreaCopy(1, 159, 70, 200, 84, LBLX, MBASE(row)); else draw_move_en(MBASE(row)); // "Move >" Draw_Menu_Line(row, ICON_Axis); @@ -505,35 +505,35 @@ inline void Prepare_Item_Move(const uint8_t row) { inline void Prepare_Item_Disable(const uint8_t row) { if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 204, 70, 271 - 12, 479 - 397, LBLX, MBASE(row)); + DWIN_Frame_AreaCopy(1, 204, 70, 259, 82, LBLX, MBASE(row)); else - DWIN_Frame_AreaCopy(1, 103, 59, 271 - 71, 479 - 405, LBLX, MBASE(row)); // "Disable Stepper" + DWIN_Frame_AreaCopy(1, 103, 59, 200, 74, LBLX, MBASE(row)); // "Disable Stepper" Draw_Menu_Line(row, ICON_CloseMotor); } inline void Prepare_Item_Home(const uint8_t row) { if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 0, 89, 271 - 230, 479 - 378, LBLX, MBASE(row)); + DWIN_Frame_AreaCopy(1, 0, 89, 41, 101, LBLX, MBASE(row)); else - DWIN_Frame_AreaCopy(1, 202, 61, 271 - 0, 479 - 408, LBLX, MBASE(row)); // "Auto Home" + DWIN_Frame_AreaCopy(1, 202, 61, 271, 71, LBLX, MBASE(row)); // "Auto Home" Draw_Menu_Line(row, ICON_Homing); } inline void Prepare_Item_Offset(const uint8_t row) { if (HMI_flag.language_chinese) { #if HAS_BED_PROBE - DWIN_Frame_AreaCopy(1, 174, 164, 271 - 48, 479 - 302, LBLX, MBASE(row)); + DWIN_Frame_AreaCopy(1, 174, 164, 223, 177, LBLX, MBASE(row)); DWIN_Draw_Signed_Float(font8x16, Background_black, 2, 2, 202, MBASE(row), probe.offset.z * 100); #else - DWIN_Frame_AreaCopy(1, 43, 89, 271 - 173, 479 - 378, LBLX, MBASE(row)); + DWIN_Frame_AreaCopy(1, 43, 89, 98, 101, LBLX, MBASE(row)); #endif } else { #if HAS_BED_PROBE - DWIN_Frame_AreaCopy(1, 93, 179, 271 - 130, 479 - 290, LBLX, MBASE(row)); // "Z-Offset" + DWIN_Frame_AreaCopy(1, 93, 179, 141, 189, LBLX, MBASE(row)); // "Z-Offset" DWIN_Draw_Signed_Float(font8x16, Background_black, 2, 2, 202, MBASE(row), probe.offset.z * 100); #else - DWIN_Frame_AreaCopy(1, 1, 76, 271 - 165, 479 - 393, LBLX, MBASE(row)); // "..." + DWIN_Frame_AreaCopy(1, 1, 76, 106, 86, LBLX, MBASE(row)); // "..." #endif } Draw_Menu_Line(row, ICON_SetHome); @@ -541,41 +541,41 @@ inline void Prepare_Item_Offset(const uint8_t row) { inline void Prepare_Item_PLA(const uint8_t row) { if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 100, 89, 271 - 93 - 27, 479 - 378, LBLX, MBASE(row)); + DWIN_Frame_AreaCopy(1, 100, 89, 151, 101, LBLX, MBASE(row)); } else { - DWIN_Frame_AreaCopy(1, 107, 76, 271 - 115, 479 - 393, LBLX, MBASE(row)); // "Preheat" - DWIN_Frame_AreaCopy(1, 157, 76, 181, 479 - 393, LBLX + 49 + 3, MBASE(row)); // "PLA" + 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" } Draw_Menu_Line(row, ICON_PLAPreheat); } inline void Prepare_Item_ABS(const uint8_t row) { if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 180, 89, 271 - 11 - 27, 479 - 379, LBLX, MBASE(row)); + DWIN_Frame_AreaCopy(1, 180, 89, 233, 100, LBLX, MBASE(row)); } else { - DWIN_Frame_AreaCopy(1, 107, 76, 271 - 115, 479 - 393, LBLX, MBASE(row)); // "Preheat" - DWIN_Frame_AreaCopy(1, 172, 76, 198, 479 - 393, LBLX + 49 + 3, MBASE(row)); // "ABS" + 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" } Draw_Menu_Line(row, ICON_ABSPreheat); } inline void Prepare_Item_Cool(const uint8_t row) { if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 1, 104, 271 - 215, 479 - 362, LBLX, MBASE(row)); + DWIN_Frame_AreaCopy(1, 1, 104, 56, 117, LBLX, MBASE(row)); else - DWIN_Frame_AreaCopy(1, 200, 76, 271 - 7, 479 - 393, LBLX, MBASE(row));// "Cooldown" + DWIN_Frame_AreaCopy(1, 200, 76, 264, 86, LBLX, MBASE(row)); // "Cooldown" Draw_Menu_Line(row, ICON_Cool); } inline void Prepare_Item_Lang(const uint8_t row) { if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 239, 134, 271 - 5, 479 - 333, LBLX, MBASE(row)); + DWIN_Frame_AreaCopy(1, 239, 134, 266, 146, LBLX, MBASE(row)); DWIN_Draw_String(false, false, font8x16, White, Background_black, 226, MBASE(row), F("CN")); } else { - DWIN_Frame_AreaCopy(1, 0, 194, 271 - 150, 479 - 272, LBLX, MBASE(row)); // "Language selection" + DWIN_Frame_AreaCopy(1, 0, 194, 121, 207, LBLX, MBASE(row)); // "Language selection" DWIN_Draw_String(false, false, font8x16, White, Background_black, 226, MBASE(row), F("EN")); } Draw_Menu_Icon(row, ICON_Language); @@ -589,13 +589,13 @@ inline void Draw_Prepare_Menu() { #define PVISI(L) WITHIN(PSCROL(L), 0, MROWS) if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 133, 1, 271 - 111, 479 - 465 - 1, 14, 8); // "Prepare" + DWIN_Frame_AreaCopy(1, 133, 1, 160, 13, 14, 8); // "Prepare" } else { #ifdef USE_STRING_HEADINGS Draw_Title(GET_TEXT_F(MSG_PREPARE)); #else - DWIN_Frame_AreaCopy(1, 178, 2, 271 - 42, 479 - 464 - 1, 14, 8); // "Prepare" + DWIN_Frame_AreaCopy(1, 178, 2, 229, 14, 14, 8); // "Prepare" #endif } @@ -621,18 +621,18 @@ inline void Draw_Control_Menu() { #define CLINE(L) MBASE(CSCROL(L)) #define CVISI(L) WITHIN(CSCROL(L), 0, MROWS) - if (CVISI(0)) Draw_Back_First(select_control.now == 0); // < Back + if (CVISI(0)) Draw_Back_First(select_control.now == 0); // < Back if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 103, 1, 271 - 141, 479 - 465, 14, 8); - DWIN_Frame_AreaCopy(1, 57, 104, 271 - 187, 479 - 363, LBLX, CLINE(1)); // Temperature > - DWIN_Frame_AreaCopy(1, 87, 104, 271 - 157, 479 - 363, LBLX, CLINE(2)); // Motion > - DWIN_Frame_AreaCopy(1, 117, 104, 271 - 99, 479 - 363, LBLX, CLINE(3)); // Store Config - DWIN_Frame_AreaCopy(1, 174, 103, 271 - 42, 479 - 363, LBLX, CLINE(4)); // Read Config - DWIN_Frame_AreaCopy(1, 1, 118, 271 - 215, 479 - 348, LBLX, CLINE(5)); // Reset Config + DWIN_Frame_AreaCopy(1, 103, 1, 130, 14, 14, 8); + DWIN_Frame_AreaCopy(1, 57, 104, 84, 116, LBLX, CLINE(1)); // Temperature > + DWIN_Frame_AreaCopy(1, 87, 104, 114, 116, LBLX, CLINE(2)); // Motion > + DWIN_Frame_AreaCopy(1, 117, 104, 172, 116, LBLX, CLINE(3)); // Store Config + DWIN_Frame_AreaCopy(1, 174, 103, 229, 116, LBLX, CLINE(4)); // Read Config + DWIN_Frame_AreaCopy(1, 1, 118, 56, 131, LBLX, CLINE(5)); // Reset Config if (CVISI(6)) - DWIN_Frame_AreaCopy(1, 231, 104, 271 - 13, 479 - 363, LBLX, CLINE(6)); // Info > + DWIN_Frame_AreaCopy(1, 231, 104, 258, 116, LBLX, CLINE(6)); // Info > } else { #ifdef USE_STRING_HEADINGS @@ -648,18 +648,18 @@ inline void Draw_Control_Menu() { if (CVISI(3)) DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 2), F("Info")); #endif #else - DWIN_Frame_AreaCopy(1, 128, 2, 271 - 95, 479 - 467, 14, 8); - DWIN_Frame_AreaCopy(1, 1, 89, 271 - 188, 479 - 377 - 1, LBLX, CLINE(1));// Temperature > - DWIN_Frame_AreaCopy(1, 84, 89, 271 - 143, 479 - 380, LBLX, CLINE(2));// Motion > + DWIN_Frame_AreaCopy(1, 128, 2, 176, 12, 14, 8); + DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX, CLINE(1)); // Temperature > + DWIN_Frame_AreaCopy(1, 84, 89, 128, 99, LBLX, CLINE(2)); // Motion > #if ENABLED(EEPROM_SETTINGS) - DWIN_Frame_AreaCopy(1, 131 + 17, 89, 271 - 3, 479 - 377 - 1, LBLX, CLINE(3));// "Store Configuration" - DWIN_Frame_AreaCopy(1, 26, 104, 271 - 214, 479 - 365, LBLX, CLINE(4)); // "Read" - DWIN_Frame_AreaCopy(1, 131 + 51, 89, 271 - 3, 479 - 377 - 1, LBLX + 31 + 3, CLINE(4)); // "Configuration" - DWIN_Frame_AreaCopy(1, 59, 104, 271 - 178, 479 - 365, LBLX, CLINE(5)); // "Reset" - DWIN_Frame_AreaCopy(1, 131 + 51, 89, 271 - 3, 479 - 377 - 1, LBLX + 34 + 3, CLINE(5)); // "Configuration" - if (CVISI(6)) DWIN_Frame_AreaCopy(1, 0, 104, 25, 115, LBLX, CLINE(6)); // Info > + DWIN_Frame_AreaCopy(1, 148, 89, 268, 101, LBLX, CLINE(3)); // "Store Configuration" + DWIN_Frame_AreaCopy(1, 26, 104, 57, 114, LBLX, CLINE(4)); // "Read" + DWIN_Frame_AreaCopy(1, 182, 89, 268, 101, LBLX + 34, CLINE(4)); // "Configuration" + DWIN_Frame_AreaCopy(1, 59, 104, 93, 114, LBLX, CLINE(5)); // "Reset" + DWIN_Frame_AreaCopy(1, 182, 89, 268, 101, LBLX + 37, CLINE(5)); // "Configuration" + if (CVISI(6)) DWIN_Frame_AreaCopy(1, 0, 104, 25, 115, LBLX, CLINE(6)); // Info > #else - if (CVISI(3)) DWIN_Frame_AreaCopy(1, 0, 104, 25, 115, LBLX, CLINE(3)); // Info > + if (CVISI(3)) DWIN_Frame_AreaCopy(1, 0, 104, 25, 115, LBLX, CLINE(3)); // Info > #endif #endif } @@ -680,12 +680,12 @@ inline void Draw_Tune_Menu() { Clear_Main_Window(); if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 73, 2, 271 - 171, 479 - 466, 14, 9); - DWIN_Frame_AreaCopy(1, 116, 164, 271 - 100, 479 - 303, LBLX, MBASE(1)); - DWIN_Frame_AreaCopy(1, 1, 134, 271 - 215, 479 - 333, LBLX, MBASE(2)); - DWIN_Frame_AreaCopy(1, 58, 134, 271 - 158, 479 - 333, LBLX, MBASE(3)); - DWIN_Frame_AreaCopy(1, 115, 134, 271 - 101, 479 - 333, LBLX, MBASE(4)); - DWIN_Frame_AreaCopy(1, 174, 164, 271 - 48, 479 - 302, LBLX, MBASE(5)); + DWIN_Frame_AreaCopy(1, 73, 2, 100, 13, 14, 9); + DWIN_Frame_AreaCopy(1, 116, 164, 171, 176, LBLX, MBASE(1)); + DWIN_Frame_AreaCopy(1, 1, 134, 56, 146, LBLX, MBASE(2)); + DWIN_Frame_AreaCopy(1, 58, 134, 113, 146, LBLX, MBASE(3)); + DWIN_Frame_AreaCopy(1, 115, 134, 170, 146, LBLX, MBASE(4)); + DWIN_Frame_AreaCopy(1, 174, 164, 223, 177, LBLX, MBASE(5)); } else { #ifdef USE_STRING_HEADINGS @@ -696,14 +696,14 @@ inline void Draw_Tune_Menu() { DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 3), GET_TEXT_F(MSG_FAN_SPEED)); DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 4), GET_TEXT_F(MSG_ZPROBE_ZOFFSET)); #else - DWIN_Frame_AreaCopy(1, 94, 2, 271 - 145, 479 - 467, 14, 9); - DWIN_Frame_AreaCopy(1, 1, 179, 271 - 179, 479 - 287 - 2, LBLX, MBASE(1)); // print speed - DWIN_Frame_AreaCopy(1, 197, 104, 271 - 33, 479 - 365, LBLX, MBASE(2)); // Hotend... - DWIN_Frame_AreaCopy(1, 1, 89, 271 - 188, 479 - 377 - 1, LBLX + 41 + 3, MBASE(2)); // ...Temperature - DWIN_Frame_AreaCopy(1, 240, 104, 271 - 7, 479 - 365, LBLX, MBASE(3)); // Bed... - DWIN_Frame_AreaCopy(1, 1, 89, 271 - 188, 479 - 377 - 1, LBLX + 24 + 3, MBASE(3)); // ...Temperature - DWIN_Frame_AreaCopy(1, 0, 119, 271 - 207, 479 - 347, LBLX, MBASE(4)); // fan speed - DWIN_Frame_AreaCopy(1, 93, 179, 271 - 130, 479 - 290, LBLX, MBASE(5)); // Z-offset + DWIN_Frame_AreaCopy(1, 94, 2, 126, 12, 14, 9); + DWIN_Frame_AreaCopy(1, 1, 179, 92, 190, LBLX, MBASE(1)); // print speed + DWIN_Frame_AreaCopy(1, 197, 104, 238, 114, LBLX, MBASE(2)); // Hotend... + DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX + 44, MBASE(2)); // ...Temperature + DWIN_Frame_AreaCopy(1, 240, 104, 264, 114, LBLX, MBASE(3)); // Bed... + DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX + 27, MBASE(3)); // ...Temperature + DWIN_Frame_AreaCopy(1, 0, 119, 64, 132, LBLX, MBASE(4)); // fan speed + DWIN_Frame_AreaCopy(1, 93, 179, 141, 189, LBLX, MBASE(5)); // Z-offset #endif } @@ -724,47 +724,47 @@ inline void Draw_Tune_Menu() { } inline void draw_max_en(const uint16_t line) { - DWIN_Frame_AreaCopy(1, 245, 119, 271 - 2, 479 - 350, LBLX, line); // "Max" + DWIN_Frame_AreaCopy(1, 245, 119, 269, 129, LBLX, line); // "Max" } inline void draw_max_accel_en(const uint16_t line) { draw_max_en(line); - DWIN_Frame_AreaCopy(1, 1, 135, 271 - 192, 479 - 334, LBLX + 24 + 3, line); // "Acceleration" + DWIN_Frame_AreaCopy(1, 1, 135, 79, 145, LBLX + 27, line); // "Acceleration" } inline void draw_speed_en(const uint16_t inset, const uint16_t line) { - DWIN_Frame_AreaCopy(1, 184, 119, 224, 479 - 347, LBLX + inset, line); // "Speed" + DWIN_Frame_AreaCopy(1, 184, 119, 224, 132, LBLX + inset, line); // "Speed" } -inline void draw_corner_en(const uint16_t line) { - DWIN_Frame_AreaCopy(1, 64, 119, 271 - 165, 479 - 350, LBLX + 24 + 3, line); // "Corner" +inline void draw_jerk_en(const uint16_t line) { + DWIN_Frame_AreaCopy(1, 64, 119, 106, 129, LBLX + 27, line); // "Jerk" } inline void draw_steps_per_mm(const uint16_t line) { - DWIN_Frame_AreaCopy(1, 1, 151, 271 - 170, 479 - 318, LBLX, line); // "Steps-per-mm" + DWIN_Frame_AreaCopy(1, 1, 151, 101, 161, LBLX, line); // "Steps-per-mm" } inline void say_x(const uint16_t inset, const uint16_t line) { - DWIN_Frame_AreaCopy(1, 95, 104, 271 - 169, 479 - 365, LBLX + inset, line); // "X" + DWIN_Frame_AreaCopy(1, 95, 104, 102, 114, LBLX + inset, line); // "X" } inline void say_y(const uint16_t inset, const uint16_t line) { - DWIN_Frame_AreaCopy(1, 104, 104, 271 - 161, 479 - 365, LBLX + inset, line); // "Y" + DWIN_Frame_AreaCopy(1, 104, 104, 110, 114, LBLX + inset, line); // "Y" } inline void say_z(const uint16_t inset, const uint16_t line) { - DWIN_Frame_AreaCopy(1, 112, 104, 271 - 151, 479 - 365, LBLX + inset, line); // "Z" + DWIN_Frame_AreaCopy(1, 112, 104, 120, 114, LBLX + inset, line); // "Z" } inline void say_e(const uint16_t inset, const uint16_t line) { - DWIN_Frame_AreaCopy(1, 237, 119, 271 - 27, 479 - 350, LBLX + inset, line); // "E" + DWIN_Frame_AreaCopy(1, 237, 119, 244, 129, LBLX + inset, line); // "E" } inline void Draw_Motion_Menu() { Clear_Main_Window(); if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 1, 16, 271 - 243, 479 - 451, 14, 8); + DWIN_Frame_AreaCopy(1, 1, 16, 28, 28, 14, 8); - DWIN_Frame_AreaCopy(1, 173, 133, 228, 479 - 332, LBLX, MBASE(1)); // max speed - DWIN_Frame_AreaCopy(1, 173, 133, 200, 479 - 332, LBLX, MBASE(2)); // max... - DWIN_Frame_AreaCopy(1, 28, 149, 271 - 202, 479 - 318, LBLX + 27, MBASE(2) + 1); // ...acceleration - DWIN_Frame_AreaCopy(1, 173, 133, 200, 479 - 332, LBLX, MBASE(3)); // max... - DWIN_Frame_AreaCopy(1, 1, 180, 271 - 243, 479 - 287, LBLX + 27, MBASE(3) + 1); // ... - DWIN_Frame_AreaCopy(1, 202, 133, 228, 479 - 332, LBLX + 54, MBASE(3)); // ...jerk - DWIN_Frame_AreaCopy(1, 153, 148, 271 - 77, 479 - 318, LBLX, MBASE(4)); // flow ratio + DWIN_Frame_AreaCopy(1, 173, 133, 228, 147, LBLX, MBASE(1)); // Max speed + DWIN_Frame_AreaCopy(1, 173, 133, 200, 147, LBLX, MBASE(2)); // Max... + DWIN_Frame_AreaCopy(1, 28, 149, 69, 161, LBLX + 27, MBASE(2) + 1); // ...acceleration + DWIN_Frame_AreaCopy(1, 173, 133, 200, 147, LBLX, MBASE(3)); // Max... + DWIN_Frame_AreaCopy(1, 1, 180, 28, 192, LBLX + 27, MBASE(3) + 1); // ... + DWIN_Frame_AreaCopy(1, 202, 133, 228, 147, LBLX + 54, MBASE(3)); // ...jerk + DWIN_Frame_AreaCopy(1, 153, 148, 194, 161, LBLX, MBASE(4)); // Flow ratio } else { #ifdef USE_STRING_HEADINGS @@ -774,11 +774,11 @@ inline void Draw_Motion_Menu() { DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 2), GET_TEXT_F(MSG_JERK)); DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 3), GET_TEXT_F(MSG_STEPS_PER_MM)); #else - DWIN_Frame_AreaCopy(1, 144, 16, 271 - 82, 479 - 453, 14, 8); - draw_max_en(MBASE(1)); draw_speed_en(24 + 3, MBASE(1)); // "Max Speed" - draw_max_accel_en(MBASE(2)); // "Max Acceleration" - draw_max_en(MBASE(3)); draw_corner_en(MBASE(3)); // "Max Corner" - draw_steps_per_mm(MBASE(4)); // "Steps-per-mm" + DWIN_Frame_AreaCopy(1, 144, 16, 189, 26, 14, 8); + draw_max_en(MBASE(1)); draw_speed_en(27, MBASE(1)); // "Max Speed" + draw_max_accel_en(MBASE(2)); // "Max Acceleration" + draw_max_en(MBASE(3)); draw_jerk_en(MBASE(3)); // "Max Jerk" + draw_steps_per_mm(MBASE(4)); // "Steps-per-mm" #endif } @@ -803,9 +803,9 @@ void Popup_Window_Temperature(const bool toohigh) { if (toohigh) { DWIN_ICON_Show(ICON, ICON_TempTooHigh, 102, 165); if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 103, 371, 237, 479 - 93, 52, 285); + 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 - 0, 402, 95, 310); + DWIN_Frame_AreaCopy(1, 189, 389, 271, 402, 95, 310); } else { DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, 36, 300, F("Nozzle or Bed temperature")); @@ -815,8 +815,8 @@ void Popup_Window_Temperature(const bool toohigh) { else { DWIN_ICON_Show(ICON, ICON_TempTooLow, 102, 165); if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 103, 371, 271 - 1, 479 - 93, 52, 285); - DWIN_Frame_AreaCopy(1, 189, 389, 271 - 0, 402, 95, 310); + DWIN_Frame_AreaCopy(1, 103, 371, 270, 386, 52, 285); + DWIN_Frame_AreaCopy(1, 189, 389, 271, 402, 95, 310); } else { DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, 36, 300, F("Nozzle or Bed temperature")); @@ -826,7 +826,7 @@ void Popup_Window_Temperature(const bool toohigh) { } inline void Draw_Popup_Bkgd_60() { - DWIN_Draw_Rectangle(1, Background_window, 14, 60, 271 - 13, 330); + DWIN_Draw_Rectangle(1, Background_window, 14, 60, 258, 330); } #if HAS_HOTEND @@ -836,8 +836,8 @@ inline void Draw_Popup_Bkgd_60() { Draw_Popup_Bkgd_60(); DWIN_ICON_Show(ICON, ICON_TempTooLow, 102, 105); if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 103, 371, 136, 479 - 93, 69, 240); - DWIN_Frame_AreaCopy(1, 170, 371, 271 - 1, 479 - 93, 69 + 33, 240); + DWIN_Frame_AreaCopy(1, 103, 371, 136, 386, 69, 240); + DWIN_Frame_AreaCopy(1, 170, 371, 270, 386, 102, 240); DWIN_ICON_Show(ICON, ICON_Confirm_C, 86, 280); } else { @@ -852,8 +852,8 @@ void Popup_Window_Resume(void) { Clear_Popup_Area(); Draw_Popup_Bkgd_105(); if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 160, 338, 271 - 36, 479 - 125, 98, 135); - DWIN_Frame_AreaCopy(1, 103, 321, 271 - 0, 479 - 144, 52, 192); + DWIN_Frame_AreaCopy(1, 160, 338, 235, 354, 98, 135); + DWIN_Frame_AreaCopy(1, 103, 321, 271, 335, 52, 192); DWIN_ICON_Show(ICON, ICON_Continue_C, 26, 307); DWIN_ICON_Show(ICON, ICON_Cancel_C, 146, 307); } @@ -926,14 +926,14 @@ void Popup_window_PauseOrStop(void) { void Draw_Printing_Screen(void) { if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 30, 1, 271 - 200, 479 - 465, 14, 9);// Tune - DWIN_Frame_AreaCopy(1, 0, 72, 271 - 208, 479 - 393, 41, 188);// Pause - DWIN_Frame_AreaCopy(1, 65, 72, 271 - 143, 479 - 393, 176, 188); // Stop + 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 } else { - DWIN_Frame_AreaCopy(1, 40, 2, 271 - 179, 479 - 464 - 1, 14, 9);// Tune - DWIN_Frame_AreaCopy(1, 0, 44, 271 - 175, 479 - 420 - 1, 41, 188);// Pause - DWIN_Frame_AreaCopy(1, 98, 44, 271 - 119, 479 - 420 - 1, 176, 188); // Stop + 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 } } @@ -941,20 +941,20 @@ void Draw_Print_ProgressBar() { DWIN_ICON_Show(ICON, ICON_Bar, 15, 93); DWIN_Draw_Rectangle(1, BarFill_Color, 16 + Percentrecord * 240 / 100, 93, 256, 113); DWIN_Draw_IntValue(true, true, 0, font8x16, Percent_Color, Background_black, 2, 117, 133, Percentrecord); - DWIN_Draw_String(false, false, font8x16, Percent_Color, Background_black, 117 + 16, 133, F("%")); + DWIN_Draw_String(false, false, font8x16, Percent_Color, Background_black, 133, 133, F("%")); } void Draw_Print_ProgressElapsed() { duration_t elapsed = print_job_timer.duration(); // print timer DWIN_Draw_IntValue(true, true, 1, font8x16, White, Background_black, 2, 42, 212, elapsed.value / 3600); - DWIN_Draw_String(false, false, font8x16, White, Background_black, 42 + 16, 212, F(":")); - DWIN_Draw_IntValue(true, true, 1, font8x16, White, Background_black, 2, 42 + 24, 212, (elapsed.value % 3600) / 60); + DWIN_Draw_String(false, false, font8x16, White, Background_black, 58, 212, F(":")); + DWIN_Draw_IntValue(true, true, 1, font8x16, White, Background_black, 2, 66, 212, (elapsed.value % 3600) / 60); } void Draw_Print_ProgressRemain() { DWIN_Draw_IntValue(true, true, 1, font8x16, White, Background_black, 2, 176, 212, remain_time / 3600); - DWIN_Draw_String(false, false, font8x16, White, Background_black, 176 + 16, 212, F(":")); - DWIN_Draw_IntValue(true, true, 1, font8x16, White, Background_black, 2, 176 + 24, 212, (remain_time % 3600) / 60); + DWIN_Draw_String(false, false, font8x16, White, Background_black, 192, 212, F(":")); + DWIN_Draw_IntValue(true, true, 1, font8x16, White, Background_black, 2, 200, 212, (remain_time % 3600) / 60); } void Goto_PrintProcess(void) { @@ -986,13 +986,13 @@ void Goto_MainMenu(void) { Clear_Main_Window(); if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 2, 2, 271 - 244, 479 - 465, 14, 9); // "Home" + DWIN_Frame_AreaCopy(1, 2, 2, 27, 14, 14, 9); // "Home" } else { #ifdef USE_STRING_HEADINGS Draw_Title(GET_TEXT_F(MSG_MAIN)); #else - DWIN_Frame_AreaCopy(1, 0, 2, 271 - 232, 479 - 467, 14, 9); + DWIN_Frame_AreaCopy(1, 0, 2, 39, 12, 14, 9); #endif } @@ -1411,37 +1411,37 @@ void HMI_MaxAccelerationXYZE(void) { } } -void HMI_MaxCornerXYZE(void) { +void HMI_MaxJerkXYZE(void) { ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); if (encoder_diffState != ENCODER_DIFF_NO) { if (encoder_diffState == ENCODER_DIFF_CW) { - HMI_ValueStruct.Max_Corner += EncoderRate.encoderMoveValue; + HMI_ValueStruct.Max_Jerk += EncoderRate.encoderMoveValue; } else if (encoder_diffState == ENCODER_DIFF_CCW) { - HMI_ValueStruct.Max_Corner -= EncoderRate.encoderMoveValue; + HMI_ValueStruct.Max_Jerk -= EncoderRate.encoderMoveValue; } else if (encoder_diffState == ENCODER_DIFF_ENTER) { // return - checkkey = MaxCorner; + checkkey = MaxJerk; EncoderRate.encoderRateEnabled = 0; - if (HMI_flag.corner_flag == X_AXIS) planner.set_max_jerk(X_AXIS, HMI_ValueStruct.Max_Corner / 10); - else if (HMI_flag.corner_flag == Y_AXIS) planner.set_max_jerk(Y_AXIS, HMI_ValueStruct.Max_Corner / 10); - else if (HMI_flag.corner_flag == Z_AXIS) planner.set_max_jerk(Z_AXIS, HMI_ValueStruct.Max_Corner / 10); - else if (HMI_flag.corner_flag == E_AXIS) planner.set_max_jerk(E_AXIS, HMI_ValueStruct.Max_Corner / 10); - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 210, MBASE(select_corner.now), HMI_ValueStruct.Max_Corner); + if (HMI_flag.jerk_flag == X_AXIS) planner.set_max_jerk(X_AXIS, HMI_ValueStruct.Max_Jerk / 10); + else if (HMI_flag.jerk_flag == Y_AXIS) planner.set_max_jerk(Y_AXIS, HMI_ValueStruct.Max_Jerk / 10); + else if (HMI_flag.jerk_flag == Z_AXIS) planner.set_max_jerk(Z_AXIS, HMI_ValueStruct.Max_Jerk / 10); + else if (HMI_flag.jerk_flag == E_AXIS) planner.set_max_jerk(E_AXIS, HMI_ValueStruct.Max_Jerk / 10); + DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 210, MBASE(select_jerk.now), HMI_ValueStruct.Max_Jerk); return; } - // MaxCorner limit - if (HMI_flag.corner_flag == X_AXIS) - NOMORE(HMI_ValueStruct.Max_Corner, default_max_jerk[X_AXIS] * 2 * MINUNITMULT); - else if (HMI_flag.corner_flag == Y_AXIS) - NOMORE(HMI_ValueStruct.Max_Corner, default_max_jerk[Y_AXIS] * 2 * MINUNITMULT); - else if (HMI_flag.corner_flag == Z_AXIS) - NOMORE(HMI_ValueStruct.Max_Corner, default_max_jerk[Z_AXIS] * 2 * MINUNITMULT); - else if (HMI_flag.corner_flag == E_AXIS) - NOMORE(HMI_ValueStruct.Max_Corner, default_max_jerk[E_AXIS] * 2 * MINUNITMULT); - NOLESS(HMI_ValueStruct.Max_Corner, (MIN_MAXCORNER) * MINUNITMULT); - // MaxCorner value - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 210, MBASE(select_corner.now), HMI_ValueStruct.Max_Corner); + // MaxJerk limit + if (HMI_flag.jerk_flag == X_AXIS) + NOMORE(HMI_ValueStruct.Max_Jerk, default_max_jerk[X_AXIS] * 2 * MINUNITMULT); + else if (HMI_flag.jerk_flag == Y_AXIS) + NOMORE(HMI_ValueStruct.Max_Jerk, default_max_jerk[Y_AXIS] * 2 * MINUNITMULT); + else if (HMI_flag.jerk_flag == Z_AXIS) + NOMORE(HMI_ValueStruct.Max_Jerk, default_max_jerk[Z_AXIS] * 2 * MINUNITMULT); + else if (HMI_flag.jerk_flag == E_AXIS) + NOMORE(HMI_ValueStruct.Max_Jerk, default_max_jerk[E_AXIS] * 2 * MINUNITMULT); + NOLESS(HMI_ValueStruct.Max_Jerk, (MIN_MAXCORNER) * MINUNITMULT); + // MaxJerk value + DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 210, MBASE(select_jerk.now), HMI_ValueStruct.Max_Jerk); } } @@ -1707,7 +1707,7 @@ void HMI_SDCardUpdate(void) { void HMI_StartFrame(const bool with_update) { Goto_MainMenu(); - DWIN_Draw_Rectangle(1, Background_black, 0, 360, 272, 479); + DWIN_Draw_Rectangle(1, Background_black, 0, 360, DWIN_WIDTH, DWIN_HEIGHT - 1); DWIN_ICON_Show(ICON, ICON_HotendTemp, 13, 381); #if HOTENDS > 1 @@ -1724,7 +1724,7 @@ void HMI_StartFrame(const bool with_update) { DWIN_Draw_IntValue(true, true, 0, STAT_FONT, White, Background_black, 3, 178 + 4 * STAT_CHR_W + 6, 382, thermalManager.temp_bed.target); DWIN_Draw_IntValue(true, true, 0, STAT_FONT, White, Background_black, 3, 33 + 2 * STAT_CHR_W, 429, feedrate_percentage); - DWIN_Draw_String(false, false, STAT_FONT, White, Background_black, 33 + (2 + 3) * STAT_CHR_W + 2, 429, F("%")); + DWIN_Draw_String(false, false, STAT_FONT, White, Background_black, 33 + 5 * STAT_CHR_W + 2, 429, F("%")); DWIN_Draw_Signed_Float(STAT_FONT, Background_black, 2, 2, 178, 429, BABY_Z_VAR * 100); DWIN_Draw_String(false, false, STAT_FONT, White, Background_black, 33 + 3 * STAT_CHR_W + 5, 383, F("/")); @@ -1743,23 +1743,23 @@ inline void Draw_Info_Menu() { DWIN_Draw_String(false, false, font8x16, White, Background_black, (DWIN_WIDTH - strlen(SHORT_BUILD_VERSION) * MENU_CHR_W) / 2, 195, (char*)SHORT_BUILD_VERSION); if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 30, 17, 271 - 214, 479 - 450, 14, 8); + DWIN_Frame_AreaCopy(1, 30, 17, 57, 29, 14, 8); - DWIN_Frame_AreaCopy(1, 197, 149, 271 - 19, 479 - 318, 108, 102); - DWIN_Frame_AreaCopy(1, 1, 164, 271 - 215, 479 - 303, 108, 175); - DWIN_Frame_AreaCopy(1, 58, 164, 271 - 158, 479 - 303, 105, 248); + 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_Draw_String(false, false, font8x16, White, Background_black, (DWIN_WIDTH - strlen(CORP_WEBSITE_C) * MENU_CHR_W) / 2, 268, (char*)CORP_WEBSITE_C); } else { #ifdef USE_STRING_HEADINGS Draw_Title(GET_TEXT_F(MSG_INFO_SCREEN)); #else - DWIN_Frame_AreaCopy(1, 190, 16, 271 - 56, 479 - 453, 14, 8); + DWIN_Frame_AreaCopy(1, 190, 16, 215, 26, 14, 8); #endif - DWIN_Frame_AreaCopy(1, 120, 150, 146, 479 - 318, 124, 102); - DWIN_Frame_AreaCopy(1, 146, 151, 271 - 17, 479 - 318, 82, 175); - DWIN_Frame_AreaCopy(1, 0, 165, 271 - 177, 479 - 304, 89, 248); + 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_Draw_String(false, false, font8x16, White, Background_black, (DWIN_WIDTH - strlen(CORP_WEBSITE_E) * MENU_CHR_W) / 2, 268, (char*)CORP_WEBSITE_E); } @@ -1774,13 +1774,13 @@ inline void Draw_Print_File_Menu() { Clear_Title_Bar(); if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 0, 31, 271 - 216, 479 - 435, 14, 8); + DWIN_Frame_AreaCopy(1, 0, 31, 55, 44, 14, 8); } else { #ifdef USE_STRING_HEADINGS Draw_Title("Print file"); // TODO: GET_TEXT_F #else - DWIN_Frame_AreaCopy(1, 52, 31, 271 - 134, 479 - 438, 14, 8); // "Print file" + DWIN_Frame_AreaCopy(1, 52, 31, 137, 41, 14, 8); // "Print file" #endif } @@ -2054,8 +2054,7 @@ void HMI_Printing(void) { Popup_window_PauseOrStop(); break; - default: - break; + default: break; } } DWIN_UpdateLCD(); @@ -2121,25 +2120,25 @@ inline void Draw_Move_Menu() { Clear_Main_Window(); if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 192, 1, 271 - 38, 479 - 465, 14, 8); - DWIN_Frame_AreaCopy(1, 58, 118, 271 - 165, 479 - 347, LBLX, MBASE(1)); - DWIN_Frame_AreaCopy(1, 109, 118, 271 - 114, 479 - 347, LBLX, MBASE(2)); - DWIN_Frame_AreaCopy(1, 160, 118, 271 - 62, 479 - 347, LBLX, MBASE(3)); + DWIN_Frame_AreaCopy(1, 192, 1, 233, 14, 14, 8); + 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)); #if HAS_HOTEND - DWIN_Frame_AreaCopy(1, 212, 118, 271 - 18, 479 - 348, LBLX, MBASE(4)); + DWIN_Frame_AreaCopy(1, 212, 118, 253, 131, LBLX, MBASE(4)); #endif } else { #ifdef USE_STRING_HEADINGS Draw_Title(GET_TEXT_F(MSG_MOVE_AXIS)); #else - DWIN_Frame_AreaCopy(1, 231, 2, 271 - 6, 479 - 467, 14, 8); + DWIN_Frame_AreaCopy(1, 231, 2, 265, 12, 14, 8); #endif - draw_move_en(MBASE(1)); say_x(33 + 3, MBASE(1)); // "Move X" - draw_move_en(MBASE(2)); say_y(33 + 3, MBASE(2)); // "Move Y" - draw_move_en(MBASE(3)); say_z(33 + 3, MBASE(3)); // "Move Z" + 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, 271 - 95, 479 - 277, LBLX, MBASE(4)); // "Extruder" + DWIN_Frame_AreaCopy(1, 123, 192, 176, 202, LBLX, MBASE(4)); // "Extruder" #endif } @@ -2277,8 +2276,7 @@ void HMI_Prepare(void) { } Draw_Prepare_Menu(); break; - default: - break; + default: break; } } DWIN_UpdateLCD(); @@ -2288,13 +2286,13 @@ void Draw_Temperature_Menu() { Clear_Main_Window(); if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 236, 2, 271 - 8, 479 - 466, 14, 8); + DWIN_Frame_AreaCopy(1, 236, 2, 263, 13, 14, 8); - DWIN_Frame_AreaCopy(1, 1, 134, 271 - 215, 479 - 333, LBLX, MBASE(1)); - DWIN_Frame_AreaCopy(1, 58, 134, 271 - 158, 479 - 333, LBLX, MBASE(2)); - DWIN_Frame_AreaCopy(1, 115, 134, 271 - 101, 479 - 333, LBLX, MBASE(3)); - DWIN_Frame_AreaCopy(1, 100, 89, 271 - 93, 479 - 378, LBLX, MBASE(4)); - DWIN_Frame_AreaCopy(1, 180, 89, 271 - 11, 479 - 379, LBLX, MBASE(5)); + DWIN_Frame_AreaCopy(1, 1, 134, 56, 146, LBLX, MBASE(1)); + DWIN_Frame_AreaCopy(1, 58, 134, 113, 146, LBLX, MBASE(2)); + DWIN_Frame_AreaCopy(1, 115, 134, 170, 146, LBLX, MBASE(3)); + DWIN_Frame_AreaCopy(1, 100, 89, 178, 101, LBLX, MBASE(4)); + DWIN_Frame_AreaCopy(1, 180, 89, 260, 100, LBLX, MBASE(5)); } else { #ifdef USE_STRING_HEADINGS @@ -2305,18 +2303,18 @@ void Draw_Temperature_Menu() { DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 3), F("PLA Preheat Settings")); DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 4), F("ABS Preheat Settings")); #else - DWIN_Frame_AreaCopy(1, 56, 16, 271 - 130, 479 - 450 - 1, 14, 8); - DWIN_Frame_AreaCopy(1, 197, 104, 271 - 33, 479 - 365, LBLX, MBASE(1)); // Nozzle... - DWIN_Frame_AreaCopy(1, 1, 89, 271 - 188, 479 - 377 - 1, LBLX + 41 + 3, MBASE(1)); // ...Temperature - DWIN_Frame_AreaCopy(1, 240, 104, 271 - 7, 479 - 365, LBLX, MBASE(2)); // Bed... - DWIN_Frame_AreaCopy(1, 1, 89, 271 - 188, 479 - 377 - 1, LBLX + 24 + 3, MBASE(2)); // ...Temperature - DWIN_Frame_AreaCopy(1, 0, 119, 271 - 207, 479 - 347, LBLX, MBASE(3)); // Fan speed - DWIN_Frame_AreaCopy(1, 107, 76, 271 - 115, 479 - 393, LBLX, MBASE(4)); // Preheat... - DWIN_Frame_AreaCopy(1, 157, 76, 181, 479 - 393, LBLX + 49 + 3, MBASE(4)); // ...PLA - DWIN_Frame_AreaCopy(1, 131, 119, 271 - 89, 479 - 347, LBLX + 49 + 24 + 6, MBASE(4)); // PLA setting - DWIN_Frame_AreaCopy(1, 107, 76, 271 - 115, 479 - 393, LBLX, MBASE(5)); // Preheat... - DWIN_Frame_AreaCopy(1, 172, 76, 198, 479 - 393, LBLX + 49 + 3, MBASE(5)); // ...ABS - DWIN_Frame_AreaCopy(1, 131, 119, 271 - 89, 479 - 347, LBLX + 49 + 3 + 26 + 3, MBASE(5)); // ABS setting + DWIN_Frame_AreaCopy(1, 56, 16, 141, 28, 14, 8); + DWIN_Frame_AreaCopy(1, 197, 104, 238, 114, LBLX, MBASE(1)); // Nozzle... + DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX + 44, MBASE(1)); // ...Temperature + DWIN_Frame_AreaCopy(1, 240, 104, 264, 114, LBLX, MBASE(2)); // Bed... + DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX + 27, MBASE(2)); // ...Temperature + DWIN_Frame_AreaCopy(1, 0, 119, 64, 132, LBLX, MBASE(3)); // Fan speed + DWIN_Frame_AreaCopy(1, 107, 76, 156, 86, LBLX, MBASE(4)); // Preheat... + DWIN_Frame_AreaCopy(1, 157, 76, 181, 86, LBLX + 52, MBASE(4)); // ...PLA + DWIN_Frame_AreaCopy(1, 131, 119, 182, 132, LBLX + 79, MBASE(4)); // PLA setting + DWIN_Frame_AreaCopy(1, 107, 76, 156, 86, LBLX, MBASE(5)); // Preheat... + DWIN_Frame_AreaCopy(1, 172, 76, 198, 86, LBLX + 52, MBASE(5)); // ...ABS + DWIN_Frame_AreaCopy(1, 131, 119, 182, 132, LBLX + 81, MBASE(5)); // ABS setting #endif } @@ -2351,9 +2349,9 @@ void HMI_Control(void) { if (index_control > MROWS) { Draw_More_Icon(6 + MROWS - index_control); // Info > if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 231, 104, 271 - 13, 479 - 363, LBLX, MBASE(5)); + DWIN_Frame_AreaCopy(1, 231, 104, 258, 116, LBLX, MBASE(5)); else - DWIN_Frame_AreaCopy(1, 0, 104, 271 - 247, 479 - 365, LBLX, MBASE(5)); + DWIN_Frame_AreaCopy(1, 0, 104, 24, 114, LBLX, MBASE(5)); } } else { @@ -2414,8 +2412,7 @@ void HMI_Control(void) { checkkey = Info; Draw_Info_Menu(); break; - default: - break; + default: break; } } DWIN_UpdateLCD(); @@ -2563,15 +2560,15 @@ void HMI_Temperature(void) { Clear_Main_Window(); if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 59, 16, 271 - 132, 479 - 450, 14, 8); - - DWIN_Frame_AreaCopy(1, 100, 89, 124, 479 - 378, LBLX, MBASE(1)); - DWIN_Frame_AreaCopy(1, 1, 134, 271 - 215, 479 - 333, LBLX + 24, MBASE(1)); // PLA nozzle temp - DWIN_Frame_AreaCopy(1, 100, 89, 124, 479 - 378, LBLX, MBASE(2)); - DWIN_Frame_AreaCopy(1, 58, 134, 271 - 158, 479 - 333, LBLX + 24, MBASE(2)); // PLA bed temp - DWIN_Frame_AreaCopy(1, 100, 89, 124, 479 - 378, LBLX, MBASE(3)); - DWIN_Frame_AreaCopy(1, 115, 134, 271 - 101, 479 - 333, LBLX + 24, MBASE(3)); // PLA fan speed - DWIN_Frame_AreaCopy(1, 72, 148, 271 - 120, 479 - 317, LBLX, MBASE(4)); // save PLA configuration + DWIN_Frame_AreaCopy(1, 59, 16, 139, 29, 14, 8); + + DWIN_Frame_AreaCopy(1, 100, 89, 124, 101, LBLX, MBASE(1)); + DWIN_Frame_AreaCopy(1, 1, 134, 56, 146, LBLX + 24, MBASE(1)); // PLA nozzle temp + DWIN_Frame_AreaCopy(1, 100, 89, 124, 101, LBLX, MBASE(2)); + DWIN_Frame_AreaCopy(1, 58, 134, 113, 146, LBLX + 24, MBASE(2)); // PLA bed temp + DWIN_Frame_AreaCopy(1, 100, 89, 124, 101, LBLX, MBASE(3)); + DWIN_Frame_AreaCopy(1, 115, 134, 170, 146, LBLX + 24, MBASE(3)); // PLA fan speed + DWIN_Frame_AreaCopy(1, 72, 148, 151, 162, LBLX, MBASE(4)); // save PLA configuration } else { #ifdef USE_STRING_HEADINGS @@ -2581,16 +2578,16 @@ void HMI_Temperature(void) { DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 2), GET_TEXT_F(MSG_FAN_SPEED)); DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 3), GET_TEXT_F(MSG_STORE_EEPROM)); #else - DWIN_Frame_AreaCopy(1, 56, 16, 271 - 130, 479 - 450 - 1, 14, 8); - DWIN_Frame_AreaCopy(1, 157, 76, 181, 479 - 393, LBLX, MBASE(1)); - DWIN_Frame_AreaCopy(1, 197, 104, 271 - 33, 479 - 365, LBLX + 24 + 3, MBASE(1)); - DWIN_Frame_AreaCopy(1, 1, 89, 271 - 188, 479 - 377 - 1, LBLX + 24 + 41 + 6, MBASE(1)); // PLA nozzle temp - DWIN_Frame_AreaCopy(1, 157, 76, 181, 479 - 393, LBLX, MBASE(2) + 3); - DWIN_Frame_AreaCopy(1, 240, 104, 271 - 7, 479 - 365, LBLX + 24 + 3, MBASE(2) + 3); - DWIN_Frame_AreaCopy(1, 1, 89, 271 - 188, 479 - 377 - 1, LBLX + 24 + 24 + 6, MBASE(2) + 3); // PLA bed temp - DWIN_Frame_AreaCopy(1, 157, 76, 181, 479 - 393, LBLX, MBASE(3)); - DWIN_Frame_AreaCopy(1, 0, 119, 271 - 207, 479 - 347, LBLX + 24 + 3, MBASE(3)); // PLA fan speed - DWIN_Frame_AreaCopy(1, 97, 165, 271 - 42, 479 - 301 - 1, LBLX, MBASE(4)); // save PLA configuration + DWIN_Frame_AreaCopy(1, 56, 16, 141, 28, 14, 8); + DWIN_Frame_AreaCopy(1, 157, 76, 181, 86, LBLX, MBASE(1)); + DWIN_Frame_AreaCopy(1, 197, 104, 238, 114, LBLX + 27, MBASE(1)); + DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX + 71, MBASE(1)); // PLA nozzle temp + DWIN_Frame_AreaCopy(1, 157, 76, 181, 86, LBLX, MBASE(2) + 3); + DWIN_Frame_AreaCopy(1, 240, 104, 264, 114, LBLX + 27, MBASE(2) + 3); + DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX + 54, MBASE(2) + 3); // PLA bed temp + DWIN_Frame_AreaCopy(1, 157, 76, 181, 86, LBLX, MBASE(3)); + DWIN_Frame_AreaCopy(1, 0, 119, 64, 132, LBLX + 27, MBASE(3)); // PLA fan speed + DWIN_Frame_AreaCopy(1, 97, 165, 229, 177, LBLX, MBASE(4)); // save PLA configuration #endif } @@ -2617,16 +2614,16 @@ void HMI_Temperature(void) { Clear_Main_Window(); if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 142, 16, 271 - 48, 479 - 450, 14, 8); - - DWIN_Frame_AreaCopy(1, 180, 89, 204, 479 - 379, LBLX, MBASE(1)); - DWIN_Frame_AreaCopy(1, 1, 134, 271 - 215, 479 - 333, LBLX + 24, MBASE(1)); // ABS nozzle temp - DWIN_Frame_AreaCopy(1, 180, 89, 204, 479 - 379, LBLX, MBASE(2)); - DWIN_Frame_AreaCopy(1, 58, 134, 271 - 158, 479 - 333, LBLX + 24, MBASE(2)); // ABS bed temp - DWIN_Frame_AreaCopy(1, 180, 89, 204, 479 - 379, LBLX, MBASE(3)); - DWIN_Frame_AreaCopy(1, 115, 134, 271 - 101, 479 - 333, LBLX + 24, MBASE(3)); // ABS fan speed - DWIN_Frame_AreaCopy(1, 72, 148, 271 - 120, 479 - 317, LBLX, MBASE(4)); - DWIN_Frame_AreaCopy(1, 180, 89, 204, 479 - 379, LBLX + 28, MBASE(4) + 2); // save ABS configuration + DWIN_Frame_AreaCopy(1, 142, 16, 223, 29, 14, 8); + + DWIN_Frame_AreaCopy(1, 180, 89, 204, 100, LBLX, MBASE(1)); + DWIN_Frame_AreaCopy(1, 1, 134, 56, 146, LBLX + 24, MBASE(1)); // ABS nozzle temp + DWIN_Frame_AreaCopy(1, 180, 89, 204, 100, LBLX, MBASE(2)); + DWIN_Frame_AreaCopy(1, 58, 134, 113, 146, LBLX + 24, MBASE(2)); // ABS bed temp + DWIN_Frame_AreaCopy(1, 180, 89, 204, 100, LBLX, MBASE(3)); + DWIN_Frame_AreaCopy(1, 115, 134, 170, 146, LBLX + 24, MBASE(3)); // ABS fan speed + DWIN_Frame_AreaCopy(1, 72, 148, 151, 162, LBLX, MBASE(4)); + DWIN_Frame_AreaCopy(1, 180, 89, 204, 100, LBLX + 28, MBASE(4) + 2); // save ABS configuration } else { #ifdef USE_STRING_HEADINGS @@ -2636,17 +2633,17 @@ void HMI_Temperature(void) { DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 2), GET_TEXT_F(MSG_FAN_SPEED)); DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 3), GET_TEXT_F(MSG_STORE_EEPROM)); #else - DWIN_Frame_AreaCopy(1, 56, 16, 271 - 130, 479 - 450 - 1, 14, 8); - DWIN_Frame_AreaCopy(1, 172, 76, 198, 479 - 393, LBLX, MBASE(1)); - DWIN_Frame_AreaCopy(1, 197, 104, 271 - 33, 479 - 365, LBLX + 24 + 3, MBASE(1)); - DWIN_Frame_AreaCopy(1, 1, 89, 271 - 188, 479 - 377 - 1, LBLX + 24 + 41 + 6, MBASE(1)); // ABS nozzle temp - DWIN_Frame_AreaCopy(1, 172, 76, 198, 479 - 393, LBLX, MBASE(2) + 3); - DWIN_Frame_AreaCopy(1, 240, 104, 271 - 7, 479 - 365, LBLX + 24 + 3, MBASE(2) + 3); - DWIN_Frame_AreaCopy(1, 1, 89, 271 - 188, 479 - 377 - 1, LBLX + 24 + 24 + 6, MBASE(2) + 3); // ABS bed temp - DWIN_Frame_AreaCopy(1, 172, 76, 198, 479 - 393, LBLX, MBASE(3)); - DWIN_Frame_AreaCopy(1, 0, 119, 271 - 207, 479 - 347, LBLX + 24 + 3, MBASE(3)); // ABS fan speed - DWIN_Frame_AreaCopy(1, 97, 165, 271 - 42, 479 - 301 - 1, LBLX, MBASE(4)); - DWIN_Frame_AreaCopy(1, 172, 76, 198, 479 - 393, LBLX + 33, MBASE(4)); // save ABS configuration + DWIN_Frame_AreaCopy(1, 56, 16, 141, 28, 14, 8); + DWIN_Frame_AreaCopy(1, 172, 76, 198, 86, LBLX, MBASE(1)); + DWIN_Frame_AreaCopy(1, 197, 104, 238, 114, LBLX + 27, MBASE(1)); + DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX + 71, MBASE(1)); // ABS nozzle temp + DWIN_Frame_AreaCopy(1, 172, 76, 198, 86, LBLX, MBASE(2) + 3); + DWIN_Frame_AreaCopy(1, 240, 104, 264, 114, LBLX + 27, MBASE(2) + 3); + DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX + 54, MBASE(2) + 3); // ABS bed temp + DWIN_Frame_AreaCopy(1, 172, 76, 198, 86, LBLX, MBASE(3)); + DWIN_Frame_AreaCopy(1, 0, 119, 64, 132, LBLX + 27, MBASE(3)); // ABS fan speed + DWIN_Frame_AreaCopy(1, 97, 165, 229, 177, LBLX, MBASE(4)); + DWIN_Frame_AreaCopy(1, 172, 76, 198, 86, LBLX + 33, MBASE(4)); // save ABS configuration #endif } @@ -2674,20 +2671,20 @@ inline void Draw_Max_Speed_Menu() { Clear_Main_Window(); if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 1, 16, 271 - 243, 479 - 451, 14, 8); + DWIN_Frame_AreaCopy(1, 1, 16, 28, 28, 14, 8); auto say_max_speed = [](const uint16_t row) { - DWIN_Frame_AreaCopy(1, 173, 133, 228, 479 - 332, LBLX, row); // "Max speed" + DWIN_Frame_AreaCopy(1, 173, 133, 228, 147, LBLX, row); // "Max speed" }; - say_max_speed(MBASE(1)); // "Max speed" - DWIN_Frame_AreaCopy(1, 229, 133, 236, 479 - 332, LBLX + 55 + 3, MBASE(1)); // X - say_max_speed(MBASE(2)); // "Max speed" - DWIN_Frame_AreaCopy(1, 1, 150, 271 - 264, 479 - 319, LBLX + 55 + 3, MBASE(2) + 3); // Y - say_max_speed(MBASE(3)); // "Max speed" - DWIN_Frame_AreaCopy(1, 9, 150, 271 - 255, 479 - 319, LBLX + 55 + 3, MBASE(3) + 3); // Z - say_max_speed(MBASE(4)); // "Max speed" - DWIN_Frame_AreaCopy(1, 18, 150, 271 - 246, 479 - 319, LBLX + 55 + 3, MBASE(4) + 3); // E + 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(MBASE(4)); // "Max speed" + DWIN_Frame_AreaCopy(1, 18, 150, 25, 160, LBLX + 58, MBASE(4) + 3); // E } else { #ifdef USE_STRING_HEADINGS @@ -2697,22 +2694,22 @@ inline void Draw_Max_Speed_Menu() { DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 2), F("Max Feedrate Z")); DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 3), F("Max Feedrate E")); #else - DWIN_Frame_AreaCopy(1, 144, 16, 271 - 82, 479 - 453, 14, 8); + DWIN_Frame_AreaCopy(1, 144, 16, 189, 26, 14, 8); draw_max_en(MBASE(1)); // "Max" - DWIN_Frame_AreaCopy(1, 184, 119, 271 - 37, 479 - 347, LBLX + 24 + 3, MBASE(1)); // "Speed X" + DWIN_Frame_AreaCopy(1, 184, 119, 234, 132, LBLX + 27, MBASE(1)); // "Speed X" draw_max_en(MBASE(2)); // "Max" - draw_speed_en(24 + 3, MBASE(2)); // "Speed" - say_y(24 + 40 + 6, MBASE(2)); // "Y" + draw_speed_en(27, MBASE(2)); // "Speed" + say_y(70, MBASE(2)); // "Y" draw_max_en(MBASE(3)); // "Max" - draw_speed_en(24 + 3, MBASE(3)); // "Speed" - say_z(24 + 40 + 6, MBASE(3)); // "Z" + draw_speed_en(27, MBASE(3)); // "Speed" + say_z(70, MBASE(3)); // "Z" draw_max_en(MBASE(4)); // "Max" - draw_speed_en(24 + 3, MBASE(4)); // "Speed" - say_e(24 + 40 + 6, MBASE(4)); // "E" + draw_speed_en(27, MBASE(4)); // "Speed" + say_e(70, MBASE(4)); // "E" #endif } @@ -2729,20 +2726,20 @@ inline void Draw_Max_Accel_Menu() { Clear_Main_Window(); if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 1, 16, 271 - 243, 479 - 451, 14, 8); - - DWIN_Frame_AreaCopy(1, 173, 133, 200, 479 - 332, LBLX, MBASE(1)); - DWIN_Frame_AreaCopy(1, 28, 149, 271 - 202, 479 - 318, LBLX + 27, MBASE(1) + 1); - DWIN_Frame_AreaCopy(1, 229, 133, 236, 479 - 332, LBLX + 27 + 41 + 3, MBASE(1)); // max acceleration X - DWIN_Frame_AreaCopy(1, 173, 133, 200, 479 - 332, LBLX, MBASE(2)); - DWIN_Frame_AreaCopy(1, 28, 149, 271 - 202, 479 - 318, LBLX + 27, MBASE(2) + 1); - DWIN_Frame_AreaCopy(1, 1, 150, 271 - 264, 479 - 319, LBLX + 27 + 41 + 3, MBASE(2) + 2); // max acceleration Y - DWIN_Frame_AreaCopy(1, 173, 133, 200, 479 - 332, LBLX, MBASE(3)); - DWIN_Frame_AreaCopy(1, 28, 149, 271 - 202, 479 - 318, LBLX + 27, MBASE(3) + 1); - DWIN_Frame_AreaCopy(1, 9, 150, 271 - 255, 479 - 319, LBLX + 27 + 41 + 3, MBASE(3) + 2); // max acceleration Z - DWIN_Frame_AreaCopy(1, 173, 133, 200, 479 - 332, LBLX, MBASE(4)); - DWIN_Frame_AreaCopy(1, 28, 149, 271 - 202, 479 - 318, LBLX + 27, MBASE(4) + 1); - DWIN_Frame_AreaCopy(1, 18, 150, 271 - 246, 479 - 319, LBLX + 27 + 41 + 3, MBASE(4) + 2); // max acceleration E + DWIN_Frame_AreaCopy(1, 1, 16, 28, 28, 14, 8); + + 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 + 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 } else { #ifdef USE_STRING_HEADINGS @@ -2752,11 +2749,11 @@ inline void Draw_Max_Accel_Menu() { DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 2), F("Max Accel Z")); DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 3), F("Max Accel E")); #else - DWIN_Frame_AreaCopy(1, 144, 16, 271 - 82, 479 - 453, 14, 8); - draw_max_accel_en(MBASE(1)); say_x(24 + 78 + 6, MBASE(1)); // "Max Acceleration X" - draw_max_accel_en(MBASE(2)); say_y(24 + 78 + 6, MBASE(2)); // "Max Acceleration Y" - draw_max_accel_en(MBASE(3)); say_z(24 + 78 + 6, MBASE(3)); // "Max Acceleration Z" - draw_max_accel_en(MBASE(4)); say_e(24 + 78 + 6, MBASE(4)); // "Max Acceleration E" + DWIN_Frame_AreaCopy(1, 144, 16, 189, 26, 14, 8); + 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" + draw_max_accel_en(MBASE(4)); say_e(108, MBASE(4)); // "Max Acceleration E" #endif } @@ -2773,24 +2770,24 @@ inline void Draw_Max_Jerk_Menu() { Clear_Main_Window(); if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 1, 16, 271 - 243, 479 - 451, 14, 8); - - DWIN_Frame_AreaCopy(1, 173, 133, 200, 479 - 332, LBLX, MBASE(1)); - DWIN_Frame_AreaCopy(1, 1, 180, 271 - 243, 479 - 287, LBLX + 27, MBASE(1) + 1); - DWIN_Frame_AreaCopy(1, 202, 133, 228, 479 - 332, LBLX + 53, MBASE(1)); - DWIN_Frame_AreaCopy(1, 229, 133, 236, 479 - 332, LBLX + 80 + 3, MBASE(1)); // max corner speed X - DWIN_Frame_AreaCopy(1, 173, 133, 200, 479 - 332, LBLX, MBASE(2)); - DWIN_Frame_AreaCopy(1, 1, 180, 271 - 243, 479 - 287, LBLX + 27, MBASE(2) + 1); - DWIN_Frame_AreaCopy(1, 202, 133, 228, 479 - 332, LBLX + 53, MBASE(2)); - DWIN_Frame_AreaCopy(1, 1, 150, 271 - 264, 479 - 319, LBLX + 80 + 3, MBASE(2) + 3); // max corner speed Y - DWIN_Frame_AreaCopy(1, 173, 133, 200, 479 - 332, LBLX, MBASE(3)); - DWIN_Frame_AreaCopy(1, 1, 180, 271 - 243, 479 - 287, LBLX + 27, MBASE(3) + 1); - DWIN_Frame_AreaCopy(1, 202, 133, 228, 479 - 332, LBLX + 53, MBASE(3)); - DWIN_Frame_AreaCopy(1, 9, 150, 271 - 255, 479 - 319, LBLX + 80 + 3, MBASE(3) + 3); // max corner speed Z - DWIN_Frame_AreaCopy(1, 173, 133, 200, 479 - 332, LBLX, MBASE(4)); - DWIN_Frame_AreaCopy(1, 1, 180, 271 - 243, 479 - 287, LBLX + 27, MBASE(4) + 1); - DWIN_Frame_AreaCopy(1, 202, 133, 228, 479 - 332, LBLX + 53, MBASE(4)); - DWIN_Frame_AreaCopy(1, 18, 150, 271 - 246, 479 - 319, LBLX + 80 + 3, MBASE(4) + 3); // max corner speed E + DWIN_Frame_AreaCopy(1, 1, 16, 28, 28, 14, 8); + + 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 + 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 } else { #ifdef USE_STRING_HEADINGS @@ -2800,31 +2797,31 @@ inline void Draw_Max_Jerk_Menu() { DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 2), F("Max Jerk Z")); DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 3), F("Max Jerk E")); #else - DWIN_Frame_AreaCopy(1, 144, 16, 271 - 82, 479 - 453, 14, 8); - draw_max_en(MBASE(1)); // "Max" - draw_corner_en(MBASE(1)); // "Corner" - draw_speed_en(66 + 6, MBASE(1)); // "Speed" - say_x(106 + 9, MBASE(1)); // "X" - - draw_max_en(MBASE(2)); // "Max" - draw_corner_en(MBASE(2)); // "Corner" - draw_speed_en(66 + 6, MBASE(2)); // "Speed" - say_y(106 + 9, MBASE(2)); // "Y" - - draw_max_en(MBASE(3)); // "Max" - draw_corner_en(MBASE(3)); // "Corner" - draw_speed_en(66 + 6, MBASE(3)); // "Speed" - say_z(106 + 9, MBASE(3)); // "Z" - - draw_max_en(MBASE(4)); // "Max" - draw_corner_en(MBASE(4)); // "Corner" - draw_speed_en(66 + 6, MBASE(4)); // "Speed" - say_e(106 + 9, MBASE(4)); // "E" + DWIN_Frame_AreaCopy(1, 144, 16, 189, 26, 14, 8); + 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" + + 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" #endif } Draw_Back_First(); - LOOP_L_N(i, 4) Draw_Menu_Line(i + 1, ICON_MaxSpeedCornerX + i); + LOOP_L_N(i, 4) Draw_Menu_Line(i + 1, ICON_MaxSpeedJerkX + i); DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 210, MBASE(1), planner.max_jerk[X_AXIS] * MINUNITMULT); DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 210, MBASE(2), planner.max_jerk[Y_AXIS] * MINUNITMULT); @@ -2836,16 +2833,16 @@ inline void Draw_Steps_Menu() { Clear_Main_Window(); if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 1, 16, 271 - 243, 479 - 451, 14, 8); + DWIN_Frame_AreaCopy(1, 1, 16, 28, 28, 14, 8); - DWIN_Frame_AreaCopy(1, 153, 148, 271 - 77, 479 - 318, LBLX, MBASE(1)); - DWIN_Frame_AreaCopy(1, 229, 133, 236, 479 - 332, LBLX + 41 + 3, MBASE(1)); // Transmission Ratio X - DWIN_Frame_AreaCopy(1, 153, 148, 271 - 77, 479 - 318, LBLX, MBASE(2)); - DWIN_Frame_AreaCopy(1, 1, 150, 271 - 264, 479 - 319, LBLX + 41 + 3, MBASE(2) + 3); // Transmission Ratio Y - DWIN_Frame_AreaCopy(1, 153, 148, 271 - 77, 479 - 318, LBLX, MBASE(3)); - DWIN_Frame_AreaCopy(1, 9, 150, 271 - 255, 479 - 319, LBLX + 41 + 3, MBASE(3) + 3); // Transmission Ratio Z - DWIN_Frame_AreaCopy(1, 153, 148, 271 - 77, 479 - 318, LBLX, MBASE(4)); - DWIN_Frame_AreaCopy(1, 18, 150, 271 - 246, 479 - 319, LBLX + 41 + 3, MBASE(4) + 3); // Transmission Ratio E + 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 + 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 } else { #ifdef USE_STRING_HEADINGS @@ -2855,11 +2852,11 @@ inline void Draw_Steps_Menu() { DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 2), F("Steps/mm Z")); DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 3), F("Steps/mm E")); #else - DWIN_Frame_AreaCopy(1, 144, 16, 271 - 82, 479 - 453, 14, 8); - draw_steps_per_mm(MBASE(1)); say_x(100 + 3, MBASE(1)); // "Steps-per-mm X" - draw_steps_per_mm(MBASE(2)); say_y(100 + 3, MBASE(2)); // "Y" - draw_steps_per_mm(MBASE(3)); say_z(100 + 3, MBASE(3)); // "Z" - draw_steps_per_mm(MBASE(4)); say_e(100 + 3, MBASE(4)); // "E" + DWIN_Frame_AreaCopy(1, 144, 16, 189, 26, 14, 8); + 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" + draw_steps_per_mm(MBASE(4)); say_e(103, MBASE(4)); // "E" #endif } @@ -2902,9 +2899,9 @@ void HMI_Motion(void) { select_acc.reset(); Draw_Max_Accel_Menu(); break; - case 3: // max corner speed - checkkey = MaxCorner; - select_corner.reset(); + case 3: // max jerk speed + checkkey = MaxJerk; + select_jerk.reset(); Draw_Max_Jerk_Menu(); break; case 4: // transmission ratio @@ -2912,8 +2909,7 @@ void HMI_Motion(void) { select_step.reset(); Draw_Steps_Menu(); break; - default: - break; + default: break; } } DWIN_UpdateLCD(); @@ -3139,8 +3135,7 @@ void HMI_ABSPreheatSetting(void) { HMI_AudioFeedback(success); } break; #endif - default: - break; + default: break; } } DWIN_UpdateLCD(); @@ -3193,8 +3188,7 @@ void HMI_MaxSpeed(void) { DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 4, 210, MBASE(select_speed.now), HMI_ValueStruct.Max_Feedspeed); EncoderRate.encoderRateEnabled = 1; break; - default: - break; + default: break; } } DWIN_UpdateLCD(); @@ -3247,62 +3241,60 @@ void HMI_MaxAcceleration(void) { DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 4, 210, MBASE(select_acc.now), HMI_ValueStruct.Max_Acceleration); EncoderRate.encoderRateEnabled = 1; break; - default: - break; + default: break; } } DWIN_UpdateLCD(); } -/* Max Corner */ -void HMI_MaxCorner(void) { +/* Max Jerk */ +void HMI_MaxJerk(void) { 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_corner.inc(4)) Move_Highlight(1, select_corner.now); + if (select_jerk.inc(4)) Move_Highlight(1, select_jerk.now); } else if (encoder_diffState == ENCODER_DIFF_CCW) { - if (select_corner.dec()) Move_Highlight(-1, select_corner.now); + if (select_jerk.dec()) Move_Highlight(-1, select_jerk.now); } else if (encoder_diffState == ENCODER_DIFF_ENTER) { - switch (select_corner.now) { + switch (select_jerk.now) { case 0: // back checkkey = Motion; select_motion.now = 3; Draw_Motion_Menu(); break; - case 1: // max corner X - checkkey = MaxCorner_value; - HMI_flag.corner_flag = X_AXIS; - HMI_ValueStruct.Max_Corner = planner.max_jerk[X_AXIS] * MINUNITMULT; - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 210, MBASE(select_corner.now), HMI_ValueStruct.Max_Corner); + case 1: // max jerk X + checkkey = MaxJerk_value; + HMI_flag.jerk_flag = X_AXIS; + HMI_ValueStruct.Max_Jerk = planner.max_jerk[X_AXIS] * MINUNITMULT; + DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 210, MBASE(select_jerk.now), HMI_ValueStruct.Max_Jerk); EncoderRate.encoderRateEnabled = 1; break; - case 2: // max corner Y - checkkey = MaxCorner_value; - HMI_flag.corner_flag = Y_AXIS; - HMI_ValueStruct.Max_Corner = planner.max_jerk[Y_AXIS] * MINUNITMULT; - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 210, MBASE(select_corner.now), HMI_ValueStruct.Max_Corner); + case 2: // max jerk Y + checkkey = MaxJerk_value; + HMI_flag.jerk_flag = Y_AXIS; + HMI_ValueStruct.Max_Jerk = planner.max_jerk[Y_AXIS] * MINUNITMULT; + DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 210, MBASE(select_jerk.now), HMI_ValueStruct.Max_Jerk); EncoderRate.encoderRateEnabled = 1; break; - case 3: // max corner Z - checkkey = MaxCorner_value; - HMI_flag.corner_flag = Z_AXIS; - HMI_ValueStruct.Max_Corner = planner.max_jerk[Z_AXIS] * MINUNITMULT; - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 210, MBASE(select_corner.now), HMI_ValueStruct.Max_Corner); + case 3: // max jerk Z + checkkey = MaxJerk_value; + HMI_flag.jerk_flag = Z_AXIS; + HMI_ValueStruct.Max_Jerk = planner.max_jerk[Z_AXIS] * MINUNITMULT; + DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 210, MBASE(select_jerk.now), HMI_ValueStruct.Max_Jerk); EncoderRate.encoderRateEnabled = 1; break; - case 4: // max corner E - checkkey = MaxCorner_value; - HMI_flag.corner_flag = E_AXIS; - HMI_ValueStruct.Max_Corner = planner.max_jerk[E_AXIS] * MINUNITMULT; - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 210, MBASE(select_corner.now), HMI_ValueStruct.Max_Corner); + case 4: // max jerk E + checkkey = MaxJerk_value; + HMI_flag.jerk_flag = E_AXIS; + HMI_ValueStruct.Max_Jerk = planner.max_jerk[E_AXIS] * MINUNITMULT; + DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 210, MBASE(select_jerk.now), HMI_ValueStruct.Max_Jerk); EncoderRate.encoderRateEnabled = 1; break; - default: - break; + default: break; } } DWIN_UpdateLCD(); @@ -3355,8 +3347,7 @@ void HMI_Step(void) { DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 210, MBASE(select_step.now), HMI_ValueStruct.Max_Step); EncoderRate.encoderRateEnabled = 1; break; - default: - break; + default: break; } } DWIN_UpdateLCD(); @@ -3406,7 +3397,7 @@ void EachMomentUpdate(void) { // show print done confirm DWIN_Draw_Rectangle(1, Background_black, 0, 250, 271, 360); - DWIN_ICON_Show(ICON, HMI_flag.language_chinese ? ICON_Confirm_C : ICON_Confirm_E, 86, 302 - 19); + DWIN_ICON_Show(ICON, HMI_flag.language_chinese ? ICON_Confirm_C : ICON_Confirm_E, 86, 283); } else if (HMI_flag.pause_flag != printingIsPaused()) { // print status update @@ -3553,7 +3544,7 @@ void DWIN_HandleScreen(void) { case ABSPreheat: HMI_ABSPreheatSetting(); break; case MaxSpeed: HMI_MaxSpeed(); break; case MaxAcceleration: HMI_MaxAcceleration(); break; - case MaxCorner: HMI_MaxCorner(); break; + case MaxJerk: HMI_MaxJerk(); break; case Step: HMI_Step(); break; case Move_X: HMI_Move_X(); break; case Move_Y: HMI_Move_Y(); break; @@ -3572,7 +3563,7 @@ void DWIN_HandleScreen(void) { case PrintSpeed: HMI_PrintSpeed(); break; case MaxSpeed_value: HMI_MaxFeedspeedXYZE(); break; case MaxAcceleration_value: HMI_MaxAccelerationXYZE(); break; - case MaxCorner_value: HMI_MaxCornerXYZE(); break; + case MaxJerk_value: HMI_MaxJerkXYZE(); break; case Step_value: HMI_StepXYZE(); break; default: break; } diff --git a/Marlin/src/lcd/dwin/e3v2/dwin.h b/Marlin/src/lcd/dwin/e3v2/dwin.h index e5d95f61661c..467cc433e7b0 100644 --- a/Marlin/src/lcd/dwin/e3v2/dwin.h +++ b/Marlin/src/lcd/dwin/e3v2/dwin.h @@ -52,8 +52,8 @@ enum processID { MaxSpeed_value, MaxAcceleration, MaxAcceleration_value, - MaxCorner, - MaxCorner_value, + MaxJerk, + MaxJerk_value, Step, Step_value, @@ -150,7 +150,7 @@ enum processID { #define ICON_MaxSpeed 51 #define ICON_MaxAccelerated 52 -#define ICON_MaxCorner 53 +#define ICON_MaxJerk 53 #define ICON_Step 54 #define ICON_PrintSize 55 #define ICON_Version 56 @@ -164,10 +164,10 @@ enum processID { #define ICON_MaxAccY 64 #define ICON_MaxAccZ 65 #define ICON_MaxAccE 66 -#define ICON_MaxSpeedCornerX 67 -#define ICON_MaxSpeedCornerY 68 -#define ICON_MaxSpeedCornerZ 69 -#define ICON_MaxSpeedCornerE 70 +#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 @@ -231,7 +231,7 @@ typedef struct { int16_t print_speed = 100; float Max_Feedspeed = 0; float Max_Acceleration = 0; - float Max_Corner = 0; + float Max_Jerk = 0; float Max_Step = 0; float Move_X_scale = 0; float Move_Y_scale = 0; @@ -261,7 +261,7 @@ typedef struct { char feedspeed_flag; #endif char acc_flag; - char corner_flag; + char jerk_flag; char step_flag; } HMI_Flag; @@ -314,7 +314,7 @@ void HMI_PrintSpeed(void); void HMI_MaxFeedspeedXYZE(void); void HMI_MaxAccelerationXYZE(void); -void HMI_MaxCornerXYZE(void); +void HMI_MaxJerkXYZE(void); void HMI_StepXYZE(void); void update_variable(void); @@ -332,28 +332,28 @@ void Icon_leveling(bool value); // Other bool Pause_HeatStatus(); -void HMI_StartFrame(const bool with_update); // startup screen -void HMI_MainMenu(void); // main process screen -void HMI_SelectFile(void); // file page -void HMI_Printing(void); // print page -void HMI_Prepare(void); // prepare page -void HMI_Control(void); // control page -void HMI_Leveling(void); // Level the page -void HMI_AxisMove(void); // Axis movement menu -void HMI_Temperature(void); // Temperature menu -void HMI_Motion(void); // Sports menu -void HMI_Info(void); // Information menu -void HMI_Tune(void); // Adjust the menu +void HMI_StartFrame(const bool with_update); // Startup screen +void HMI_MainMenu(void); // Main process screen +void HMI_SelectFile(void); // File page +void HMI_Printing(void); // Print page +void HMI_Prepare(void); // Prepare page +void HMI_Control(void); // Control page +void HMI_Leveling(void); // Level the page +void HMI_AxisMove(void); // Axis movement menu +void HMI_Temperature(void); // Temperature menu +void HMI_Motion(void); // Sports menu +void HMI_Info(void); // Information menu +void HMI_Tune(void); // Adjust the menu #if HAS_HOTEND void HMI_PLAPreheatSetting(void); // PLA warm-up setting void HMI_ABSPreheatSetting(void); // ABS warm-up setting #endif -void HMI_MaxSpeed(void); // Maximum speed submenu -void HMI_MaxAcceleration(void); // Maximum acceleration submenu -void HMI_MaxCorner(void); // Maximum corner speed submenu -void HMI_Step(void); // transmission ratio +void HMI_MaxSpeed(void); // Maximum speed submenu +void HMI_MaxAcceleration(void); // Maximum acceleration submenu +void HMI_MaxJerk(void); // Maximum jerk speed submenu +void HMI_Step(void); // Transmission ratio void HMI_Init(void); void DWIN_Update(void); From 217bae9ff156c0c65c19606a32e42425ea39c68d Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 16 Sep 2020 06:56:48 -0500 Subject: [PATCH 21/44] More DWIN cleanup --- Marlin/src/lcd/dwin/e3v2/dwin.cpp | 713 +++++++++++++----------------- Marlin/src/lcd/dwin/e3v2/dwin.h | 8 +- 2 files changed, 320 insertions(+), 401 deletions(-) diff --git a/Marlin/src/lcd/dwin/e3v2/dwin.cpp b/Marlin/src/lcd/dwin/e3v2/dwin.cpp index 1bef8f14088b..c94292980506 100644 --- a/Marlin/src/lcd/dwin/e3v2/dwin.cpp +++ b/Marlin/src/lcd/dwin/e3v2/dwin.cpp @@ -32,6 +32,10 @@ #define HAS_ONESTEP_LEVELING 1 #endif +#if HAS_HOTEND || HAS_HEATED_BED || HAS_FAN + #define HAS_COOLDOWN 1 +#endif + #include "dwin.h" #include @@ -116,7 +120,7 @@ // Feedspeed limit (max feedspeed = DEFAULT_MAX_FEEDRATE * 2) #define MIN_MAXFEEDSPEED 1 #define MIN_MAXACCELERATION 1 -#define MIN_MAXCORNER 0.1 +#define MIN_MAXJERK 0.1 #define MIN_STEP 1 #define FEEDRATE_E (60) @@ -134,7 +138,7 @@ constexpr uint16_t TROWS = 6, MROWS = TROWS - 1, // Total rows, and other LBLX = 60, // Menu item label X MENU_CHR_W = 8, STAT_CHR_W = 10; -#define MBASE(L) (49 + (L)*MLINE) +#define MBASE(L) (49 + MLINE * (L)) #define BABY_Z_VAR TERN(HAS_BED_PROBE, probe.offset.z, dwin_zoffset) @@ -415,7 +419,7 @@ inline void Clear_Main_Window(void) { inline void Clear_Popup_Area(void) { Clear_Title_Bar(); - DWIN_Draw_Rectangle(1, Background_black, 0, 31, DWIN_WIDTH, DWIN_HEIGHT); + DWIN_Draw_Rectangle(1, Background_black, 0, 31, DWIN_WIDTH, DWIN_HEIGHT); } void Draw_Popup_Bkgd_105(void) { @@ -423,16 +427,16 @@ void Draw_Popup_Bkgd_105(void) { } inline void Draw_More_Icon(const uint8_t line) { - DWIN_ICON_Show(ICON, ICON_More, 226, 46 + line * MLINE); + DWIN_ICON_Show(ICON, ICON_More, 226, MBASE(line) - 3); } inline void Draw_Menu_Cursor(const uint8_t line) { - // DWIN_ICON_Show(ICON,ICON_Rectangle, 0, 31 + line * MLINE); - DWIN_Draw_Rectangle(1, Rectangle_Color, 0, 31 + line * MLINE, 14, 31 + (line + 1) * MLINE - 2); + // 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); } inline void Erase_Menu_Cursor(const uint8_t line) { - DWIN_Draw_Rectangle(1, Background_black, 0, 31 + line * MLINE, 14, 31 + (line + 1) * MLINE - 2); + DWIN_Draw_Rectangle(1, Background_black, 0, MBASE(line) - 18, 14, MBASE(line + 1) - 20); } inline void Move_Highlight(const int16_t from, const uint16_t newline) { @@ -442,7 +446,7 @@ inline void Move_Highlight(const int16_t from, const uint16_t newline) { inline void Add_Menu_Line() { Move_Highlight(1, MROWS); - DWIN_Draw_Line(Line_Color, 16, 82 + MROWS * MLINE, 256, 83 + MROWS * MLINE); + DWIN_Draw_Line(Line_Color, 16, MBASE(MROWS + 1) - 20, 256, MBASE(MROWS + 1) - 19); } inline void Scroll_Menu(const uint8_t dir) { @@ -458,17 +462,17 @@ inline uint16_t nr_sd_menu_items() { } inline void Draw_Menu_Icon(const uint8_t line, const uint8_t icon) { - DWIN_ICON_Show(ICON, icon, 26, 46 + line * MLINE); + DWIN_ICON_Show(ICON, icon, 26, MBASE(line) - 3); } inline void Erase_Menu_Text(const uint8_t line) { - DWIN_Draw_Rectangle(1, Background_black, LBLX, 31 + line * MLINE + 4, 271, 28 + (line + 1) * MLINE - 4); + DWIN_Draw_Rectangle(1, Background_black, LBLX, MBASE(line) - 14, 271, MBASE(line) + 28); } inline void Draw_Menu_Line(const uint8_t line, const uint8_t icon=0, const char * const label=nullptr) { - if (label) DWIN_Draw_String(false, false, font8x16, White, Background_black, LBLX, 48 + line * MLINE, (char*)label); + if (label) DWIN_Draw_String(false, false, font8x16, White, Background_black, LBLX, MBASE(line) - 1, (char*)label); if (icon) Draw_Menu_Icon(line, icon); - DWIN_Draw_Line(Line_Color, 16, 29 + (line + 1) * MLINE, 256, 30 + (line + 1) * MLINE); + DWIN_Draw_Line(Line_Color, 16, MBASE(line) + 33, 256, MBASE(line) + 34); } // The "Back" label is always on the first line @@ -494,6 +498,8 @@ inline void draw_move_en(const uint16_t line) { DWIN_Frame_AreaCopy(1, 69, 61, 102, 71, LBLX, line); // "Move" } +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); } + inline void Prepare_Item_Move(const uint8_t row) { if (HMI_flag.language_chinese) DWIN_Frame_AreaCopy(1, 159, 70, 200, 84, LBLX, MBASE(row)); @@ -523,17 +529,17 @@ inline void Prepare_Item_Offset(const uint8_t row) { if (HMI_flag.language_chinese) { #if HAS_BED_PROBE DWIN_Frame_AreaCopy(1, 174, 164, 223, 177, LBLX, MBASE(row)); - DWIN_Draw_Signed_Float(font8x16, Background_black, 2, 2, 202, MBASE(row), probe.offset.z * 100); + DWIN_Draw_Signed_Float(font8x16, Background_black, 2, 2, 202, MBASE(row), BABY_Z_VAR * 100); #else DWIN_Frame_AreaCopy(1, 43, 89, 98, 101, LBLX, MBASE(row)); #endif } else { #if HAS_BED_PROBE - DWIN_Frame_AreaCopy(1, 93, 179, 141, 189, LBLX, MBASE(row)); // "Z-Offset" - DWIN_Draw_Signed_Float(font8x16, Background_black, 2, 2, 202, MBASE(row), probe.offset.z * 100); + DWIN_Frame_AreaCopy(1, 93, 179, 141, 189, LBLX, MBASE(row)); // "Z-Offset" + DWIN_Draw_Signed_Float(font8x16, Background_black, 2, 2, 202, MBASE(row), BABY_Z_VAR * 100); #else - DWIN_Frame_AreaCopy(1, 1, 76, 106, 86, LBLX, MBASE(row)); // "..." + DWIN_Frame_AreaCopy(1, 1, 76, 106, 86, LBLX, MBASE(row)); // "..." #endif } Draw_Menu_Line(row, ICON_SetHome); @@ -544,8 +550,8 @@ inline void Prepare_Item_PLA(const uint8_t row) { DWIN_Frame_AreaCopy(1, 100, 89, 151, 101, LBLX, MBASE(row)); } 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" + 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" } Draw_Menu_Line(row, ICON_PLAPreheat); } @@ -555,17 +561,17 @@ inline void Prepare_Item_ABS(const uint8_t row) { DWIN_Frame_AreaCopy(1, 180, 89, 233, 100, LBLX, MBASE(row)); } 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" + 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" } Draw_Menu_Line(row, ICON_ABSPreheat); } inline void Prepare_Item_Cool(const uint8_t row) { if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 1, 104, 56, 117, LBLX, MBASE(row)); + DWIN_Frame_AreaCopy(1, 1, 104, 56, 117, LBLX, MBASE(row)); else - DWIN_Frame_AreaCopy(1, 200, 76, 264, 86, LBLX, MBASE(row)); // "Cooldown" + DWIN_Frame_AreaCopy(1, 200, 76, 264, 86, LBLX, MBASE(row)); // "Cooldown" Draw_Menu_Line(row, ICON_Cool); } @@ -589,13 +595,13 @@ inline void Draw_Prepare_Menu() { #define PVISI(L) WITHIN(PSCROL(L), 0, MROWS) if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 133, 1, 160, 13, 14, 8); // "Prepare" + DWIN_Frame_TitleCopy(1, 133, 1, 160, 13); // "Prepare" } else { #ifdef USE_STRING_HEADINGS Draw_Title(GET_TEXT_F(MSG_PREPARE)); #else - DWIN_Frame_AreaCopy(1, 178, 2, 229, 14, 14, 8); // "Prepare" + DWIN_Frame_TitleCopy(1, 178, 2, 229, 14); // "Prepare" #endif } @@ -615,13 +621,13 @@ inline void Draw_Prepare_Menu() { inline void Draw_Control_Menu() { Clear_Main_Window(); - const int16_t scroll = TERN(HAS_ONESTEP_LEVELING, MROWS - index_control, 0); // Scrolled-up lines + const int16_t scroll = TERN(HAS_ONESTEP_LEVELING, MROWS - index_control, 0); // Scrolled-up lines #define CSCROL(L) (scroll + (L)) #define CLINE(L) MBASE(CSCROL(L)) #define CVISI(L) WITHIN(CSCROL(L), 0, MROWS) - if (CVISI(0)) Draw_Back_First(select_control.now == 0); // < Back + if (CVISI(0)) Draw_Back_First(select_control.now == 0); // < Back if (HMI_flag.language_chinese) { DWIN_Frame_AreaCopy(1, 103, 1, 130, 14, 14, 8); @@ -637,15 +643,15 @@ inline void Draw_Control_Menu() { else { #ifdef USE_STRING_HEADINGS Draw_Title(GET_TEXT_F(MSG_CONTROL)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 0), GET_TEXT_F(MSG_TEMPERATURE)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 1), GET_TEXT_F(MSG_MOTION)); + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(1), GET_TEXT_F(MSG_TEMPERATURE)); + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(2), GET_TEXT_F(MSG_MOTION)); #if ENABLED(EEPROM_SETTINGS) - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 2), GET_TEXT_F(MSG_STORE_EEPROM)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 3), GET_TEXT_F(MSG_LOAD_EEPROM)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 4), GET_TEXT_F(MSG_RESTORE_DEFAULTS)); - if (CVISI(6)) DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 5), F("Info")); + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(3), GET_TEXT_F(MSG_STORE_EEPROM)); + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(4), GET_TEXT_F(MSG_LOAD_EEPROM)); + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(5), GET_TEXT_F(MSG_RESTORE_DEFAULTS)); + if (CVISI(6)) DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(6), F("Info")); #else - if (CVISI(3)) DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 2), F("Info")); + if (CVISI(3)) DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(3), F("Info")); #endif #else DWIN_Frame_AreaCopy(1, 128, 2, 176, 12, 14, 8); @@ -690,11 +696,11 @@ inline void Draw_Tune_Menu() { else { #ifdef USE_STRING_HEADINGS Draw_Title(GET_TEXT_F(MSG_TUNE)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 0), GET_TEXT_F(MSG_SPEED)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 1), GET_TEXT_F(MSG_UBL_SET_TEMP_HOTEND)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 2), GET_TEXT_F(MSG_UBL_SET_TEMP_BED)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 3), GET_TEXT_F(MSG_FAN_SPEED)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 4), GET_TEXT_F(MSG_ZPROBE_ZOFFSET)); + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(1), GET_TEXT_F(MSG_SPEED)); + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(2), GET_TEXT_F(MSG_UBL_SET_TEMP_HOTEND)); + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(3), GET_TEXT_F(MSG_UBL_SET_TEMP_BED)); + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(4), GET_TEXT_F(MSG_FAN_SPEED)); + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(5), GET_TEXT_F(MSG_ZPROBE_ZOFFSET)); #else DWIN_Frame_AreaCopy(1, 94, 2, 126, 12, 14, 9); DWIN_Frame_AreaCopy(1, 1, 179, 92, 190, LBLX, MBASE(1)); // print speed @@ -769,10 +775,10 @@ inline void Draw_Motion_Menu() { else { #ifdef USE_STRING_HEADINGS Draw_Title(GET_TEXT_F(MSG_MOTION)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 0), F("Feedrate")); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 1), GET_TEXT_F(MSG_ACCELERATION)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 2), GET_TEXT_F(MSG_JERK)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 3), GET_TEXT_F(MSG_STEPS_PER_MM)); + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(1), F("Feedrate")); + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(2), GET_TEXT_F(MSG_ACCELERATION)); + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(3), GET_TEXT_F(MSG_JERK)); + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(4), GET_TEXT_F(MSG_STEPS_PER_MM)); #else DWIN_Frame_AreaCopy(1, 144, 16, 189, 26, 14, 8); draw_max_en(MBASE(1)); draw_speed_en(27, MBASE(1)); // "Max Speed" @@ -1035,7 +1041,7 @@ void HMI_Move_X(void) { } NOLESS(HMI_ValueStruct.Move_X_scale, (X_MIN_POS) * MINUNITMULT); NOMORE(HMI_ValueStruct.Move_X_scale, (X_MAX_POS) * MINUNITMULT); - current_position[X_AXIS] = HMI_ValueStruct.Move_X_scale / 10; + current_position.x = HMI_ValueStruct.Move_X_scale / 10; DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 216, MBASE(1), HMI_ValueStruct.Move_X_scale); DWIN_UpdateLCD(); } @@ -1064,7 +1070,7 @@ void HMI_Move_Y(void) { } NOLESS(HMI_ValueStruct.Move_Y_scale, (Y_MIN_POS) * MINUNITMULT); NOMORE(HMI_ValueStruct.Move_Y_scale, (Y_MAX_POS) * MINUNITMULT); - current_position[Y_AXIS] = HMI_ValueStruct.Move_Y_scale / 10; + current_position.y = HMI_ValueStruct.Move_Y_scale / 10; DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 216, MBASE(2), HMI_ValueStruct.Move_Y_scale); DWIN_UpdateLCD(); } @@ -1093,13 +1099,13 @@ void HMI_Move_Z(void) { } NOLESS(HMI_ValueStruct.Move_Z_scale, Z_MIN_POS * MINUNITMULT); NOMORE(HMI_ValueStruct.Move_Z_scale, Z_MAX_POS * MINUNITMULT); - current_position[Z_AXIS] = HMI_ValueStruct.Move_Z_scale / 10; + current_position.z = HMI_ValueStruct.Move_Z_scale / 10; DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 216, MBASE(3), HMI_ValueStruct.Move_Z_scale); DWIN_UpdateLCD(); } } -#if EXTRUDERS +#if HAS_HOTEND void HMI_Move_E(void) { ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); @@ -1335,7 +1341,7 @@ void HMI_PrintSpeed(void) { else if (encoder_diffState == ENCODER_DIFF_ENTER) { // return checkkey = Tune; EncoderRate.encoderRateEnabled = 0; - feedrate_percentage = HMI_ValueStruct.print_speed; + feedrate_percentage = HMI_ValueStruct.print_speed; DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(1 + MROWS - index_tune), HMI_ValueStruct.print_speed); return; } @@ -1359,22 +1365,14 @@ void HMI_MaxFeedspeedXYZE(void) { else if (encoder_diffState == ENCODER_DIFF_ENTER) { // return checkkey = MaxSpeed; EncoderRate.encoderRateEnabled = 0; - if (HMI_flag.feedspeed_flag == X_AXIS) planner.set_max_feedrate(X_AXIS, HMI_ValueStruct.Max_Feedspeed); - else if (HMI_flag.feedspeed_flag == Y_AXIS) planner.set_max_feedrate(Y_AXIS, HMI_ValueStruct.Max_Feedspeed); - else if (HMI_flag.feedspeed_flag == Z_AXIS) planner.set_max_feedrate(Z_AXIS, HMI_ValueStruct.Max_Feedspeed); - #if HAS_HOTEND - else if (HMI_flag.feedspeed_flag == E_AXIS) planner.set_max_feedrate(E_AXIS, HMI_ValueStruct.Max_Feedspeed); - #endif + if (WITHIN(HMI_flag.feedspeed_flag, X_AXIS, E_AXIS)) + planner.set_max_feedrate(HMI_flag.feedspeed_flag, HMI_ValueStruct.Max_Feedspeed); DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 4, 210, MBASE(select_speed.now), HMI_ValueStruct.Max_Feedspeed); return; } // MaxFeedspeed limit - if (HMI_flag.feedspeed_flag == X_AXIS) {if (HMI_ValueStruct.Max_Feedspeed > default_max_feedrate[X_AXIS] * 2) HMI_ValueStruct.Max_Feedspeed = default_max_feedrate[X_AXIS] * 2; } - else if (HMI_flag.feedspeed_flag == Y_AXIS) {if (HMI_ValueStruct.Max_Feedspeed > default_max_feedrate[Y_AXIS] * 2) HMI_ValueStruct.Max_Feedspeed = default_max_feedrate[Y_AXIS] * 2; } - else if (HMI_flag.feedspeed_flag == Z_AXIS) {if (HMI_ValueStruct.Max_Feedspeed > default_max_feedrate[Z_AXIS] * 2) HMI_ValueStruct.Max_Feedspeed = default_max_feedrate[Z_AXIS] * 2; } - #if HAS_HOTEND - else if (HMI_flag.feedspeed_flag == E_AXIS) {if (HMI_ValueStruct.Max_Feedspeed > default_max_feedrate[E_AXIS] * 2) HMI_ValueStruct.Max_Feedspeed = default_max_feedrate[E_AXIS] * 2; } - #endif + if (WITHIN(HMI_flag.feedspeed_flag, X_AXIS, E_AXIS)) + NOMORE(HMI_ValueStruct.Max_Feedspeed, default_max_feedrate[HMI_flag.feedspeed_flag] * 2); if (HMI_ValueStruct.Max_Feedspeed < MIN_MAXFEEDSPEED) HMI_ValueStruct.Max_Feedspeed = MIN_MAXFEEDSPEED; // MaxFeedspeed value DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 4, 210, MBASE(select_speed.now), HMI_ValueStruct.Max_Feedspeed); @@ -1399,12 +1397,8 @@ void HMI_MaxAccelerationXYZE(void) { return; } // MaxAcceleration limit - if (HMI_flag.acc_flag == X_AXIS) {if (HMI_ValueStruct.Max_Acceleration > default_max_acceleration[X_AXIS] * 2) HMI_ValueStruct.Max_Acceleration = default_max_acceleration[X_AXIS] * 2; } - else if (HMI_flag.acc_flag == Y_AXIS) {if (HMI_ValueStruct.Max_Acceleration > default_max_acceleration[Y_AXIS] * 2) HMI_ValueStruct.Max_Acceleration = default_max_acceleration[Y_AXIS] * 2; } - else if (HMI_flag.acc_flag == Z_AXIS) {if (HMI_ValueStruct.Max_Acceleration > default_max_acceleration[Z_AXIS] * 2) HMI_ValueStruct.Max_Acceleration = default_max_acceleration[Z_AXIS] * 2; } - #if HAS_HOTEND - else if (HMI_flag.acc_flag == E_AXIS) {if (HMI_ValueStruct.Max_Acceleration > default_max_acceleration[E_AXIS] * 2) HMI_ValueStruct.Max_Acceleration = default_max_acceleration[E_AXIS] * 2; } - #endif + if (WITHIN(HMI_flag.acc_flag, X_AXIS, E_AXIS)) + NOMORE(HMI_ValueStruct.Max_Acceleration, default_max_acceleration[HMI_flag.acc_flag] * 2); if (HMI_ValueStruct.Max_Acceleration < MIN_MAXACCELERATION) HMI_ValueStruct.Max_Acceleration = MIN_MAXACCELERATION; // MaxAcceleration value DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 4, 210, MBASE(select_acc.now), HMI_ValueStruct.Max_Acceleration); @@ -1439,7 +1433,7 @@ void HMI_MaxJerkXYZE(void) { NOMORE(HMI_ValueStruct.Max_Jerk, default_max_jerk[Z_AXIS] * 2 * MINUNITMULT); else if (HMI_flag.jerk_flag == E_AXIS) NOMORE(HMI_ValueStruct.Max_Jerk, default_max_jerk[E_AXIS] * 2 * MINUNITMULT); - NOLESS(HMI_ValueStruct.Max_Jerk, (MIN_MAXCORNER) * MINUNITMULT); + NOLESS(HMI_ValueStruct.Max_Jerk, (MIN_MAXJERK) * MINUNITMULT); // MaxJerk value DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 210, MBASE(select_jerk.now), HMI_ValueStruct.Max_Jerk); } @@ -1457,22 +1451,14 @@ void HMI_StepXYZE(void) { else if (encoder_diffState == ENCODER_DIFF_ENTER) { // return checkkey = Step; EncoderRate.encoderRateEnabled = 0; - if (HMI_flag.step_flag == X_AXIS) planner.settings.axis_steps_per_mm[X_AXIS] = HMI_ValueStruct.Max_Step / 10; - else if (HMI_flag.step_flag == Y_AXIS) planner.settings.axis_steps_per_mm[Y_AXIS] = HMI_ValueStruct.Max_Step / 10; - else if (HMI_flag.step_flag == Z_AXIS) planner.settings.axis_steps_per_mm[Z_AXIS] = HMI_ValueStruct.Max_Step / 10; - else if (HMI_flag.step_flag == E_AXIS) planner.settings.axis_steps_per_mm[E_AXIS] = HMI_ValueStruct.Max_Step / 10; + if (WITHIN(HMI_flag.step_flag, X_AXIS, E_AXIS)) + planner.settings.axis_steps_per_mm[HMI_flag.step_flag] = HMI_ValueStruct.Max_Step / 10; DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 210, MBASE(select_step.now), HMI_ValueStruct.Max_Step); return; } // Step limit - if (HMI_flag.step_flag == X_AXIS) - NOMORE(HMI_ValueStruct.Max_Step, default_axis_steps_per_unit[X_AXIS] * 2 * MINUNITMULT); - else if (HMI_flag.step_flag == Y_AXIS) - NOMORE(HMI_ValueStruct.Max_Step, default_axis_steps_per_unit[Y_AXIS] * 2 * MINUNITMULT); - else if (HMI_flag.step_flag == Z_AXIS) - NOMORE(HMI_ValueStruct.Max_Step, default_axis_steps_per_unit[Z_AXIS] * 2 * MINUNITMULT); - else if (HMI_flag.step_flag == E_AXIS) - NOMORE(HMI_ValueStruct.Max_Step, default_axis_steps_per_unit[E_AXIS] * 2 * MINUNITMULT); + if (WITHIN(HMI_flag.step_flag, X_AXIS, E_AXIS)) + NOMORE(HMI_ValueStruct.Max_Step, default_axis_steps_per_unit[HMI_flag.step_flag] * 2 * MINUNITMULT); NOLESS(HMI_ValueStruct.Max_Step, MIN_STEP); // Step value DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 210, MBASE(select_step.now), HMI_ValueStruct.Max_Step); @@ -1743,7 +1729,7 @@ inline void Draw_Info_Menu() { DWIN_Draw_String(false, false, font8x16, White, Background_black, (DWIN_WIDTH - strlen(SHORT_BUILD_VERSION) * MENU_CHR_W) / 2, 195, (char*)SHORT_BUILD_VERSION); if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 30, 17, 57, 29, 14, 8); + DWIN_Frame_TitleCopy(1, 30, 17, 57, 29); // "Info" DWIN_Frame_AreaCopy(1, 197, 149, 252, 161, 108, 102); DWIN_Frame_AreaCopy(1, 1, 164, 56, 176, 108, 175); @@ -1754,7 +1740,7 @@ inline void Draw_Info_Menu() { #ifdef USE_STRING_HEADINGS Draw_Title(GET_TEXT_F(MSG_INFO_SCREEN)); #else - DWIN_Frame_AreaCopy(1, 190, 16, 215, 26, 14, 8); + DWIN_Frame_TitleCopy(1, 190, 16, 215, 26); // "Info" #endif DWIN_Frame_AreaCopy(1, 120, 150, 146, 161, 124, 102); @@ -1774,13 +1760,13 @@ inline void Draw_Print_File_Menu() { Clear_Title_Bar(); if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 0, 31, 55, 44, 14, 8); + DWIN_Frame_TitleCopy(1, 0, 31, 55, 44); // "Print file" } else { #ifdef USE_STRING_HEADINGS Draw_Title("Print file"); // TODO: GET_TEXT_F #else - DWIN_Frame_AreaCopy(1, 52, 31, 137, 41, 14, 8); // "Print file" + DWIN_Frame_TitleCopy(1, 52, 31, 137, 41); // "Print file" #endif } @@ -1814,30 +1800,26 @@ void HMI_MainMenu(void) { } else if (encoder_diffState == ENCODER_DIFF_ENTER) { switch (select_page.now) { - /* Print File */ - case 0: + case 0: // Print File checkkey = SelectFile; Draw_Print_File_Menu(); break; - /* Prepare */ - case 1: + case 1: // Prepare checkkey = Prepare; select_prepare.reset(); index_prepare = MROWS; Draw_Prepare_Menu(); break; - /* Control */ - case 2: + case 2: // Control checkkey = Control; select_control.reset(); index_control = MROWS; Draw_Control_Menu(); break; - /* Leveling */ - case 3: + case 3: // Leveling or Info #if HAS_ONESTEP_LEVELING checkkey = Leveling; HMI_Leveling(); @@ -1851,7 +1833,7 @@ void HMI_MainMenu(void) { DWIN_UpdateLCD(); } -/* Select (and Print) File */ +// Select (and Print) File void HMI_SelectFile(void) { ENCODER_DiffState encoder_diffState = get_encoder_state(); @@ -2017,14 +1999,14 @@ void HMI_Printing(void) { } else if (encoder_diffState == ENCODER_DIFF_ENTER) { switch (select_print.now) { - case 0: // setting + case 0: // Setting checkkey = Tune; HMI_ValueStruct.show_mode = 0; select_tune.reset(); index_tune = 5; Draw_Tune_Menu(); break; - case 1: // pause + case 1: // Pause /* pause */ if (HMI_flag.pause_flag) { ICON_Pause(); @@ -2047,7 +2029,7 @@ void HMI_Printing(void) { } break; - case 2: // stop + case 2: // Stop /* stop */ HMI_flag.select_flag = 1; checkkey = Print_window; @@ -2060,7 +2042,7 @@ void HMI_Printing(void) { DWIN_UpdateLCD(); } -/* pause and stop window */ +/* Pause and Stop window */ void HMI_PauseOrStop(void) { ENCODER_DiffState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; @@ -2120,7 +2102,7 @@ inline void Draw_Move_Menu() { Clear_Main_Window(); if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 192, 1, 233, 14, 14, 8); + 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)); @@ -2132,7 +2114,7 @@ inline void Draw_Move_Menu() { #ifdef USE_STRING_HEADINGS Draw_Title(GET_TEXT_F(MSG_MOVE_AXIS)); #else - DWIN_Frame_AreaCopy(1, 231, 2, 265, 12, 14, 8); + DWIN_Frame_TitleCopy(1, 231, 2, 265, 12); // "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" @@ -2145,7 +2127,8 @@ inline void Draw_Move_Menu() { Draw_Back_First(select_axis.now == 0); if (select_axis.now) Draw_Menu_Cursor(select_axis.now); - LOOP_L_N(i, MROWS) Draw_Menu_Line(i + 1, ICON_MoveX + i); + // Draw separators so it looks like a menu + LOOP_L_N(i, 3 + ENABLED(HAS_HOTEND)) Draw_Menu_Line(i + 1, ICON_MoveX + i); } #include "../../../libs/buzzer.h" @@ -2211,7 +2194,7 @@ void HMI_Prepare(void) { } else if (encoder_diffState == ENCODER_DIFF_ENTER) { switch (select_prepare.now) { - case 0: // back + case 0: // Back select_page.set(1); Goto_MainMenu(); break; @@ -2222,10 +2205,12 @@ void HMI_Prepare(void) { queue.inject_P(PSTR("G92 E0")); current_position.e = HMI_ValueStruct.Move_E_scale = 0; - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 216, MBASE(1), current_position[X_AXIS] * MINUNITMULT); - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 216, MBASE(2), current_position[Y_AXIS] * MINUNITMULT); - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 216, MBASE(3), current_position[Z_AXIS] * MINUNITMULT); - DWIN_Draw_Signed_Float(font8x16, Background_black, 3, 1, 216, MBASE(4), current_position.e * MINUNITMULT); + DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 216, MBASE(1), current_position.x * MINUNITMULT); + DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 216, MBASE(2), current_position.y * MINUNITMULT); + DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 216, MBASE(3), current_position.z * MINUNITMULT); + #if HAS_HOTEND + DWIN_Draw_Signed_Float(font8x16, Background_black, 3, 1, 216, MBASE(4), current_position.e * MINUNITMULT); + #endif break; case 2: // close motion queue.inject_P(PSTR("M84")); @@ -2297,11 +2282,11 @@ void Draw_Temperature_Menu() { else { #ifdef USE_STRING_HEADINGS Draw_Title(GET_TEXT_F(MSG_TEMPERATURE)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 0), GET_TEXT_F(MSG_UBL_SET_TEMP_HOTEND)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 1), GET_TEXT_F(MSG_UBL_SET_TEMP_BED)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 2), GET_TEXT_F(MSG_FAN_SPEED)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 3), F("PLA Preheat Settings")); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 4), F("ABS Preheat Settings")); + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(1), GET_TEXT_F(MSG_UBL_SET_TEMP_HOTEND)); + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(2), GET_TEXT_F(MSG_UBL_SET_TEMP_BED)); + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(3), GET_TEXT_F(MSG_FAN_SPEED)); + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(4), F("PLA Preheat Settings")); + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(5), F("ABS Preheat Settings")); #else DWIN_Frame_AreaCopy(1, 56, 16, 141, 28, 14, 8); DWIN_Frame_AreaCopy(1, 197, 104, 238, 114, LBLX, MBASE(1)); // Nozzle... @@ -2378,7 +2363,7 @@ void HMI_Control(void) { } else if (encoder_diffState == ENCODER_DIFF_ENTER) { switch (select_control.now) { - case 0: // back + case 0: // Back select_page.set(2); Goto_MainMenu(); break; @@ -2461,7 +2446,7 @@ void HMI_AxisMove(void) { } else if (encoder_diffState == ENCODER_DIFF_ENTER) { switch (select_axis.now) { - case 0: // back + case 0: // Back checkkey = Prepare; select_prepare.set(1); index_prepare = MROWS; @@ -2469,19 +2454,19 @@ void HMI_AxisMove(void) { break; case 1: // X axis move checkkey = Move_X; - HMI_ValueStruct.Move_X_scale = current_position[X_AXIS] * MINUNITMULT; + HMI_ValueStruct.Move_X_scale = current_position.x * MINUNITMULT; DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 216, MBASE(1), HMI_ValueStruct.Move_X_scale); EncoderRate.encoderRateEnabled = 1; break; case 2: // Y axis move checkkey = Move_Y; - HMI_ValueStruct.Move_Y_scale = current_position[Y_AXIS] * MINUNITMULT; + HMI_ValueStruct.Move_Y_scale = current_position.y * MINUNITMULT; DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 216, MBASE(2), HMI_ValueStruct.Move_Y_scale); EncoderRate.encoderRateEnabled = 1; break; case 3: // Z axis move checkkey = Move_Z; - HMI_ValueStruct.Move_Z_scale = current_position[Z_AXIS] * MINUNITMULT; + HMI_ValueStruct.Move_Z_scale = current_position.z * MINUNITMULT; DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 216, MBASE(3), HMI_ValueStruct.Move_Z_scale); EncoderRate.encoderRateEnabled = 1; break; @@ -2521,7 +2506,7 @@ void HMI_Temperature(void) { } else if (encoder_diffState == ENCODER_DIFF_ENTER) { switch (select_temp.now) { - case 0: // back + case 0: // Back checkkey = Control; select_control.set(1); index_control = MROWS; @@ -2573,10 +2558,10 @@ void HMI_Temperature(void) { else { #ifdef USE_STRING_HEADINGS Draw_Title("PLA Settings"); // TODO: GET_TEXT_F - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 0), F("Nozzle Temp")); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 1), F("Bed Temp")); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 2), GET_TEXT_F(MSG_FAN_SPEED)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 3), GET_TEXT_F(MSG_STORE_EEPROM)); + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(1), F("Nozzle Temp")); + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(2), F("Bed Temp")); + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(3), GET_TEXT_F(MSG_FAN_SPEED)); + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(4), GET_TEXT_F(MSG_STORE_EEPROM)); #else DWIN_Frame_AreaCopy(1, 56, 16, 141, 28, 14, 8); DWIN_Frame_AreaCopy(1, 157, 76, 181, 86, LBLX, MBASE(1)); @@ -2628,10 +2613,10 @@ void HMI_Temperature(void) { else { #ifdef USE_STRING_HEADINGS Draw_Title("ABS Settings"); // TODO: GET_TEXT_F - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 0), F("Nozzle Temp")); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 1), F("Bed Temp")); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 2), GET_TEXT_F(MSG_FAN_SPEED)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 3), GET_TEXT_F(MSG_STORE_EEPROM)); + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(1), F("Nozzle Temp")); + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(2), F("Bed Temp")); + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(3), GET_TEXT_F(MSG_FAN_SPEED)); + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(4), GET_TEXT_F(MSG_STORE_EEPROM)); #else DWIN_Frame_AreaCopy(1, 56, 16, 141, 28, 14, 8); DWIN_Frame_AreaCopy(1, 172, 76, 198, 86, LBLX, MBASE(1)); @@ -2671,62 +2656,69 @@ inline void Draw_Max_Speed_Menu() { Clear_Main_Window(); if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 1, 16, 28, 28, 14, 8); + DWIN_Frame_TitleCopy(1, 1, 16, 28, 28); // "Max Speed (mm/s)" auto say_max_speed = [](const uint16_t row) { - DWIN_Frame_AreaCopy(1, 173, 133, 228, 147, LBLX, row); // "Max speed" + DWIN_Frame_AreaCopy(1, 173, 133, 228, 147, LBLX, row); // "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(MBASE(4)); // "Max speed" - DWIN_Frame_AreaCopy(1, 18, 150, 25, 160, LBLX + 58, MBASE(4) + 3); // E + 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 + #if HAS_HOTEND + say_max_speed(MBASE(4)); // "Max speed" + DWIN_Frame_AreaCopy(1, 18, 150, 25, 160, LBLX + 58, MBASE(4) + 3); // E + #endif } else { #ifdef USE_STRING_HEADINGS Draw_Title("Max Speed (mm/s)"); // TODO: GET_TEXT_F - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 0), F("Max Feedrate X")); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 1), F("Max Feedrate Y")); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 2), F("Max Feedrate Z")); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 3), F("Max Feedrate E")); + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(1), F("Max Feedrate X")); + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(2), F("Max Feedrate Y")); + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(3), F("Max Feedrate Z")); + #if HAS_HOTEND + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(4), F("Max Feedrate E")); + #endif #else - DWIN_Frame_AreaCopy(1, 144, 16, 189, 26, 14, 8); + DWIN_Frame_TitleCopy(1, 144, 16, 189, 26); // "Max Speed (mm/s)" - draw_max_en(MBASE(1)); // "Max" + 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(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" + draw_max_en(MBASE(3)); // "Max" + draw_speed_en(27, MBASE(3)); // "Speed" + say_z(70, MBASE(3)); // "Z" - draw_max_en(MBASE(4)); // "Max" - draw_speed_en(27, MBASE(4)); // "Speed" - say_e(70, MBASE(4)); // "E" + #if HAS_HOTEND + draw_max_en(MBASE(4)); // "Max" + draw_speed_en(27, MBASE(4)); // "Speed" + say_e(70, MBASE(4)); // "E" + #endif #endif } Draw_Back_First(); - LOOP_L_N(i, 4) Draw_Menu_Line(i + 1, ICON_MaxSpeedX + i); - + LOOP_L_N(i, 3 + ENABLED(HAS_HOTEND)) Draw_Menu_Line(i + 1, ICON_MaxSpeedX + i); DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 4, 210, MBASE(1), planner.settings.max_feedrate_mm_s[X_AXIS]); DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 4, 210, MBASE(2), planner.settings.max_feedrate_mm_s[Y_AXIS]); DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 4, 210, MBASE(3), planner.settings.max_feedrate_mm_s[Z_AXIS]); - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 4, 210, MBASE(4), planner.settings.max_feedrate_mm_s[E_AXIS]); + #if HAS_HOTEND + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 4, 210, MBASE(4), planner.settings.max_feedrate_mm_s[E_AXIS]); + #endif } inline void Draw_Max_Accel_Menu() { Clear_Main_Window(); if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 1, 16, 28, 28, 14, 8); + DWIN_Frame_TitleCopy(1, 1, 16, 28, 28); // "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); @@ -2737,103 +2729,117 @@ inline void Draw_Max_Accel_Menu() { 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 - 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 + #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 + #endif } else { #ifdef USE_STRING_HEADINGS Draw_Title(GET_TEXT_F(MSG_ACCELERATION)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 0), F("Max Accel X")); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 1), F("Max Accel Y")); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 2), F("Max Accel Z")); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 3), F("Max Accel E")); + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(1), F("Max Accel X")); + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(2), F("Max Accel Y")); + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(3), F("Max Accel Z")); + #if HAS_HOTEND + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(4), F("Max Accel E")); + #endif #else - DWIN_Frame_AreaCopy(1, 144, 16, 189, 26, 14, 8); - 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" - draw_max_accel_en(MBASE(4)); say_e(108, MBASE(4)); // "Max Acceleration E" + DWIN_Frame_TitleCopy(1, 144, 16, 189, 26); // "Acceleration" + 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" + #if HAS_HOTEND + draw_max_accel_en(MBASE(4)); say_e(108, MBASE(4)); // "Max Acceleration E" + #endif #endif } Draw_Back_First(); - LOOP_L_N(i, 4) Draw_Menu_Line(i + 1, ICON_MaxAccX + i); - + LOOP_L_N(i, 3 + ENABLED(HAS_HOTEND)) Draw_Menu_Line(i + 1, ICON_MaxAccX + i); DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 4, 210, MBASE(1), planner.settings.max_acceleration_mm_per_s2[X_AXIS]); DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 4, 210, MBASE(2), planner.settings.max_acceleration_mm_per_s2[Y_AXIS]); DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 4, 210, MBASE(3), planner.settings.max_acceleration_mm_per_s2[Z_AXIS]); - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 4, 210, MBASE(4), planner.settings.max_acceleration_mm_per_s2[E_AXIS]); + #if HAS_HOTEND + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 4, 210, MBASE(4), planner.settings.max_acceleration_mm_per_s2[E_AXIS]); + #endif } inline void Draw_Max_Jerk_Menu() { Clear_Main_Window(); if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 1, 16, 28, 28, 14, 8); + DWIN_Frame_TitleCopy(1, 1, 16, 28, 28); // "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, 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, 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, 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 - 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 + DWIN_Frame_AreaCopy(1, 9, 150, 16, 160, LBLX + 83, MBASE(3) + 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 + #endif } else { #ifdef USE_STRING_HEADINGS Draw_Title(GET_TEXT_F(MSG_JERK)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 0), F("Max Jerk X")); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 1), F("Max Jerk Y")); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 2), F("Max Jerk Z")); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 3), F("Max Jerk E")); + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(1), F("Max Jerk X")); + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(2), F("Max Jerk Y")); + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(3), F("Max Jerk Z")); + #if HAS_HOTEND + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(4), F("Max Jerk E")); + #endif #else - DWIN_Frame_AreaCopy(1, 144, 16, 189, 26, 14, 8); - 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" - - 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" + DWIN_Frame_TitleCopy(1, 144, 16, 189, 26); // "Jerk" + 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" + + #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" + #endif #endif } Draw_Back_First(); - LOOP_L_N(i, 4) Draw_Menu_Line(i + 1, ICON_MaxSpeedJerkX + i); - + LOOP_L_N(i, 3 + ENABLED(HAS_HOTEND)) Draw_Menu_Line(i + 1, ICON_MaxSpeedJerkX + i); DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 210, MBASE(1), planner.max_jerk[X_AXIS] * MINUNITMULT); DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 210, MBASE(2), planner.max_jerk[Y_AXIS] * MINUNITMULT); DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 210, MBASE(3), planner.max_jerk[Z_AXIS] * MINUNITMULT); - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 210, MBASE(4), planner.max_jerk[E_AXIS] * MINUNITMULT); + #if HAS_HOTEND + DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 210, MBASE(4), planner.max_jerk[E_AXIS] * MINUNITMULT); + #endif } inline void Draw_Steps_Menu() { Clear_Main_Window(); if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 1, 16, 28, 28, 14, 8); + DWIN_Frame_TitleCopy(1, 1, 16, 28, 28); // "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 @@ -2841,32 +2847,39 @@ inline void Draw_Steps_Menu() { 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 - 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 + #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 + #endif } else { #ifdef USE_STRING_HEADINGS Draw_Title(GET_TEXT_F(MSG_STEPS_PER_MM)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 0), F("Steps/mm X")); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 1), F("Steps/mm Y")); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 2), F("Steps/mm Z")); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 3), F("Steps/mm E")); + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(1), F("Steps/mm X")); + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(2), F("Steps/mm Y")); + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(3), F("Steps/mm Z")); + #if HAS_HOTEND + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(4), F("Steps/mm E")); + #endif #else - DWIN_Frame_AreaCopy(1, 144, 16, 189, 26, 14, 8); + DWIN_Frame_TitleCopy(1, 144, 16, 189, 26); // "Steps per mm" 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" - draw_steps_per_mm(MBASE(4)); say_e(103, MBASE(4)); // "E" + #if HAS_HOTEND + draw_steps_per_mm(MBASE(4)); say_e(103, MBASE(4)); // "E" + #endif #endif } Draw_Back_First(); - LOOP_L_N(i, 4) Draw_Menu_Line(i + 1, ICON_StepX + i); - + LOOP_L_N(i, 3 + ENABLED(HAS_HOTEND)) Draw_Menu_Line(i + 1, ICON_StepX + i); DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 210, MBASE(1), planner.settings.axis_steps_per_mm[X_AXIS] * MINUNITMULT); DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 210, MBASE(2), planner.settings.axis_steps_per_mm[Y_AXIS] * MINUNITMULT); DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 210, MBASE(3), planner.settings.axis_steps_per_mm[Z_AXIS] * MINUNITMULT); - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 210, MBASE(4), planner.settings.axis_steps_per_mm[E_AXIS] * MINUNITMULT); + #if HAS_HOTEND + DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 210, MBASE(4), planner.settings.axis_steps_per_mm[E_AXIS] * MINUNITMULT); + #endif } /* Motion */ @@ -2883,7 +2896,7 @@ void HMI_Motion(void) { } else if (encoder_diffState == ENCODER_DIFF_ENTER) { switch (select_motion.now) { - case 0: // back + case 0: // Back checkkey = Control; select_control.set(2); index_control = MROWS; @@ -3043,7 +3056,7 @@ void HMI_PLAPreheatSetting(void) { } else if (encoder_diffState == ENCODER_DIFF_ENTER) { switch (select_PLA.now) { - case 0: // back + case 0: // Back checkkey = TemperatureID; select_temp.now = 4; HMI_ValueStruct.show_mode = -1; @@ -3074,7 +3087,7 @@ void HMI_PLAPreheatSetting(void) { break; #endif #if ENABLED(EEPROM_SETTINGS) - case 4: { // save PLA configuration + case 4: { // Save PLA configuration const bool success = settings.save(); HMI_AudioFeedback(success); } break; @@ -3099,7 +3112,7 @@ void HMI_ABSPreheatSetting(void) { } else if (encoder_diffState == ENCODER_DIFF_ENTER) { switch (select_ABS.now) { - case 0: // back + case 0: // Back checkkey = TemperatureID; select_temp.now = 5; HMI_ValueStruct.show_mode = -1; @@ -3154,41 +3167,17 @@ void HMI_MaxSpeed(void) { if (select_speed.dec()) Move_Highlight(-1, select_speed.now); } else if (encoder_diffState == ENCODER_DIFF_ENTER) { - switch (select_speed.now) { - case 0: // back - checkkey = Motion; - select_motion.now = 1; - Draw_Motion_Menu(); - break; - case 1: // max Speed X - checkkey = MaxSpeed_value; - HMI_flag.feedspeed_flag = X_AXIS; - HMI_ValueStruct.Max_Feedspeed = planner.settings.max_feedrate_mm_s[X_AXIS]; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 4, 210, MBASE(select_speed.now), HMI_ValueStruct.Max_Feedspeed); - EncoderRate.encoderRateEnabled = 1; - break; - case 2: // max Speed Y - checkkey = MaxSpeed_value; - HMI_flag.feedspeed_flag = Y_AXIS; - HMI_ValueStruct.Max_Feedspeed = planner.settings.max_feedrate_mm_s[Y_AXIS]; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 4, 210, MBASE(select_speed.now), HMI_ValueStruct.Max_Feedspeed); - EncoderRate.encoderRateEnabled = 1; - break; - case 3: // max Speed Z - checkkey = MaxSpeed_value; - HMI_flag.feedspeed_flag = Z_AXIS; - HMI_ValueStruct.Max_Feedspeed = planner.settings.max_feedrate_mm_s[Z_AXIS]; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 4, 210, MBASE(select_speed.now), HMI_ValueStruct.Max_Feedspeed); - EncoderRate.encoderRateEnabled = 1; - break; - case 4: // max Speed E - checkkey = MaxSpeed_value; - HMI_flag.feedspeed_flag = E_AXIS; - HMI_ValueStruct.Max_Feedspeed = planner.settings.max_feedrate_mm_s[E_AXIS]; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 4, 210, MBASE(select_speed.now), HMI_ValueStruct.Max_Feedspeed); - EncoderRate.encoderRateEnabled = 1; - break; - default: break; + if (WITHIN(select_speed.now, 1, 4)) { + checkkey = MaxSpeed_value; + HMI_flag.feedspeed_flag = AxisEnum(select_speed.now - 1); + HMI_ValueStruct.Max_Feedspeed = planner.settings.max_feedrate_mm_s[HMI_flag.feedspeed_flag]; + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 4, 210, MBASE(select_speed.now), HMI_ValueStruct.Max_Feedspeed); + EncoderRate.encoderRateEnabled = 1; + } + else { // Back + checkkey = Motion; + select_motion.now = 1; + Draw_Motion_Menu(); } } DWIN_UpdateLCD(); @@ -3207,41 +3196,17 @@ void HMI_MaxAcceleration(void) { if (select_acc.dec()) Move_Highlight(-1, select_acc.now); } else if (encoder_diffState == ENCODER_DIFF_ENTER) { - switch (select_acc.now) { - case 0: // back - checkkey = Motion; - select_motion.now = 2; - Draw_Motion_Menu(); - break; - case 1: // max acceleration X - checkkey = MaxAcceleration_value; - HMI_flag.acc_flag = X_AXIS; - HMI_ValueStruct.Max_Acceleration = planner.settings.max_acceleration_mm_per_s2[X_AXIS]; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 4, 210, MBASE(select_acc.now), HMI_ValueStruct.Max_Acceleration); - EncoderRate.encoderRateEnabled = 1; - break; - case 2: // max acceleration Y - checkkey = MaxAcceleration_value; - HMI_flag.acc_flag = Y_AXIS; - HMI_ValueStruct.Max_Acceleration = planner.settings.max_acceleration_mm_per_s2[Y_AXIS]; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 4, 210, MBASE(select_acc.now), HMI_ValueStruct.Max_Acceleration); - EncoderRate.encoderRateEnabled = 1; - break; - case 3: // max acceleration Z - checkkey = MaxAcceleration_value; - HMI_flag.acc_flag = Z_AXIS; - HMI_ValueStruct.Max_Acceleration = planner.settings.max_acceleration_mm_per_s2[Z_AXIS]; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 4, 210, MBASE(select_acc.now), HMI_ValueStruct.Max_Acceleration); - EncoderRate.encoderRateEnabled = 1; - break; - case 4: // max acceleration E - checkkey = MaxAcceleration_value; - HMI_flag.acc_flag = E_AXIS; - HMI_ValueStruct.Max_Acceleration = planner.settings.max_acceleration_mm_per_s2[E_AXIS]; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 4, 210, MBASE(select_acc.now), HMI_ValueStruct.Max_Acceleration); - EncoderRate.encoderRateEnabled = 1; - break; - default: break; + if (WITHIN(select_acc.now, 1, 4)) { + checkkey = MaxAcceleration_value; + HMI_flag.acc_flag = AxisEnum(select_acc.now - 1); + HMI_ValueStruct.Max_Acceleration = planner.settings.max_acceleration_mm_per_s2[HMI_flag.acc_flag]; + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 4, 210, MBASE(select_acc.now), HMI_ValueStruct.Max_Acceleration); + EncoderRate.encoderRateEnabled = 1; + } + else { // Back + checkkey = Motion; + select_motion.now = 2; + Draw_Motion_Menu(); } } DWIN_UpdateLCD(); @@ -3260,41 +3225,17 @@ void HMI_MaxJerk(void) { if (select_jerk.dec()) Move_Highlight(-1, select_jerk.now); } else if (encoder_diffState == ENCODER_DIFF_ENTER) { - switch (select_jerk.now) { - case 0: // back - checkkey = Motion; - select_motion.now = 3; - Draw_Motion_Menu(); - break; - case 1: // max jerk X - checkkey = MaxJerk_value; - HMI_flag.jerk_flag = X_AXIS; - HMI_ValueStruct.Max_Jerk = planner.max_jerk[X_AXIS] * MINUNITMULT; - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 210, MBASE(select_jerk.now), HMI_ValueStruct.Max_Jerk); - EncoderRate.encoderRateEnabled = 1; - break; - case 2: // max jerk Y - checkkey = MaxJerk_value; - HMI_flag.jerk_flag = Y_AXIS; - HMI_ValueStruct.Max_Jerk = planner.max_jerk[Y_AXIS] * MINUNITMULT; - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 210, MBASE(select_jerk.now), HMI_ValueStruct.Max_Jerk); - EncoderRate.encoderRateEnabled = 1; - break; - case 3: // max jerk Z - checkkey = MaxJerk_value; - HMI_flag.jerk_flag = Z_AXIS; - HMI_ValueStruct.Max_Jerk = planner.max_jerk[Z_AXIS] * MINUNITMULT; - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 210, MBASE(select_jerk.now), HMI_ValueStruct.Max_Jerk); - EncoderRate.encoderRateEnabled = 1; - break; - case 4: // max jerk E - checkkey = MaxJerk_value; - HMI_flag.jerk_flag = E_AXIS; - HMI_ValueStruct.Max_Jerk = planner.max_jerk[E_AXIS] * MINUNITMULT; - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 210, MBASE(select_jerk.now), HMI_ValueStruct.Max_Jerk); - EncoderRate.encoderRateEnabled = 1; - break; - default: break; + if (WITHIN(select_jerk.now, 1, 4)) { + checkkey = MaxJerk_value; + HMI_flag.jerk_flag = AxisEnum(select_jerk.now - 1); + HMI_ValueStruct.Max_Jerk = planner.max_jerk[HMI_flag.jerk_flag] * MINUNITMULT; + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 4, 210, MBASE(select_jerk.now), HMI_ValueStruct.Max_Jerk); + EncoderRate.encoderRateEnabled = 1; + } + else { // Back + checkkey = Motion; + select_motion.now = 3; + Draw_Motion_Menu(); } } DWIN_UpdateLCD(); @@ -3313,41 +3254,17 @@ void HMI_Step(void) { if (select_step.dec()) Move_Highlight(-1, select_step.now); } else if (encoder_diffState == ENCODER_DIFF_ENTER) { - switch (select_step.now) { - case 0: // back - checkkey = Motion; - select_motion.now = 4; - Draw_Motion_Menu(); - break; - case 1: // max step X - checkkey = Step_value; - HMI_flag.step_flag = X_AXIS; - HMI_ValueStruct.Max_Step = planner.settings.axis_steps_per_mm[X_AXIS] * MINUNITMULT; - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 210, MBASE(select_step.now), HMI_ValueStruct.Max_Step); - EncoderRate.encoderRateEnabled = 1; - break; - case 2: // max step Y - checkkey = Step_value; - HMI_flag.step_flag = Y_AXIS; - HMI_ValueStruct.Max_Step = planner.settings.axis_steps_per_mm[Y_AXIS] * MINUNITMULT; - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 210, MBASE(select_step.now), HMI_ValueStruct.Max_Step); - EncoderRate.encoderRateEnabled = 1; - break; - case 3: // max step Z - checkkey = Step_value; - HMI_flag.step_flag = Z_AXIS; - HMI_ValueStruct.Max_Step = planner.settings.axis_steps_per_mm[Z_AXIS] * MINUNITMULT; - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 210, MBASE(select_step.now), HMI_ValueStruct.Max_Step); - EncoderRate.encoderRateEnabled = 1; - break; - case 4: // max step E - checkkey = Step_value; - HMI_flag.step_flag = E_AXIS; - HMI_ValueStruct.Max_Step = planner.settings.axis_steps_per_mm[E_AXIS] * MINUNITMULT; - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 210, MBASE(select_step.now), HMI_ValueStruct.Max_Step); - EncoderRate.encoderRateEnabled = 1; - break; - default: break; + if (WITHIN(select_step.now, 1, 4)) { + checkkey = Step_value; + HMI_flag.step_flag = AxisEnum(select_step.now - 1); + HMI_ValueStruct.Max_Step = planner.settings.axis_steps_per_mm[HMI_flag.step_flag] * MINUNITMULT; + DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 210, MBASE(select_step.now), HMI_ValueStruct.Max_Step); + EncoderRate.encoderRateEnabled = 1; + } + else { // Back + checkkey = Motion; + select_motion.now = 4; + Draw_Motion_Menu(); } } DWIN_UpdateLCD(); @@ -3429,16 +3346,18 @@ void EachMomentUpdate(void) { } duration_t elapsed = print_job_timer.duration(); // print timer - /* already print time */ + + // Print time so far const uint16_t min = (elapsed.value % 3600) / 60; if (last_Printtime != min) { // 1 minute update last_Printtime = min; Draw_Print_ProgressElapsed(); } - /* remain print time */ + + // Estimate remaining time every 20 seconds static millis_t next_remain_time_update = 0; - if (elapsed.minute() > 5 && ELAPSED(ms, next_remain_time_update) && HMI_flag.heat_flag == 0) { // show after 5 min and 20s update - remain_time = ((elapsed.value - dwin_heat_time) * ((float)card.getFileSize() / (float)card.getIndex())) - (elapsed.value - dwin_heat_time); + if (Percentrecord > 1 && ELAPSED(ms, next_remain_time_update) && HMI_flag.heat_flag == 0) { + remain_time = (elapsed.value - dwin_heat_time) / (Percentrecord * 0.01f) - (elapsed.value - dwin_heat_time); next_remain_time_update += 20 * 1000UL; Draw_Print_ProgressRemain(); } @@ -3528,43 +3447,43 @@ void EachMomentUpdate(void) { void DWIN_HandleScreen(void) { switch (checkkey) { - case MainMenu: HMI_MainMenu(); break; - case SelectFile: HMI_SelectFile(); break; - case Prepare: HMI_Prepare(); break; - case Control: HMI_Control(); break; - case Leveling: break; - case PrintProcess: HMI_Printing(); break; - case Print_window: HMI_PauseOrStop(); break; - case AxisMove: HMI_AxisMove(); break; - case TemperatureID: HMI_Temperature(); break; - case Motion: HMI_Motion(); break; - case Info: HMI_Info(); break; - case Tune: HMI_Tune(); break; - case PLAPreheat: HMI_PLAPreheatSetting(); break; - case ABSPreheat: HMI_ABSPreheatSetting(); break; - case MaxSpeed: HMI_MaxSpeed(); break; - case MaxAcceleration: HMI_MaxAcceleration(); break; - case MaxJerk: HMI_MaxJerk(); break; - case Step: HMI_Step(); break; - case Move_X: HMI_Move_X(); break; - case Move_Y: HMI_Move_Y(); break; - case Move_Z: HMI_Move_Z(); break; + case MainMenu: HMI_MainMenu(); break; + case SelectFile: HMI_SelectFile(); break; + case Prepare: HMI_Prepare(); break; + case Control: HMI_Control(); break; + case Leveling: break; + case PrintProcess: HMI_Printing(); break; + case Print_window: HMI_PauseOrStop(); break; + case AxisMove: HMI_AxisMove(); break; + case TemperatureID: HMI_Temperature(); break; + case Motion: HMI_Motion(); break; + case Info: HMI_Info(); break; + case Tune: HMI_Tune(); break; + case PLAPreheat: HMI_PLAPreheatSetting(); break; + case ABSPreheat: HMI_ABSPreheatSetting(); break; + case MaxSpeed: HMI_MaxSpeed(); break; + case MaxAcceleration: HMI_MaxAcceleration(); break; + case MaxJerk: HMI_MaxJerk(); break; + case Step: HMI_Step(); break; + case Move_X: HMI_Move_X(); break; + case Move_Y: HMI_Move_Y(); break; + case Move_Z: HMI_Move_Z(); break; #if HAS_HOTEND - case Extruder: HMI_Move_E(); break; - case ETemp: HMI_ETemp(); break; + case Extruder: HMI_Move_E(); break; + case ETemp: HMI_ETemp(); break; #endif - case Homeoffset: HMI_Zoffset(); break; + case Homeoffset: HMI_Zoffset(); break; #if HAS_HEATED_BED - case BedTemp: HMI_BedTemp(); break; + case BedTemp: HMI_BedTemp(); break; #endif #if HAS_FAN - case FanSpeed: HMI_FanSpeed(); break; + case FanSpeed: HMI_FanSpeed(); break; #endif - case PrintSpeed: HMI_PrintSpeed(); break; - case MaxSpeed_value: HMI_MaxFeedspeedXYZE(); break; + case PrintSpeed: HMI_PrintSpeed(); break; + case MaxSpeed_value: HMI_MaxFeedspeedXYZE(); break; case MaxAcceleration_value: HMI_MaxAccelerationXYZE(); break; - case MaxJerk_value: HMI_MaxJerkXYZE(); break; - case Step_value: HMI_StepXYZE(); break; + case MaxJerk_value: HMI_MaxJerkXYZE(); break; + case Step_value: HMI_StepXYZE(); break; default: break; } } diff --git a/Marlin/src/lcd/dwin/e3v2/dwin.h b/Marlin/src/lcd/dwin/e3v2/dwin.h index 467cc433e7b0..abdf343a9ded 100644 --- a/Marlin/src/lcd/dwin/e3v2/dwin.h +++ b/Marlin/src/lcd/dwin/e3v2/dwin.h @@ -258,11 +258,11 @@ typedef struct { bool leveling_offset_flag:1; #endif #if HAS_FAN - char feedspeed_flag; + AxisEnum feedspeed_flag; #endif - char acc_flag; - char jerk_flag; - char step_flag; + AxisEnum acc_flag; + AxisEnum jerk_flag; + AxisEnum step_flag; } HMI_Flag; extern HMI_value_t HMI_ValueStruct; From 56ed55ddba555b6550ee4da0a1accfc5418e0f3e Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 16 Sep 2020 05:52:01 -0500 Subject: [PATCH 22/44] MarlinUI percent methods for all --- Marlin/src/lcd/ultralcd.h | 62 +++++++++++++++++++-------------------- 1 file changed, 31 insertions(+), 31 deletions(-) diff --git a/Marlin/src/lcd/ultralcd.h b/Marlin/src/lcd/ultralcd.h index 0200d39014c1..ee7f50dabf72 100644 --- a/Marlin/src/lcd/ultralcd.h +++ b/Marlin/src/lcd/ultralcd.h @@ -328,6 +328,37 @@ class MarlinUI { static inline void init_lcd() {} #endif + #if HAS_PRINT_PROGRESS + #if HAS_PRINT_PROGRESS_PERMYRIAD + typedef uint16_t progress_t; + #define PROGRESS_SCALE 100U + #define PROGRESS_MASK 0x7FFF + #else + typedef uint8_t progress_t; + #define PROGRESS_SCALE 1U + #define PROGRESS_MASK 0x7F + #endif + #if ENABLED(LCD_SET_PROGRESS_MANUALLY) + static progress_t progress_override; + static void set_progress(const progress_t p) { progress_override = _MIN(p, 100U * (PROGRESS_SCALE)); } + static void set_progress_done() { progress_override = (PROGRESS_MASK + 1U) + 100U * (PROGRESS_SCALE); } + static void progress_reset() { if (progress_override & (PROGRESS_MASK + 1U)) set_progress(0); } + #if BOTH(LCD_SET_PROGRESS_MANUALLY, USE_M73_REMAINING_TIME) + static uint32_t remaining_time; + FORCE_INLINE static void set_remaining_time(const uint32_t r) { remaining_time = r; } + FORCE_INLINE static uint32_t get_remaining_time() { return remaining_time; } + FORCE_INLINE static void reset_remaining_time() { set_remaining_time(0); } + #endif + #endif + static progress_t _get_progress(); + #if HAS_PRINT_PROGRESS_PERMYRIAD + FORCE_INLINE static uint16_t get_progress_permyriad() { return _get_progress(); } + #endif + static uint8_t get_progress_percent() { return uint8_t(_get_progress() / (PROGRESS_SCALE)); } + #else + static constexpr uint8_t get_progress_percent() { return 0; } + #endif + #if HAS_DISPLAY static void init(); @@ -350,37 +381,6 @@ class MarlinUI { static void pause_print(); static void resume_print(); - #if HAS_PRINT_PROGRESS - #if HAS_PRINT_PROGRESS_PERMYRIAD - typedef uint16_t progress_t; - #define PROGRESS_SCALE 100U - #define PROGRESS_MASK 0x7FFF - #else - typedef uint8_t progress_t; - #define PROGRESS_SCALE 1U - #define PROGRESS_MASK 0x7F - #endif - #if ENABLED(LCD_SET_PROGRESS_MANUALLY) - static progress_t progress_override; - static void set_progress(const progress_t p) { progress_override = _MIN(p, 100U * (PROGRESS_SCALE)); } - static void set_progress_done() { progress_override = (PROGRESS_MASK + 1U) + 100U * (PROGRESS_SCALE); } - static void progress_reset() { if (progress_override & (PROGRESS_MASK + 1U)) set_progress(0); } - #if BOTH(LCD_SET_PROGRESS_MANUALLY, USE_M73_REMAINING_TIME) - static uint32_t remaining_time; - FORCE_INLINE static void set_remaining_time(const uint32_t r) { remaining_time = r; } - FORCE_INLINE static uint32_t get_remaining_time() { return remaining_time; } - FORCE_INLINE static void reset_remaining_time() { set_remaining_time(0); } - #endif - #endif - static progress_t _get_progress(); - #if HAS_PRINT_PROGRESS_PERMYRIAD - FORCE_INLINE static uint16_t get_progress_permyriad() { return _get_progress(); } - #endif - static uint8_t get_progress_percent() { return uint8_t(_get_progress() / (PROGRESS_SCALE)); } - #else - static constexpr uint8_t get_progress_percent() { return 0; } - #endif - #if HAS_SPI_LCD static millis_t next_button_update_ms; From 9cf8537051dfb1bba75f5a7dcba34946bf70068f Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 17 Sep 2020 00:13:06 +0000 Subject: [PATCH 23/44] [cron] Bump distribution date (2020-09-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 63f117b932d1..0ae661f1b18e 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-09-16" + #define STRING_DISTRIBUTION_DATE "2020-09-17" #endif /** From 9d5a9621de30e5a2c62727a479a6e73007ced7de Mon Sep 17 00:00:00 2001 From: Jason Smith Date: Thu, 17 Sep 2020 01:06:01 -0700 Subject: [PATCH 24/44] Demo and test multiple PID defaults (#19413) --- Marlin/Configuration.h | 29 ++++++++++---------------- buildroot/tests/BIGTREE_GTR_V1_0-tests | 5 ++++- 2 files changed, 15 insertions(+), 19 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 52af1375a509..2635bc750eb0 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -486,24 +486,17 @@ //#define PID_AUTOTUNE_MENU // Add PID auto-tuning to the "Advanced Settings" menu. (~250 bytes of PROGMEM) //#define PID_PARAMS_PER_HOTEND // Uses separate PID parameters for each extruder (useful for mismatched extruders) // Set/get with gcode: M301 E[extruder number, 0-2] - - // If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it - - // Ultimaker - #define DEFAULT_Kp 22.2 - #define DEFAULT_Ki 1.08 - #define DEFAULT_Kd 114 - - // MakerGear - //#define DEFAULT_Kp 7.0 - //#define DEFAULT_Ki 0.1 - //#define DEFAULT_Kd 12 - - // Mendel Parts V9 on 12V - //#define DEFAULT_Kp 63.0 - //#define DEFAULT_Ki 2.25 - //#define DEFAULT_Kd 440 - + #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. + #define DEFAULT_Kp_LIST { 22.20, 20.0 } + #define DEFAULT_Ki_LIST { 1.08, 1.0 } + #define DEFAULT_Kd_LIST { 114.00, 112.0 } + #else + #define DEFAULT_Kp 22.20 + #define DEFAULT_Ki 1.08 + #define DEFAULT_Kd 114.00 + #endif #endif // PIDTEMP //=========================================================================== diff --git a/buildroot/tests/BIGTREE_GTR_V1_0-tests b/buildroot/tests/BIGTREE_GTR_V1_0-tests index 58f6f71fda9e..e8d47562aa61 100644 --- a/buildroot/tests/BIGTREE_GTR_V1_0-tests +++ b/buildroot/tests/BIGTREE_GTR_V1_0-tests @@ -36,7 +36,10 @@ opt_set TEMP_SENSOR_3 1 opt_set TEMP_SENSOR_4 1 opt_set TEMP_SENSOR_5 1 opt_set NUM_Z_STEPPER_DRIVERS 3 -opt_enable TOOLCHANGE_FILAMENT_SWAP TOOLCHANGE_MIGRATION_FEATURE TOOLCHANGE_FS_INIT_BEFORE_SWAP TOOLCHANGE_FS_PRIME_FIRST_USED +opt_set DEFAULT_Kp_LIST "{ 22.2, 20.0, 21.0, 19.0, 18.0, 17.0 }" +opt_set DEFAULT_Ki_LIST "{ 1.08 }" +opt_set 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" # clean up From c5204807e9f55da13364901aec94927f7a25d5a2 Mon Sep 17 00:00:00 2001 From: tovam Date: Thu, 17 Sep 2020 10:07:03 +0200 Subject: [PATCH 25/44] Fix missing spaces in info menu (#19404) --- Marlin/src/lcd/menu/menu_info.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/lcd/menu/menu_info.cpp b/Marlin/src/lcd/menu/menu_info.cpp index 864e855df23d..a4cbc31d8b6b 100644 --- a/Marlin/src/lcd/menu/menu_info.cpp +++ b/Marlin/src/lcd/menu/menu_info.cpp @@ -179,7 +179,7 @@ void menu_info_thermistors() { #undef THERMISTOR_ID #define THERMISTOR_ID TEMP_SENSOR_BED #include "../thermistornames.h" - STATIC_ITEM_P(PSTR("BED:" THERMISTOR_NAME), SS_INVERT); + STATIC_ITEM_P(PSTR("BED: " THERMISTOR_NAME), SS_INVERT); PSTRING_ITEM(MSG_INFO_MIN_TEMP, STRINGIFY(BED_MINTEMP), SS_LEFT); PSTRING_ITEM(MSG_INFO_MAX_TEMP, STRINGIFY(BED_MAXTEMP), SS_LEFT); STATIC_ITEM(TERN(WATCH_BED, MSG_INFO_RUNAWAY_ON, MSG_INFO_RUNAWAY_OFF), SS_LEFT); @@ -189,7 +189,7 @@ void menu_info_thermistors() { #undef THERMISTOR_ID #define THERMISTOR_ID TEMP_SENSOR_CHAMBER #include "../thermistornames.h" - STATIC_ITEM_P(PSTR("CHAM:" THERMISTOR_NAME), SS_INVERT); + STATIC_ITEM_P(PSTR("CHAM: " THERMISTOR_NAME), SS_INVERT); PSTRING_ITEM(MSG_INFO_MIN_TEMP, STRINGIFY(CHAMBER_MINTEMP), SS_LEFT); PSTRING_ITEM(MSG_INFO_MAX_TEMP, STRINGIFY(CHAMBER_MAXTEMP), SS_LEFT); STATIC_ITEM(TERN(WATCH_CHAMBER, MSG_INFO_RUNAWAY_ON, MSG_INFO_RUNAWAY_OFF), SS_LEFT); From 5926bacea132744abacd31c83a4d6005f9caa495 Mon Sep 17 00:00:00 2001 From: enigmaquip Date: Thu, 17 Sep 2020 02:17:47 -0600 Subject: [PATCH 26/44] Add more DWIN commands, docs (#19395) --- Marlin/src/lcd/dwin/dwin_lcd.cpp | 92 ++++++++++++++++++++++++++++++++ Marlin/src/lcd/dwin/dwin_lcd.h | 21 ++++++++ 2 files changed, 113 insertions(+) diff --git a/Marlin/src/lcd/dwin/dwin_lcd.cpp b/Marlin/src/lcd/dwin/dwin_lcd.cpp index 3b30629a8dae..7d1528bed19b 100644 --- a/Marlin/src/lcd/dwin/dwin_lcd.cpp +++ b/Marlin/src/lcd/dwin/dwin_lcd.cpp @@ -153,6 +153,20 @@ void DWIN_Frame_Clear(const uint16_t 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(uint8_t width, uint8_t height, uint16_t x, uint16_t y) { + size_t i = 0; + DWIN_Byte(i, 0x02); + 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 @@ -221,6 +235,10 @@ 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) { 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); @@ -244,6 +262,11 @@ void DWIN_Draw_IntValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t 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); @@ -360,4 +383,73 @@ 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, 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 diff --git a/Marlin/src/lcd/dwin/dwin_lcd.h b/Marlin/src/lcd/dwin/dwin_lcd.h index 0893974e4c3f..11409666d893 100644 --- a/Marlin/src/lcd/dwin/dwin_lcd.h +++ b/Marlin/src/lcd/dwin/dwin_lcd.h @@ -67,6 +67,12 @@ void DWIN_UpdateLCD(void); // color: Clear screen color void DWIN_Frame_Clear(const uint16_t color); +// Draw a point +// 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); + // Draw a line // color: Line segment color // xStart/yStart: Start point @@ -190,3 +196,18 @@ inline void DWIN_JPG_CacheTo1(uint8_t id) { DWIN_JPG_CacheToN(1, id); } // 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); From 073b7f1e3a77f6d00d58bb144fe3aa96ce3770f3 Mon Sep 17 00:00:00 2001 From: cosmoderp <36945803+cosmoderp@users.noreply.github.com> Date: Thu, 17 Sep 2020 06:35:04 -0400 Subject: [PATCH 27/44] E3 V2 DWIN: Z-Offset, cleanup, versatility (#19384) Co-authored-by: Scott Lahteine --- Marlin/Configuration_adv.h | 2 +- Marlin/src/inc/Conditionals_adv.h | 2 +- Marlin/src/lcd/dwin/e3v2/dwin.cpp | 2252 +++++++++-------- Marlin/src/lcd/dwin/e3v2/dwin.h | 136 +- Marlin/src/lcd/dwin/e3v2/rotary_encoder.cpp | 2 +- Marlin/src/lcd/dwin/e3v2/rotary_encoder.h | 2 +- Marlin/src/module/temperature.cpp | 26 +- .../PlatformIO/scripts/common-dependencies.h | 4 - platformio.ini | 2 - 9 files changed, 1349 insertions(+), 1079 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 2712312747de..d46ba55a922e 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1572,6 +1572,7 @@ #if ENABLED(BABYSTEPPING) //#define INTEGRATED_BABYSTEPPING // EXPERIMENTAL integration of babystepping into the Stepper ISR //#define BABYSTEP_WITHOUT_HOMING + //#define BABYSTEP_ALWAYS_AVAILABLE // Allow babystepping at all times (not just during movement). //#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA! #define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way //#define BABYSTEP_MILLIMETER_UNITS // Specify BABYSTEP_MULTIPLICATOR_(XY|Z) in mm instead of micro-steps @@ -1582,7 +1583,6 @@ #if ENABLED(DOUBLECLICK_FOR_Z_BABYSTEPPING) #define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds. // Note: Extra time may be added to mitigate controller latency. - //#define BABYSTEP_ALWAYS_AVAILABLE // Allow babystepping at all times (not just during movement). //#define MOVE_Z_WHEN_IDLE // Jump to the move Z menu on doubleclick when printer is idle. #if ENABLED(MOVE_Z_WHEN_IDLE) #define MOVE_Z_IDLE_MULTIPLICATOR 1 // Multiply 1mm by this factor for the move step size. diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h index 9742967a09d9..ff13d2897df2 100644 --- a/Marlin/src/inc/Conditionals_adv.h +++ b/Marlin/src/inc/Conditionals_adv.h @@ -59,7 +59,7 @@ #if TEMP_SENSOR_BED == 0 #undef THERMAL_PROTECTION_BED #undef THERMAL_PROTECTION_BED_PERIOD -#endif +#endif #if TEMP_SENSOR_CHAMBER == 0 #undef THERMAL_PROTECTION_CHAMBER diff --git a/Marlin/src/lcd/dwin/e3v2/dwin.cpp b/Marlin/src/lcd/dwin/e3v2/dwin.cpp index c94292980506..d45511f5bc84 100644 --- a/Marlin/src/lcd/dwin/e3v2/dwin.cpp +++ b/Marlin/src/lcd/dwin/e3v2/dwin.cpp @@ -28,15 +28,19 @@ #if ENABLED(DWIN_CREALITY_LCD) +#include "dwin.h" + #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_HOTEND || HAS_HEATED_BED || HAS_FAN - #define HAS_COOLDOWN 1 +#if ANY(BABYSTEPPING, HAS_BED_PROBE, HAS_WORKSPACE_OFFSET) + #define HAS_ZOFFSET_ITEM 1 #endif -#include "dwin.h" +#if !HAS_BED_PROBE && ENABLED(BABYSTEPPING) + #define JUST_BABYSTEP 1 +#endif #include #include @@ -52,8 +56,6 @@ #include "../../../core/macros.h" #include "../../../gcode/queue.h" -#include "../../../feature/babystep.h" - #include "../../../module/temperature.h" #include "../../../module/printcounter.h" #include "../../../module/motion.h" @@ -75,6 +77,10 @@ #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 @@ -89,7 +95,7 @@ #define CORP_WEBSITE_E "www.creality.com" #endif -#define PAUSE_HEAT true +#define PAUSE_HEAT #define USE_STRING_HEADINGS @@ -98,6 +104,7 @@ #define HEADER_FONT font10x20 #define MENU_CHAR_LIMIT 24 +#define STATUS_Y 360 // Fan speed limit #define FANON 255 @@ -146,11 +153,9 @@ constexpr uint16_t TROWS = 6, MROWS = TROWS - 1, // Total rows, and other HMI_value_t HMI_ValueStruct; HMI_Flag HMI_flag{0}; -millis_t Encoder_ms = 0; -millis_t Wait_ms = 0; millis_t dwin_heat_time = 0; -int checkkey = 0, last_checkkey = 0; +uint8_t checkkey = 0; typedef struct { uint8_t now, last; @@ -158,7 +163,7 @@ typedef struct { 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) now++; else now = v; 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}, select_prepare{0} @@ -175,13 +180,9 @@ uint8_t index_file = MROWS, index_prepare = MROWS, index_control = MROWS, index_leveling = MROWS, - index_tune = 5; - -// char filebuf[50]; - -uint8_t countbuf = 0; + index_tune = MROWS; -bool recovery_flag = false, abort_flag = false; +bool dwin_abort_flag = false; constexpr float default_max_feedrate[] = DEFAULT_MAX_FEEDRATE; constexpr float default_max_acceleration[] = DEFAULT_MAX_ACCELERATION; @@ -189,38 +190,41 @@ constexpr float default_max_jerk[] = { DEFAULT_XJERK, DEFAULT_YJERK, constexpr float default_axis_steps_per_unit[] = DEFAULT_AXIS_STEPS_PER_UNIT; uint8_t Percentrecord = 0; -uint16_t last_Printtime = 0, remain_time = 0; -float last_temp_hotend_target = 0, last_temp_bed_target = 0; -float last_temp_hotend_current = 0, last_temp_bed_current = 0; -uint8_t last_fan_speed = 0; -uint16_t last_speed = 0; -float last_E_scale = 0; -bool DWIN_lcd_sd_status = 0; -bool pause_action_flag = 0; -int temphot = 0, tempbed = 0; -float dwin_zoffset = 0; -float last_zoffset = 0; +uint16_t remain_time = 0; + +#if ENABLED(PAUSE_HEAT) + #if HAS_HOTEND + uint16_t temphot = 0; + #endif + #if HAS_HEATED_BED + uint16_t tempbed = 0; + #endif +#endif + +#if HAS_ZOFFSET_ITEM + float dwin_zoffset = 0, last_zoffset = 0; +#endif #define DWIN_LANGUAGE_EEPROM_ADDRESS 0x01 // Between 0x01 and 0x63 (EEPROM_OFFSET-1) // BL24CXX::check() uses 0x00 -void HMI_SetLanguage(void) { - BL24CXX::read(DWIN_LANGUAGE_EEPROM_ADDRESS, (uint8_t*)&HMI_flag.language_chinese, sizeof(HMI_flag.language_chinese)); - if (HMI_flag.language_chinese) - DWIN_JPG_CacheTo1(Language_Chinese); - else - DWIN_JPG_CacheTo1(Language_English); +void HMI_SetLanguageCache() { + DWIN_JPG_CacheTo1(HMI_flag.language_chinese ? Language_Chinese : Language_English); } -void HMI_SetAndSaveLanguageWestern(void) { - HMI_flag.language_chinese = false; - DWIN_JPG_CacheTo1(Language_English); - BL24CXX::write(DWIN_LANGUAGE_EEPROM_ADDRESS, (uint8_t*)&HMI_flag.language_chinese, sizeof(HMI_flag.language_chinese)); +void HMI_SetLanguage() { + #if ENABLED(EEPROM_SETTINGS) + BL24CXX::read(DWIN_LANGUAGE_EEPROM_ADDRESS, (uint8_t*)&HMI_flag.language_chinese, sizeof(HMI_flag.language_chinese)); + #endif + HMI_SetLanguageCache(); } -void HMI_SetAndSaveLanguageChinese(void) { - HMI_flag.language_chinese = true; - DWIN_JPG_CacheTo1(Language_Chinese); - BL24CXX::write(DWIN_LANGUAGE_EEPROM_ADDRESS, (uint8_t*)&HMI_flag.language_chinese, sizeof(HMI_flag.language_chinese)); + +void HMI_ToggleLanguage() { + HMI_flag.language_chinese ^= true; + HMI_SetLanguageCache(); + #if ENABLED(EEPROM_SETTINGS) + BL24CXX::write(DWIN_LANGUAGE_EEPROM_ADDRESS, (uint8_t*)&HMI_flag.language_chinese, sizeof(HMI_flag.language_chinese)); + #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) { @@ -331,14 +335,14 @@ void ICON_Tune() { if (HMI_flag.language_chinese) DWIN_Frame_AreaCopy(1, 121, 447, 148, 458, 34, 325); else - DWIN_Frame_AreaCopy(1, 1, 465, 34, 477, 31, 325); + DWIN_Frame_AreaCopy(1, 0, 466, 34, 476, 31, 325); } else { DWIN_ICON_Show(ICON, ICON_Setup_0, 8, 252); if (HMI_flag.language_chinese) DWIN_Frame_AreaCopy(1, 121, 405, 148, 420, 34, 325); else - DWIN_Frame_AreaCopy(1, 1, 438, 32, 448, 31, 325); + DWIN_Frame_AreaCopy(1, 0, 438, 32, 448, 31, 325); } } @@ -367,7 +371,7 @@ void ICON_Continue() { if (HMI_flag.language_chinese) DWIN_Frame_AreaCopy(1, 1, 447, 28, 460, 124, 325); else - DWIN_Frame_AreaCopy(1, 1, 451, 32, 463, 121, 325); + DWIN_Frame_AreaCopy(1, 1, 452, 32, 464, 121, 325); } else { DWIN_ICON_Show(ICON, ICON_Continue_0, 96, 252); @@ -385,7 +389,7 @@ void ICON_Stop() { if (HMI_flag.language_chinese) DWIN_Frame_AreaCopy(1, 151, 447, 178, 459, 210, 325); else - DWIN_Frame_AreaCopy(1, 218, 451, 249, 465, 209, 325); + DWIN_Frame_AreaCopy(1, 218, 452, 249, 466, 209, 325); } else { DWIN_ICON_Show(ICON, ICON_Stop_0, 184, 252); @@ -396,8 +400,8 @@ void ICON_Stop() { } } -inline void Clear_Title_Bar(void) { - DWIN_Draw_Rectangle(1, Background_blue, 0, 0, DWIN_WIDTH, 30); +inline void Clear_Title_Bar() { + DWIN_Draw_Rectangle(1, Background_blue, 0, 0, DWIN_WIDTH, 30); } inline void Draw_Title(const char * const title) { @@ -408,21 +412,21 @@ inline void Draw_Title(const __FlashStringHelper * title) { DWIN_Draw_String(false, false, HEADER_FONT, White, Background_blue, 14, 4, (char*)title); } -inline void Clear_Menu_Area(void) { - DWIN_Draw_Rectangle(1, Background_black, 0, 31, DWIN_WIDTH, 360); +inline void Clear_Menu_Area() { + DWIN_Draw_Rectangle(1, Background_black, 0, 31, DWIN_WIDTH, STATUS_Y); } -inline void Clear_Main_Window(void) { +inline void Clear_Main_Window() { Clear_Title_Bar(); Clear_Menu_Area(); } -inline void Clear_Popup_Area(void) { +inline void Clear_Popup_Area() { Clear_Title_Bar(); DWIN_Draw_Rectangle(1, Background_black, 0, 31, DWIN_WIDTH, DWIN_HEIGHT); } -void Draw_Popup_Bkgd_105(void) { +void Draw_Popup_Bkgd_105() { DWIN_Draw_Rectangle(1, Background_window, 14, 105, 258, 374); } @@ -476,7 +480,7 @@ inline void Draw_Menu_Line(const uint8_t line, const uint8_t icon=0, const char } // The "Back" label is always on the first line -inline void Draw_Back_Label(void) { +inline void Draw_Back_Label() { if (HMI_flag.language_chinese) DWIN_Frame_AreaCopy(1, 129, 72, 156, 84, LBLX, MBASE(0)); else @@ -494,13 +498,61 @@ inline void Draw_Back_First(const bool is_sel=true) { // Draw Menus // +#define MOTION_CASE_RATE 1 +#define MOTION_CASE_ACCEL 2 +#define MOTION_CASE_JERK (MOTION_CASE_ACCEL + ENABLED(HAS_CLASSIC_JERK)) +#define MOTION_CASE_STEPS (MOTION_CASE_JERK + 1) +#define MOTION_CASE_TOTAL MOTION_CASE_STEPS + +#define PREPARE_CASE_MOVE 1 +#define PREPARE_CASE_DISA 2 +#define PREPARE_CASE_HOME 3 +#define PREPARE_CASE_ZOFF (PREPARE_CASE_HOME + ENABLED(HAS_ZOFFSET_ITEM)) +#define PREPARE_CASE_PLA (PREPARE_CASE_ZOFF + ENABLED(HAS_HOTEND)) +#define PREPARE_CASE_ABS (PREPARE_CASE_PLA + ENABLED(HAS_HOTEND)) +#define PREPARE_CASE_COOL (PREPARE_CASE_ABS + EITHER(HAS_HOTEND, HAS_HEATED_BED)) +#define PREPARE_CASE_LANG (PREPARE_CASE_COOL + 1) +#define PREPARE_CASE_TOTAL PREPARE_CASE_LANG + +#define CONTROL_CASE_TEMP 1 +#define CONTROL_CASE_MOVE (CONTROL_CASE_TEMP + 1) +#define CONTROL_CASE_SAVE (CONTROL_CASE_MOVE + ENABLED(EEPROM_SETTINGS)) +#define CONTROL_CASE_LOAD (CONTROL_CASE_SAVE + ENABLED(EEPROM_SETTINGS)) +#define CONTROL_CASE_RESET (CONTROL_CASE_LOAD + ENABLED(EEPROM_SETTINGS)) +#define CONTROL_CASE_INFO (CONTROL_CASE_RESET + 1) +#define CONTROL_CASE_TOTAL CONTROL_CASE_INFO + +#define TUNE_CASE_SPEED 1 +#define TUNE_CASE_TEMP (TUNE_CASE_SPEED + ENABLED(HAS_HOTEND)) +#define TUNE_CASE_BED (TUNE_CASE_TEMP + ENABLED(HAS_HEATED_BED)) +#define TUNE_CASE_FAN (TUNE_CASE_BED + ENABLED(HAS_FAN)) +#define TUNE_CASE_ZOFF (TUNE_CASE_FAN + ENABLED(HAS_ZOFFSET_ITEM)) +#define TUNE_CASE_TOTAL TUNE_CASE_ZOFF + +#define TEMP_CASE_TEMP (0 + ENABLED(HAS_HOTEND)) +#define TEMP_CASE_BED (TEMP_CASE_TEMP + ENABLED(HAS_HEATED_BED)) +#define TEMP_CASE_FAN (TEMP_CASE_BED + ENABLED(HAS_FAN)) +#define TEMP_CASE_PLA (TEMP_CASE_FAN + ENABLED(HAS_HOTEND)) +#define TEMP_CASE_ABS (TEMP_CASE_PLA + ENABLED(HAS_HOTEND)) +#define TEMP_CASE_TOTAL TEMP_CASE_ABS + +#define PREHEAT_CASE_TEMP (0 + ENABLED(HAS_HOTEND)) +#define PREHEAT_CASE_BED (PREHEAT_CASE_TEMP + ENABLED(HAS_HEATED_BED)) +#define PREHEAT_CASE_FAN (PREHEAT_CASE_BED + ENABLED(HAS_FAN)) +#define PREHEAT_CASE_SAVE (PREHEAT_CASE_FAN + ENABLED(EEPROM_SETTINGS)) +#define PREHEAT_CASE_TOTAL PREHEAT_CASE_SAVE + +// +// Draw Menus +// + inline void draw_move_en(const uint16_t line) { DWIN_Frame_AreaCopy(1, 69, 61, 102, 71, LBLX, line); // "Move" } 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); } -inline void Prepare_Item_Move(const uint8_t row) { +inline void Item_Prepare_Move(const uint8_t row) { if (HMI_flag.language_chinese) DWIN_Frame_AreaCopy(1, 159, 70, 200, 84, LBLX, MBASE(row)); else @@ -509,7 +561,7 @@ inline void Prepare_Item_Move(const uint8_t row) { Draw_More_Icon(row); } -inline void Prepare_Item_Disable(const uint8_t row) { +inline void Item_Prepare_Disable(const uint8_t row) { if (HMI_flag.language_chinese) DWIN_Frame_AreaCopy(1, 204, 70, 259, 82, LBLX, MBASE(row)); else @@ -517,7 +569,7 @@ inline void Prepare_Item_Disable(const uint8_t row) { Draw_Menu_Line(row, ICON_CloseMotor); } -inline void Prepare_Item_Home(const uint8_t row) { +inline void Item_Prepare_Home(const uint8_t row) { if (HMI_flag.language_chinese) DWIN_Frame_AreaCopy(1, 0, 89, 41, 101, LBLX, MBASE(row)); else @@ -525,57 +577,65 @@ inline void Prepare_Item_Home(const uint8_t row) { Draw_Menu_Line(row, ICON_Homing); } -inline void Prepare_Item_Offset(const uint8_t row) { - if (HMI_flag.language_chinese) { - #if HAS_BED_PROBE - DWIN_Frame_AreaCopy(1, 174, 164, 223, 177, LBLX, MBASE(row)); - DWIN_Draw_Signed_Float(font8x16, Background_black, 2, 2, 202, MBASE(row), BABY_Z_VAR * 100); - #else - DWIN_Frame_AreaCopy(1, 43, 89, 98, 101, LBLX, MBASE(row)); - #endif - } - else { - #if HAS_BED_PROBE - DWIN_Frame_AreaCopy(1, 93, 179, 141, 189, LBLX, MBASE(row)); // "Z-Offset" - DWIN_Draw_Signed_Float(font8x16, Background_black, 2, 2, 202, MBASE(row), BABY_Z_VAR * 100); - #else - DWIN_Frame_AreaCopy(1, 1, 76, 106, 86, LBLX, MBASE(row)); // "..." - #endif - } - Draw_Menu_Line(row, ICON_SetHome); -} +#if HAS_ZOFFSET_ITEM -inline void Prepare_Item_PLA(const uint8_t row) { - if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 100, 89, 151, 101, LBLX, MBASE(row)); - } - 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" + inline void Item_Prepare_Offset(const uint8_t row) { + if (HMI_flag.language_chinese) { + #if HAS_BED_PROBE + DWIN_Frame_AreaCopy(1, 174, 164, 223, 177, LBLX, MBASE(row)); + DWIN_Draw_Signed_Float(font8x16, Background_black, 2, 2, 202, MBASE(row), BABY_Z_VAR * 100); + #else + DWIN_Frame_AreaCopy(1, 43, 89, 98, 101, LBLX, MBASE(row)); + #endif + } + else { + #if HAS_BED_PROBE + DWIN_Frame_AreaCopy(1, 93, 179, 141, 189, LBLX, MBASE(row)); // "Z-Offset" + DWIN_Draw_Signed_Float(font8x16, Background_black, 2, 2, 202, MBASE(row), BABY_Z_VAR * 100); + #else + DWIN_Frame_AreaCopy(1, 1, 76, 106, 86, LBLX, MBASE(row)); // "..." + #endif + } + Draw_Menu_Line(row, ICON_SetHome); } - Draw_Menu_Line(row, ICON_PLAPreheat); -} -inline void Prepare_Item_ABS(const uint8_t row) { - if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 180, 89, 233, 100, LBLX, MBASE(row)); +#endif + +#if HAS_HOTEND + inline void Item_Prepare_PLA(const uint8_t row) { + if (HMI_flag.language_chinese) { + DWIN_Frame_AreaCopy(1, 100, 89, 151, 101, LBLX, MBASE(row)); + } + 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" + } + Draw_Menu_Line(row, ICON_PLAPreheat); } - 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" + + inline void Item_Prepare_ABS(const uint8_t row) { + if (HMI_flag.language_chinese) { + DWIN_Frame_AreaCopy(1, 180, 89, 233, 100, LBLX, MBASE(row)); + } + 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" + } + Draw_Menu_Line(row, ICON_ABSPreheat); } - Draw_Menu_Line(row, ICON_ABSPreheat); -} +#endif -inline void Prepare_Item_Cool(const uint8_t row) { - if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 1, 104, 56, 117, LBLX, MBASE(row)); - else - DWIN_Frame_AreaCopy(1, 200, 76, 264, 86, LBLX, MBASE(row)); // "Cooldown" - Draw_Menu_Line(row, ICON_Cool); -} +#if HAS_PREHEAT + inline void Item_Prepare_Cool(const uint8_t row) { + if (HMI_flag.language_chinese) + DWIN_Frame_AreaCopy(1, 1, 104, 56, 117, LBLX, MBASE(row)); + else + DWIN_Frame_AreaCopy(1, 200, 76, 264, 86, LBLX, MBASE(row)); // "Cooldown" + Draw_Menu_Line(row, ICON_Cool); + } +#endif -inline void Prepare_Item_Lang(const uint8_t row) { +inline void Item_Prepare_Lang(const uint8_t row) { if (HMI_flag.language_chinese) { DWIN_Frame_AreaCopy(1, 239, 134, 266, 146, LBLX, MBASE(row)); DWIN_Draw_String(false, false, font8x16, White, Background_black, 226, MBASE(row), F("CN")); @@ -605,15 +665,21 @@ inline void Draw_Prepare_Menu() { #endif } - if (PVISI(0)) Draw_Back_First(select_prepare.now == 0); // < Back - if (PVISI(1)) Prepare_Item_Move(PSCROL(1)); // Move > - if (PVISI(2)) Prepare_Item_Disable(PSCROL(2)); // Disable Stepper - if (PVISI(3)) Prepare_Item_Home(PSCROL(3)); // Auto Home - if (PVISI(4)) Prepare_Item_Offset(PSCROL(4)); // Z-Offset - if (PVISI(5)) Prepare_Item_PLA(PSCROL(5)); // Preheat PLA - if (PVISI(6)) Prepare_Item_ABS(PSCROL(6)); // Preheat ABS - if (PVISI(7)) Prepare_Item_Cool(PSCROL(7)); // Cooldown - if (PVISI(8)) Prepare_Item_Lang(PSCROL(8)); // Language CN/EN + if (PVISI(0)) Draw_Back_First(select_prepare.now == 0); // < 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 + #if HAS_ZOFFSET_ITEM + if (PVISI(PREPARE_CASE_ZOFF)) Item_Prepare_Offset(PSCROL(PREPARE_CASE_ZOFF)); // Edit Z-Offset / Babystep / Set Home Offset + #endif + #if HAS_HOTEND + if (PVISI(PREPARE_CASE_PLA)) Item_Prepare_PLA(PSCROL(PREPARE_CASE_PLA)); // Preheat PLA + if (PVISI(PREPARE_CASE_ABS)) Item_Prepare_ABS(PSCROL(PREPARE_CASE_ABS)); // Preheat ABS + #endif + #if HAS_PREHEAT + if (PVISI(PREPARE_CASE_COOL)) Item_Prepare_Cool(PSCROL(PREPARE_CASE_COOL)); // Cooldown + #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)); } @@ -621,52 +687,55 @@ inline void Draw_Prepare_Menu() { inline void Draw_Control_Menu() { Clear_Main_Window(); - const int16_t scroll = TERN(HAS_ONESTEP_LEVELING, MROWS - index_control, 0); // Scrolled-up lines - - #define CSCROL(L) (scroll + (L)) + #if CONTROL_CASE_TOTAL >= 6 + const int16_t scroll = MROWS - index_control; // Scrolled-up lines + #define CSCROL(L) (scroll + (L)) + #else + #define CSCROL(L) (L) + #endif #define CLINE(L) MBASE(CSCROL(L)) #define CVISI(L) WITHIN(CSCROL(L), 0, MROWS) if (CVISI(0)) Draw_Back_First(select_control.now == 0); // < Back if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 103, 1, 130, 14, 14, 8); - DWIN_Frame_AreaCopy(1, 57, 104, 84, 116, LBLX, CLINE(1)); // Temperature > - DWIN_Frame_AreaCopy(1, 87, 104, 114, 116, LBLX, CLINE(2)); // Motion > - DWIN_Frame_AreaCopy(1, 117, 104, 172, 116, LBLX, CLINE(3)); // Store Config - DWIN_Frame_AreaCopy(1, 174, 103, 229, 116, LBLX, CLINE(4)); // Read Config - DWIN_Frame_AreaCopy(1, 1, 118, 56, 131, LBLX, CLINE(5)); // Reset Config + 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 - if (CVISI(6)) - DWIN_Frame_AreaCopy(1, 231, 104, 258, 116, LBLX, CLINE(6)); // Info > + if (CVISI(CONTROL_CASE_INFO)) + DWIN_Frame_AreaCopy(1, 231, 104, 258, 116, LBLX, CLINE(CONTROL_CASE_TEMP)); // Info > } else { #ifdef USE_STRING_HEADINGS Draw_Title(GET_TEXT_F(MSG_CONTROL)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(1), GET_TEXT_F(MSG_TEMPERATURE)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(2), GET_TEXT_F(MSG_MOTION)); + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(CONTROL_CASE_TEMP), GET_TEXT_F(MSG_TEMPERATURE)); + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(CONTROL_CASE_MOVE), GET_TEXT_F(MSG_MOTION)); #if ENABLED(EEPROM_SETTINGS) - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(3), GET_TEXT_F(MSG_STORE_EEPROM)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(4), GET_TEXT_F(MSG_LOAD_EEPROM)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(5), GET_TEXT_F(MSG_RESTORE_DEFAULTS)); - if (CVISI(6)) DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(6), F("Info")); - #else - if (CVISI(3)) DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(3), F("Info")); + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(CONTROL_CASE_SAVE), GET_TEXT_F(MSG_STORE_EEPROM)); + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(CONTROL_CASE_LOAD), GET_TEXT_F(MSG_LOAD_EEPROM)); + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(CONTROL_CASE_RESET), GET_TEXT_F(MSG_RESTORE_DEFAULTS)); #endif + if (CVISI(CONTROL_CASE_INFO)) DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(CONTROL_CASE_INFO), F("Info")); #else - DWIN_Frame_AreaCopy(1, 128, 2, 176, 12, 14, 8); - DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX, CLINE(1)); // Temperature > - DWIN_Frame_AreaCopy(1, 84, 89, 128, 99, LBLX, CLINE(2)); // Motion > + DWIN_Frame_TitleCopy(1, 128, 2, 176, 12); // "Control" + DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX, CLINE(CONTROL_CASE_TEMP)); // Temperature > + DWIN_Frame_AreaCopy(1, 84, 89, 128, 99, LBLX, CLINE(CONTROL_CASE_MOVE)); // Motion > #if ENABLED(EEPROM_SETTINGS) - DWIN_Frame_AreaCopy(1, 148, 89, 268, 101, LBLX, CLINE(3)); // "Store Configuration" - DWIN_Frame_AreaCopy(1, 26, 104, 57, 114, LBLX, CLINE(4)); // "Read" - DWIN_Frame_AreaCopy(1, 182, 89, 268, 101, LBLX + 34, CLINE(4)); // "Configuration" - DWIN_Frame_AreaCopy(1, 59, 104, 93, 114, LBLX, CLINE(5)); // "Reset" - DWIN_Frame_AreaCopy(1, 182, 89, 268, 101, LBLX + 37, CLINE(5)); // "Configuration" - if (CVISI(6)) DWIN_Frame_AreaCopy(1, 0, 104, 25, 115, LBLX, CLINE(6)); // Info > - #else - if (CVISI(3)) DWIN_Frame_AreaCopy(1, 0, 104, 25, 115, LBLX, CLINE(3)); // Info > + DWIN_Frame_AreaCopy(1, 148, 89, 268, 101, LBLX , CLINE(CONTROL_CASE_SAVE // "Store Configuration" + 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" + 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" #endif + if (CVISI(CONTROL_CASE_INFO)) DWIN_Frame_AreaCopy(1, 0, 104, 25, 115, LBLX, CLINE(CONTROL_CASE_INFO)); // Info > #endif } @@ -674,12 +743,23 @@ inline void Draw_Control_Menu() { Draw_Menu_Cursor(CSCROL(select_control.now)); // Draw icons and lines - LOOP_L_N(i, 6) - if (CVISI(i + 1)) Draw_Menu_Line(CSCROL(i + 1), ICON_Temperature + i); + uint8_t i = 0; + #define _TEMP_ICON(N) do{ ++i; if (CVISI(i)) Draw_Menu_Line(CSCROL(i), ICON_SetEndTemp + (N) - 1); }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)); - Draw_More_Icon(CSCROL(1)); - Draw_More_Icon(CSCROL(2)); - if (CVISI(6)) Draw_More_Icon(CSCROL(6)); + #if ENABLED(EEPROM_SETTINGS) + _TEMP_ICON(CONTROL_CASE_SAVE); + _TEMP_ICON(CONTROL_CASE_LOAD); + _TEMP_ICON(CONTROL_CASE_RESET); + #endif + + _TEMP_ICON(CONTROL_CASE_INFO); + if (CVISI(CONTROL_CASE_INFO)) Draw_More_Icon(CSCROL(i)); } inline void Draw_Tune_Menu() { @@ -687,46 +767,76 @@ inline void Draw_Tune_Menu() { if (HMI_flag.language_chinese) { DWIN_Frame_AreaCopy(1, 73, 2, 100, 13, 14, 9); - DWIN_Frame_AreaCopy(1, 116, 164, 171, 176, LBLX, MBASE(1)); - DWIN_Frame_AreaCopy(1, 1, 134, 56, 146, LBLX, MBASE(2)); - DWIN_Frame_AreaCopy(1, 58, 134, 113, 146, LBLX, MBASE(3)); - DWIN_Frame_AreaCopy(1, 115, 134, 170, 146, LBLX, MBASE(4)); - DWIN_Frame_AreaCopy(1, 174, 164, 223, 177, LBLX, MBASE(5)); + 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)); + #endif + #if HAS_HEATED_BED + DWIN_Frame_AreaCopy(1, 58, 134, 113, 146, LBLX, MBASE(TUNE_CASE_BED)); + #endif + #if HAS_FAN + DWIN_Frame_AreaCopy(1, 115, 134, 170, 146, LBLX, MBASE(TUNE_CASE_FAN)); + #endif + #if HAS_ZOFFSET_ITEM + DWIN_Frame_AreaCopy(1, 174, 164, 223, 177, LBLX, MBASE(TUNE_CASE_ZOFF)); + #endif } else { #ifdef USE_STRING_HEADINGS Draw_Title(GET_TEXT_F(MSG_TUNE)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(1), GET_TEXT_F(MSG_SPEED)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(2), GET_TEXT_F(MSG_UBL_SET_TEMP_HOTEND)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(3), GET_TEXT_F(MSG_UBL_SET_TEMP_BED)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(4), GET_TEXT_F(MSG_FAN_SPEED)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(5), GET_TEXT_F(MSG_ZPROBE_ZOFFSET)); + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(TUNE_CASE_SPEED), GET_TEXT_F(MSG_SPEED)); + #if HAS_HOTEND + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(TUNE_CASE_TEMP), GET_TEXT_F(MSG_UBL_SET_TEMP_HOTEND)); + #endif + #if HAS_HEATED_BED + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(TUNE_CASE_BED), GET_TEXT_F(MSG_UBL_SET_TEMP_BED)); + #endif + #if HAS_FAN + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(TUNE_CASE_FAN), GET_TEXT_F(MSG_FAN_SPEED)); + #endif + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(TUNE_CASE_ZOFF), GET_TEXT_F(MSG_ZPROBE_ZOFFSET)); #else DWIN_Frame_AreaCopy(1, 94, 2, 126, 12, 14, 9); - DWIN_Frame_AreaCopy(1, 1, 179, 92, 190, LBLX, MBASE(1)); // print speed - DWIN_Frame_AreaCopy(1, 197, 104, 238, 114, LBLX, MBASE(2)); // Hotend... - DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX + 44, MBASE(2)); // ...Temperature - DWIN_Frame_AreaCopy(1, 240, 104, 264, 114, LBLX, MBASE(3)); // Bed... - DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX + 27, MBASE(3)); // ...Temperature - DWIN_Frame_AreaCopy(1, 0, 119, 64, 132, LBLX, MBASE(4)); // fan speed - DWIN_Frame_AreaCopy(1, 93, 179, 141, 189, LBLX, MBASE(5)); // Z-offset + 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... + DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX + 44, MBASE(TUNE_CASE_TEMP)); // ...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 + #endif + #if HAS_FAN + DWIN_Frame_AreaCopy(1, 0, 119, 64, 132, LBLX, MBASE(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 + #endif #endif } Draw_Back_First(select_tune.now == 0); if (select_tune.now) Draw_Menu_Cursor(select_tune.now); - Draw_Menu_Line(1, ICON_Speed); - Draw_Menu_Line(2, ICON_HotendTemp); - Draw_Menu_Line(3, ICON_BedTemp); - Draw_Menu_Line(4, ICON_FanSpeed); - Draw_Menu_Line(5, ICON_Zoffset); + Draw_Menu_Line(TUNE_CASE_SPEED, ICON_Speed); + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(TUNE_CASE_SPEED), feedrate_percentage); - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(1), feedrate_percentage); - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(2), thermalManager.temp_hotend[0].target); - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(3), thermalManager.temp_bed.target); - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(4), thermalManager.fan_speed[0]); - DWIN_Draw_Signed_Float(font8x16, Background_black, 2, 2, 202, MBASE(5), BABY_Z_VAR * 100); + #if HAS_HOTEND + Draw_Menu_Line(TUNE_CASE_TEMP, ICON_HotendTemp); + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(TUNE_CASE_TEMP), thermalManager.temp_hotend[0].target); + #endif + #if HAS_HEATED_BED + Draw_Menu_Line(TUNE_CASE_BED, ICON_BedTemp); + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(TUNE_CASE_BED), thermalManager.temp_bed.target); + #endif + #if HAS_FAN + Draw_Menu_Line(TUNE_CASE_FAN, ICON_FanSpeed); + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(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, Background_black, 2, 2, 202, MBASE(TUNE_CASE_ZOFF), BABY_Z_VAR * 100); + #endif } inline void draw_max_en(const uint16_t line) { @@ -762,74 +872,84 @@ inline void Draw_Motion_Menu() { Clear_Main_Window(); if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 1, 16, 28, 28, 14, 8); - - DWIN_Frame_AreaCopy(1, 173, 133, 228, 147, LBLX, MBASE(1)); // Max speed - DWIN_Frame_AreaCopy(1, 173, 133, 200, 147, LBLX, MBASE(2)); // Max... - DWIN_Frame_AreaCopy(1, 28, 149, 69, 161, LBLX + 27, MBASE(2) + 1); // ...acceleration - DWIN_Frame_AreaCopy(1, 173, 133, 200, 147, LBLX, MBASE(3)); // Max... - DWIN_Frame_AreaCopy(1, 1, 180, 28, 192, LBLX + 27, MBASE(3) + 1); // ... - DWIN_Frame_AreaCopy(1, 202, 133, 228, 147, LBLX + 54, MBASE(3)); // ...jerk - DWIN_Frame_AreaCopy(1, 153, 148, 194, 161, LBLX, MBASE(4)); // Flow ratio + 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 + #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 + #endif + DWIN_Frame_AreaCopy(1, 153, 148, 194, 161, LBLX, MBASE(MOTION_CASE_STEPS)); // Flow ratio } else { #ifdef USE_STRING_HEADINGS Draw_Title(GET_TEXT_F(MSG_MOTION)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(1), F("Feedrate")); - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(2), GET_TEXT_F(MSG_ACCELERATION)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(3), GET_TEXT_F(MSG_JERK)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(4), GET_TEXT_F(MSG_STEPS_PER_MM)); + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(MOTION_CASE_RATE), F("Feedrate")); + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(MOTION_CASE_ACCEL), GET_TEXT_F(MSG_ACCELERATION)); + #if HAS_CLASSIC_JERK + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(MOTION_CASE_JERK), GET_TEXT_F(MSG_JERK)); + #endif + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(MOTION_CASE_STEPS), GET_TEXT_F(MSG_STEPS_PER_MM)); #else - DWIN_Frame_AreaCopy(1, 144, 16, 189, 26, 14, 8); - draw_max_en(MBASE(1)); draw_speed_en(27, MBASE(1)); // "Max Speed" - draw_max_accel_en(MBASE(2)); // "Max Acceleration" - draw_max_en(MBASE(3)); draw_jerk_en(MBASE(3)); // "Max Jerk" - draw_steps_per_mm(MBASE(4)); // "Steps-per-mm" + DWIN_Frame_TitleCopy(1, 144, 16, 189, 26); // "Motion" + 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" + #if HAS_CLASSIC_JERK + draw_max_en(MBASE(MOTION_CASE_JERK)); draw_jerk_en(MBASE(MOTION_CASE_JERK)); // "Max Jerk" + #endif + draw_steps_per_mm(MBASE(MOTION_CASE_STEPS)); // "Steps-per-mm" #endif } Draw_Back_First(select_motion.now == 0); if (select_motion.now) Draw_Menu_Cursor(select_motion.now); - LOOP_L_N(i, 4) Draw_Menu_Line(i + 1, ICON_MaxSpeed + i); - - Draw_More_Icon(1); - Draw_More_Icon(2); - Draw_More_Icon(3); - Draw_More_Icon(4); + uint8_t i = 0; + #define _MOTION_ICON(N) Draw_Menu_Line(++i, ICON_MaxSpeed + (N) - 1) + _MOTION_ICON(MOTION_CASE_RATE); Draw_More_Icon(i); + _MOTION_ICON(MOTION_CASE_ACCEL); Draw_More_Icon(i); + #if HAS_CLASSIC_JERK + _MOTION_ICON(MOTION_CASE_JERK); Draw_More_Icon(i); + #endif + _MOTION_ICON(MOTION_CASE_STEPS); Draw_More_Icon(i); } // // Draw Popup Windows // - -void Popup_Window_Temperature(const bool toohigh) { - Clear_Popup_Area(); - Draw_Popup_Bkgd_105(); - if (toohigh) { - DWIN_ICON_Show(ICON, ICON_TempTooHigh, 102, 165); - if (HMI_flag.language_chinese) { - 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 { - DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, 36, 300, F("Nozzle or Bed temperature")); - DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, 92, 300, F("is too high")); - } - } - else { - DWIN_ICON_Show(ICON, ICON_TempTooLow, 102, 165); - if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 103, 371, 270, 386, 52, 285); - DWIN_Frame_AreaCopy(1, 189, 389, 271, 402, 95, 310); +#if HAS_HOTEND || HAS_HEATED_BED + + void DWIN_Popup_Temperature(const bool toohigh) { + Clear_Popup_Area(); + Draw_Popup_Bkgd_105(); + if (toohigh) { + DWIN_ICON_Show(ICON, ICON_TempTooHigh, 102, 165); + if (HMI_flag.language_chinese) { + 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 { + DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, 36, 300, F("Nozzle or Bed temperature")); + DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, 92, 300, F("is too high")); + } } else { - DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, 36, 300, F("Nozzle or Bed temperature")); - DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, 92, 300, F("is too low")); + DWIN_ICON_Show(ICON, ICON_TempTooLow, 102, 165); + if (HMI_flag.language_chinese) { + DWIN_Frame_AreaCopy(1, 103, 371, 270, 386, 52, 285); + DWIN_Frame_AreaCopy(1, 189, 389, 271, 402, 95, 310); + } + else { + DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, 36, 300, F("Nozzle or Bed temperature")); + DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, 92, 300, F("is too low")); + } } } -} + +#endif inline void Draw_Popup_Bkgd_60() { DWIN_Draw_Rectangle(1, Background_window, 14, 60, 258, 330); @@ -837,7 +957,7 @@ inline void Draw_Popup_Bkgd_60() { #if HAS_HOTEND - void Popup_Window_ETempTooLow(void) { + void Popup_Window_ETempTooLow() { Clear_Main_Window(); Draw_Popup_Bkgd_60(); DWIN_ICON_Show(ICON, ICON_TempTooLow, 102, 105); @@ -854,7 +974,7 @@ inline void Draw_Popup_Bkgd_60() { #endif -void Popup_Window_Resume(void) { +void Popup_Window_Resume() { Clear_Popup_Area(); Draw_Popup_Bkgd_105(); if (HMI_flag.language_chinese) { @@ -864,15 +984,15 @@ void Popup_Window_Resume(void) { DWIN_ICON_Show(ICON, ICON_Cancel_C, 146, 307); } else { - DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, 120, 115, F("Tips")); - DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, 24, 192, F("I see the file stopped")); - DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, 68, 212, F("unexpectedly last time")); + DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, (272 - 8 * 14) / 2, 115, F("Continue Print")); + DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, (272 - 8 * 22) / 2, 192, F("It looks like the last")); + DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, (272 - 8 * 22) / 2, 212, F("file was interrupted.")); DWIN_ICON_Show(ICON, ICON_Continue_E, 26, 307); DWIN_ICON_Show(ICON, ICON_Cancel_E, 146, 307); } } -void Popup_Window_Home(void) { +void Popup_Window_Home(const bool parking/*=false*/) { Clear_Main_Window(); Draw_Popup_Bkgd_60(); DWIN_ICON_Show(ICON, ICON_BLTouch, 101, 105); @@ -882,24 +1002,28 @@ void Popup_Window_Home(void) { DWIN_Frame_AreaCopy(1, 0, 389, 150, 402, 61, 280); } else { - DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, 80, 230, GET_TEXT_F(MSG_LEVEL_BED_HOMING)); - DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, 24, 260, F("Please wait until completed")); + DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, (272 - 8 * (parking ? 7 : 10)) / 2, 230, parking ? F("Parking") : F("Homing XYZ")); + DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, (272 - 8 * 23) / 2, 260, F("Please wait until done.")); } } -void Popup_Window_Leveling(void) { - Clear_Main_Window(); - Draw_Popup_Bkgd_60(); - DWIN_ICON_Show(ICON, ICON_AutoLeveling, 101, 105); - if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 0, 371, 100, 386, 84, 240); - DWIN_Frame_AreaCopy(1, 0, 389, 150, 402, 61, 280); - } - else { - DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, 76, 230, GET_TEXT_F(MSG_BED_LEVELING)); - DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, 24, 260, F("Please wait until completed")); +#if HAS_ONESTEP_LEVELING + + void Popup_Window_Leveling() { + Clear_Main_Window(); + Draw_Popup_Bkgd_60(); + DWIN_ICON_Show(ICON, ICON_AutoLeveling, 101, 105); + if (HMI_flag.language_chinese) { + DWIN_Frame_AreaCopy(1, 0, 371, 100, 386, 84, 240); + DWIN_Frame_AreaCopy(1, 0, 389, 150, 402, 61, 280); + } + else { + DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, (272 - 8 * 13) / 2, 230, GET_TEXT_F(MSG_BED_LEVELING)); + DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, (272 - 8 * 23) / 2, 260, F("Please wait until done.")); + } } -} + +#endif void Draw_Select_Highlight(const bool sel) { HMI_flag.select_flag = sel; @@ -911,34 +1035,34 @@ void Draw_Select_Highlight(const bool sel) { DWIN_Draw_Rectangle(0, c2, 144, 278, 247, 319); } -void Popup_window_PauseOrStop(void) { +void Popup_window_PauseOrStop() { Clear_Main_Window(); Draw_Popup_Bkgd_60(); if (HMI_flag.language_chinese) { - if (select_print.now == 1) DWIN_Frame_AreaCopy(1, 237, 338, 269, 356, 98, 150); + 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); 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(false, true, font8x16, Font_window, Background_window, 88, 150, GET_TEXT_F(MSG_PAUSE_PRINT)); - else if (select_print.now == 2) DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, 92, 150, GET_TEXT_F(MSG_STOP_PRINT)); + if (select_print.now == 1) DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, (272 - 8 * 11) / 2, 150, GET_TEXT_F(MSG_PAUSE_PRINT)); + else if (select_print.now == 2) DWIN_Draw_String(false, true, font8x16, Font_window, Background_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); } Draw_Select_Highlight(true); } -void Draw_Printing_Screen(void) { +void Draw_Printing_Screen() { if (HMI_flag.language_chinese) { - 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, 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 } 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, 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 } } @@ -963,7 +1087,7 @@ void Draw_Print_ProgressRemain() { DWIN_Draw_IntValue(true, true, 1, font8x16, White, Background_black, 2, 200, 212, (remain_time % 3600) / 60); } -void Goto_PrintProcess(void) { +void Goto_PrintProcess() { checkkey = PrintProcess; Clear_Main_Window(); @@ -986,7 +1110,7 @@ void Goto_PrintProcess(void) { Draw_Print_ProgressRemain(); } -void Goto_MainMenu(void) { +void Goto_MainMenu() { checkkey = MainMenu; Clear_Main_Window(); @@ -1011,6 +1135,7 @@ void Goto_MainMenu(void) { } 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(); @@ -1018,7 +1143,7 @@ inline ENCODER_DiffState get_encoder_state() { return state; } -void HMI_Move_X(void) { +void HMI_Move_X() { ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); if (encoder_diffState != ENCODER_DIFF_NO) { if (encoder_diffState == ENCODER_DIFF_CW) { @@ -1029,7 +1154,7 @@ void HMI_Move_X(void) { } else if (encoder_diffState == ENCODER_DIFF_ENTER) { checkkey = AxisMove; - EncoderRate.encoderRateEnabled = 0; + EncoderRate.enabled = false; DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 216, MBASE(1), HMI_ValueStruct.Move_X_scale); if (!planner.is_full()) { // Wait for planner moves to finish! @@ -1047,7 +1172,7 @@ void HMI_Move_X(void) { } } -void HMI_Move_Y(void) { +void HMI_Move_Y() { ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); if (encoder_diffState != ENCODER_DIFF_NO) { if (encoder_diffState == ENCODER_DIFF_CW) { @@ -1058,7 +1183,7 @@ void HMI_Move_Y(void) { } else if (encoder_diffState == ENCODER_DIFF_ENTER) { checkkey = AxisMove; - EncoderRate.encoderRateEnabled = 0; + EncoderRate.enabled = false; DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 216, MBASE(2), HMI_ValueStruct.Move_Y_scale); if (!planner.is_full()) { // Wait for planner moves to finish! @@ -1076,7 +1201,7 @@ void HMI_Move_Y(void) { } } -void HMI_Move_Z(void) { +void HMI_Move_Z() { ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); if (encoder_diffState != ENCODER_DIFF_NO) { if (encoder_diffState == ENCODER_DIFF_CW) { @@ -1087,7 +1212,7 @@ void HMI_Move_Z(void) { } else if (encoder_diffState == ENCODER_DIFF_ENTER) { checkkey = AxisMove; - EncoderRate.encoderRateEnabled = 0; + EncoderRate.enabled = false; DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 216, MBASE(3), HMI_ValueStruct.Move_Z_scale); if (!planner.is_full()) { // Wait for planner moves to finish! @@ -1107,7 +1232,8 @@ void HMI_Move_Z(void) { #if HAS_HOTEND - void HMI_Move_E(void) { + void HMI_Move_E() { + static float last_E_scale = 0; ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); if (encoder_diffState != ENCODER_DIFF_NO) { if (encoder_diffState == ENCODER_DIFF_CW) { @@ -1118,7 +1244,7 @@ void HMI_Move_Z(void) { } else if (encoder_diffState == ENCODER_DIFF_ENTER) { checkkey = AxisMove; - EncoderRate.encoderRateEnabled = 0; + EncoderRate.enabled = false; last_E_scale = HMI_ValueStruct.Move_E_scale; DWIN_Draw_Signed_Float(font8x16, Background_black, 3, 1, 216, MBASE(4), HMI_ValueStruct.Move_E_scale); if (!planner.is_full()) { @@ -1140,53 +1266,66 @@ void HMI_Move_Z(void) { #endif -void HMI_Zoffset(void) { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - last_zoffset = dwin_zoffset; - if (encoder_diffState == ENCODER_DIFF_CW) { - HMI_ValueStruct.offset_value += EncoderRate.encoderMoveValue; - } - else if (encoder_diffState == ENCODER_DIFF_CCW) { - HMI_ValueStruct.offset_value -= EncoderRate.encoderMoveValue; - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { - EncoderRate.encoderRateEnabled = 0; - dwin_zoffset = HMI_ValueStruct.offset_value / 100; - #if HAS_BED_PROBE - if (WITHIN(dwin_zoffset - last_zoffset, Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX)) - probe.offset.z = dwin_zoffset; - TERN_(EEPROM_SETTINGS, settings.save()); - #elif ENABLED(BABYSTEPPING) - babystep.add_mm(Z_AXIS, dwin_zoffset - last_zoffset); - #endif +#if HAS_ZOFFSET_ITEM - if (HMI_ValueStruct.show_mode == -4) { - checkkey = Prepare; - DWIN_Draw_Signed_Float(font8x16, Background_black, 2, 2, 202, MBASE(4 + MROWS - index_prepare), TERN(HAS_BED_PROBE, probe.offset.z * 100, HMI_ValueStruct.offset_value)); + bool printer_busy() { return planner.movesplanned() || printingIsActive(); } + + 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; } - else { - checkkey = Tune; - DWIN_Draw_Signed_Float(font8x16, Background_black, 2, 2, 202, MBASE(5 + MROWS - index_tune), TERN(HAS_BED_PROBE, probe.offset.z * 100, HMI_ValueStruct.offset_value)); + if (encoder_diffState == ENCODER_DIFF_CW) + HMI_ValueStruct.offset_value += EncoderRate.encoderMoveValue; + else if (encoder_diffState == ENCODER_DIFF_CCW) + HMI_ValueStruct.offset_value -= EncoderRate.encoderMoveValue; + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + EncoderRate.enabled = false; + #if HAS_BED_PROBE + probe.offset.z = dwin_zoffset; + TERN_(EEPROM_SETTINGS, settings.save()); + #endif + if (HMI_ValueStruct.show_mode == -4) { + checkkey = Prepare; + DWIN_Draw_Signed_Float(font8x16, Background_black, 2, 2, 202, MBASE(zoff_line), TERN(HAS_BED_PROBE, BABY_Z_VAR * 100, HMI_ValueStruct.offset_value)); + } + else { + checkkey = Tune; + DWIN_Draw_Signed_Float(font8x16, Background_black, 2, 2, 202, MBASE(zoff_line), TERN(HAS_BED_PROBE, BABY_Z_VAR * 100, HMI_ValueStruct.offset_value)); + } + DWIN_UpdateLCD(); + return; } + NOLESS(HMI_ValueStruct.offset_value, (Z_PROBE_OFFSET_RANGE_MIN) * 100); + NOMORE(HMI_ValueStruct.offset_value, (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 ( (ENABLED(BABYSTEP_WITHOUT_HOMING) || all_axes_known()) && (ENABLED(BABYSTEP_ALWAYS_AVAILABLE) || printer_busy()) ) + 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_UpdateLCD(); - return; } - NOLESS(HMI_ValueStruct.offset_value, (Z_PROBE_OFFSET_RANGE_MIN) * 100); - NOMORE(HMI_ValueStruct.offset_value, (Z_PROBE_OFFSET_RANGE_MAX) * 100); - if (HMI_ValueStruct.show_mode == -4) - DWIN_Draw_Signed_Float(font8x16, Select_Color, 2, 2, 202, MBASE(4 + MROWS - index_prepare), HMI_ValueStruct.offset_value); - else - DWIN_Draw_Signed_Float(font8x16, Select_Color, 2, 2, 202, MBASE(5 + MROWS - index_tune), HMI_ValueStruct.offset_value); - DWIN_UpdateLCD(); } -} + +#endif // HAS_ZOFFSET_ITEM #if HAS_HOTEND - void HMI_ETemp(void) { + 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 (encoder_diffState == ENCODER_DIFF_CW) { HMI_ValueStruct.E_Temp += EncoderRate.encoderMoveValue; } @@ -1194,26 +1333,26 @@ void HMI_Zoffset(void) { HMI_ValueStruct.E_Temp -= EncoderRate.encoderMoveValue; } else if (encoder_diffState == ENCODER_DIFF_ENTER) { // return - EncoderRate.encoderRateEnabled = 0; + EncoderRate.enabled = false; if (HMI_ValueStruct.show_mode == -1) { // temperature checkkey = TemperatureID; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(1), HMI_ValueStruct.E_Temp); + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(temp_line), HMI_ValueStruct.E_Temp); } else 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, White, Background_black, 3, 216, MBASE(1), ui.material_preset[0].hotend_temp); + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(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, White, Background_black, 3, 216, MBASE(1), ui.material_preset[1].hotend_temp); + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(temp_line), ui.material_preset[1].hotend_temp); return; } else { // tune checkkey = Tune; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(2 + MROWS - index_tune), HMI_ValueStruct.E_Temp); + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(temp_line), HMI_ValueStruct.E_Temp); } thermalManager.setTargetHotend(HMI_ValueStruct.E_Temp, 0); return; @@ -1222,10 +1361,7 @@ void HMI_Zoffset(void) { NOMORE(HMI_ValueStruct.E_Temp, MAX_E_TEMP); NOLESS(HMI_ValueStruct.E_Temp, MIN_E_TEMP); // E_Temp value - if (HMI_ValueStruct.show_mode >= 0) // tune - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(2 + MROWS - index_tune), HMI_ValueStruct.E_Temp); - else // other page - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(1), HMI_ValueStruct.E_Temp); + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(temp_line), HMI_ValueStruct.E_Temp); } } @@ -1233,9 +1369,16 @@ void HMI_Zoffset(void) { #if HAS_HEATED_BED - void HMI_BedTemp(void) { + 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 (encoder_diffState == ENCODER_DIFF_CW) { HMI_ValueStruct.Bed_Temp += EncoderRate.encoderMoveValue; } @@ -1243,26 +1386,26 @@ void HMI_Zoffset(void) { HMI_ValueStruct.Bed_Temp -= EncoderRate.encoderMoveValue; } else if (encoder_diffState == ENCODER_DIFF_ENTER) { // return - EncoderRate.encoderRateEnabled = 0; + EncoderRate.enabled = false; if (HMI_ValueStruct.show_mode == -1) { checkkey = TemperatureID; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(2), HMI_ValueStruct.Bed_Temp); + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(bed_line), HMI_ValueStruct.Bed_Temp); } else 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, White, Background_black, 3, 216, MBASE(2), ui.material_preset[0].bed_temp); + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(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, White, Background_black, 3, 216, MBASE(2), ui.material_preset[1].bed_temp); + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(bed_line), ui.material_preset[1].bed_temp); return; } else { checkkey = Tune; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(3 + MROWS - index_tune), HMI_ValueStruct.Bed_Temp); + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(bed_line), HMI_ValueStruct.Bed_Temp); } thermalManager.setTargetBed(HMI_ValueStruct.Bed_Temp); return; @@ -1271,20 +1414,25 @@ void HMI_Zoffset(void) { NOMORE(HMI_ValueStruct.Bed_Temp, BED_MAX_TARGET); NOLESS(HMI_ValueStruct.Bed_Temp, MIN_BED_TEMP); // Bed_Temp value - if (HMI_ValueStruct.show_mode >= 0) // tune page - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(3 + MROWS - index_tune), HMI_ValueStruct.Bed_Temp); - else // other page - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(2), HMI_ValueStruct.Bed_Temp); + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(bed_line), HMI_ValueStruct.Bed_Temp); } } #endif // HAS_HEATED_BED -#if HAS_FAN +#if HAS_PREHEAT - void HMI_FanSpeed(void) { + 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_CW) { HMI_ValueStruct.Fan_speed += EncoderRate.encoderMoveValue; } @@ -1292,26 +1440,26 @@ void HMI_Zoffset(void) { HMI_ValueStruct.Fan_speed -= EncoderRate.encoderMoveValue; } else if (encoder_diffState == ENCODER_DIFF_ENTER) { // return - EncoderRate.encoderRateEnabled = 0; + EncoderRate.enabled = false; if (HMI_ValueStruct.show_mode == -1) { checkkey = TemperatureID; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(3), HMI_ValueStruct.Fan_speed); + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(fan_line), HMI_ValueStruct.Fan_speed); } else 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, White, Background_black, 3, 216, MBASE(3), ui.material_preset[0].fan_speed); + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(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, White, Background_black, 3, 216, MBASE(3), ui.material_preset[1].fan_speed); + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(fan_line), ui.material_preset[1].fan_speed); return; } else { checkkey = Tune; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(4 + MROWS - index_tune), HMI_ValueStruct.Fan_speed); + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(fan_line), HMI_ValueStruct.Fan_speed); } thermalManager.set_fan_speed(0, HMI_ValueStruct.Fan_speed); return; @@ -1320,16 +1468,13 @@ void HMI_Zoffset(void) { NOMORE(HMI_ValueStruct.Fan_speed, FANON); NOLESS(HMI_ValueStruct.Fan_speed, FANOFF); // Fan_speed value - if (HMI_ValueStruct.show_mode >= 0) // tune page - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(4 + MROWS - index_tune), HMI_ValueStruct.Fan_speed); - else // other page - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(3), HMI_ValueStruct.Fan_speed); + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(fan_line), HMI_ValueStruct.Fan_speed); } } -#endif // HAS_FAN +#endif // HAS_PREHEAT -void HMI_PrintSpeed(void) { +void HMI_PrintSpeed() { ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); if (encoder_diffState != ENCODER_DIFF_NO) { if (encoder_diffState == ENCODER_DIFF_CW) { @@ -1340,20 +1485,20 @@ void HMI_PrintSpeed(void) { } else if (encoder_diffState == ENCODER_DIFF_ENTER) { // return checkkey = Tune; - EncoderRate.encoderRateEnabled = 0; + EncoderRate.enabled = false; feedrate_percentage = HMI_ValueStruct.print_speed; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(1 + MROWS - index_tune), HMI_ValueStruct.print_speed); + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(select_tune.now + MROWS - index_tune), HMI_ValueStruct.print_speed); return; } // print_speed limit NOMORE(HMI_ValueStruct.print_speed, MAX_PRINT_SPEED); NOLESS(HMI_ValueStruct.print_speed, MIN_PRINT_SPEED); // print_speed value - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(1 + MROWS - index_tune), HMI_ValueStruct.print_speed); + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(select_tune.now + MROWS - index_tune), HMI_ValueStruct.print_speed); } } -void HMI_MaxFeedspeedXYZE(void) { +void HMI_MaxFeedspeedXYZE() { ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); if (encoder_diffState != ENCODER_DIFF_NO) { if (encoder_diffState == ENCODER_DIFF_CW) { @@ -1364,82 +1509,76 @@ void HMI_MaxFeedspeedXYZE(void) { } else if (encoder_diffState == ENCODER_DIFF_ENTER) { // return checkkey = MaxSpeed; - EncoderRate.encoderRateEnabled = 0; - if (WITHIN(HMI_flag.feedspeed_flag, X_AXIS, E_AXIS)) - planner.set_max_feedrate(HMI_flag.feedspeed_flag, HMI_ValueStruct.Max_Feedspeed); + EncoderRate.enabled = false; + if (WITHIN(HMI_flag.feedspeed_axis, X_AXIS, E_AXIS)) + planner.set_max_feedrate(HMI_flag.feedspeed_axis, HMI_ValueStruct.Max_Feedspeed); DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 4, 210, MBASE(select_speed.now), HMI_ValueStruct.Max_Feedspeed); return; } // MaxFeedspeed limit - if (WITHIN(HMI_flag.feedspeed_flag, X_AXIS, E_AXIS)) - NOMORE(HMI_ValueStruct.Max_Feedspeed, default_max_feedrate[HMI_flag.feedspeed_flag] * 2); + if (WITHIN(HMI_flag.feedspeed_axis, X_AXIS, E_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 DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 4, 210, MBASE(select_speed.now), HMI_ValueStruct.Max_Feedspeed); } } -void HMI_MaxAccelerationXYZE(void) { +void HMI_MaxAccelerationXYZE() { ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); if (encoder_diffState != ENCODER_DIFF_NO) { if (encoder_diffState == ENCODER_DIFF_CW) { HMI_ValueStruct.Max_Acceleration += EncoderRate.encoderMoveValue;} else if (encoder_diffState == ENCODER_DIFF_CCW) { HMI_ValueStruct.Max_Acceleration -= EncoderRate.encoderMoveValue;} else if (encoder_diffState == ENCODER_DIFF_ENTER) { // return checkkey = MaxAcceleration; - EncoderRate.encoderRateEnabled = 0; - if (HMI_flag.acc_flag == X_AXIS) planner.set_max_acceleration(X_AXIS, HMI_ValueStruct.Max_Acceleration); - else if (HMI_flag.acc_flag == Y_AXIS) planner.set_max_acceleration(Y_AXIS, HMI_ValueStruct.Max_Acceleration); - else if (HMI_flag.acc_flag == Z_AXIS) planner.set_max_acceleration(Z_AXIS, HMI_ValueStruct.Max_Acceleration); + EncoderRate.enabled = false; + if (HMI_flag.acc_axis == X_AXIS) planner.set_max_acceleration(X_AXIS, HMI_ValueStruct.Max_Acceleration); + else if (HMI_flag.acc_axis == Y_AXIS) planner.set_max_acceleration(Y_AXIS, HMI_ValueStruct.Max_Acceleration); + else if (HMI_flag.acc_axis == Z_AXIS) planner.set_max_acceleration(Z_AXIS, HMI_ValueStruct.Max_Acceleration); #if HAS_HOTEND - else if (HMI_flag.acc_flag == E_AXIS) planner.set_max_acceleration(E_AXIS, HMI_ValueStruct.Max_Acceleration); + else if (HMI_flag.acc_axis == E_AXIS) planner.set_max_acceleration(E_AXIS, HMI_ValueStruct.Max_Acceleration); #endif DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 4, 210, MBASE(select_acc.now), HMI_ValueStruct.Max_Acceleration); return; } // MaxAcceleration limit - if (WITHIN(HMI_flag.acc_flag, X_AXIS, E_AXIS)) - NOMORE(HMI_ValueStruct.Max_Acceleration, default_max_acceleration[HMI_flag.acc_flag] * 2); + if (WITHIN(HMI_flag.acc_axis, X_AXIS, E_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 DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 4, 210, MBASE(select_acc.now), HMI_ValueStruct.Max_Acceleration); } } -void HMI_MaxJerkXYZE(void) { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - if (encoder_diffState == ENCODER_DIFF_CW) { - HMI_ValueStruct.Max_Jerk += EncoderRate.encoderMoveValue; - } - else if (encoder_diffState == ENCODER_DIFF_CCW) { - HMI_ValueStruct.Max_Jerk -= EncoderRate.encoderMoveValue; - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { // return - checkkey = MaxJerk; - EncoderRate.encoderRateEnabled = 0; - if (HMI_flag.jerk_flag == X_AXIS) planner.set_max_jerk(X_AXIS, HMI_ValueStruct.Max_Jerk / 10); - else if (HMI_flag.jerk_flag == Y_AXIS) planner.set_max_jerk(Y_AXIS, HMI_ValueStruct.Max_Jerk / 10); - else if (HMI_flag.jerk_flag == Z_AXIS) planner.set_max_jerk(Z_AXIS, HMI_ValueStruct.Max_Jerk / 10); - else if (HMI_flag.jerk_flag == E_AXIS) planner.set_max_jerk(E_AXIS, HMI_ValueStruct.Max_Jerk / 10); - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 210, MBASE(select_jerk.now), HMI_ValueStruct.Max_Jerk); - return; +#if HAS_CLASSIC_JERK + + void HMI_MaxJerkXYZE() { + ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState != ENCODER_DIFF_NO) { + if (encoder_diffState == ENCODER_DIFF_CW) + HMI_ValueStruct.Max_Jerk += EncoderRate.encoderMoveValue; + else if (encoder_diffState == ENCODER_DIFF_CCW) + HMI_ValueStruct.Max_Jerk -= EncoderRate.encoderMoveValue; + else if (encoder_diffState == ENCODER_DIFF_ENTER) { // return + checkkey = MaxJerk; + EncoderRate.enabled = false; + if (WITHIN(HMI_flag.step_axis, X_AXIS, E_AXIS)) + planner.set_max_jerk(HMI_flag.step_axis, HMI_ValueStruct.Max_Jerk / 10); + DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 210, MBASE(select_jerk.now), HMI_ValueStruct.Max_Jerk); + return; + } + // MaxJerk limit + if (WITHIN(HMI_flag.jerk_axis, X_AXIS, E_AXIS)) + NOMORE(HMI_ValueStruct.Max_Jerk, default_max_jerk[HMI_flag.jerk_axis] * 2 * MINUNITMULT); + NOLESS(HMI_ValueStruct.Max_Jerk, (MIN_MAXJERK) * MINUNITMULT); + // MaxJerk value + DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 210, MBASE(select_jerk.now), HMI_ValueStruct.Max_Jerk); } - // MaxJerk limit - if (HMI_flag.jerk_flag == X_AXIS) - NOMORE(HMI_ValueStruct.Max_Jerk, default_max_jerk[X_AXIS] * 2 * MINUNITMULT); - else if (HMI_flag.jerk_flag == Y_AXIS) - NOMORE(HMI_ValueStruct.Max_Jerk, default_max_jerk[Y_AXIS] * 2 * MINUNITMULT); - else if (HMI_flag.jerk_flag == Z_AXIS) - NOMORE(HMI_ValueStruct.Max_Jerk, default_max_jerk[Z_AXIS] * 2 * MINUNITMULT); - else if (HMI_flag.jerk_flag == E_AXIS) - NOMORE(HMI_ValueStruct.Max_Jerk, default_max_jerk[E_AXIS] * 2 * MINUNITMULT); - NOLESS(HMI_ValueStruct.Max_Jerk, (MIN_MAXJERK) * MINUNITMULT); - // MaxJerk value - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 210, MBASE(select_jerk.now), HMI_ValueStruct.Max_Jerk); } -} -void HMI_StepXYZE(void) { +#endif // HAS_CLASSIC_JERK + +void HMI_StepXYZE() { ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); if (encoder_diffState != ENCODER_DIFF_NO) { if (encoder_diffState == ENCODER_DIFF_CW) { @@ -1450,71 +1589,100 @@ void HMI_StepXYZE(void) { } else if (encoder_diffState == ENCODER_DIFF_ENTER) { // return checkkey = Step; - EncoderRate.encoderRateEnabled = 0; - if (WITHIN(HMI_flag.step_flag, X_AXIS, E_AXIS)) - planner.settings.axis_steps_per_mm[HMI_flag.step_flag] = HMI_ValueStruct.Max_Step / 10; + EncoderRate.enabled = false; + if (WITHIN(HMI_flag.step_axis, X_AXIS, E_AXIS)) + planner.settings.axis_steps_per_mm[HMI_flag.step_axis] = HMI_ValueStruct.Max_Step / 10; DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 210, MBASE(select_step.now), HMI_ValueStruct.Max_Step); return; } // Step limit - if (WITHIN(HMI_flag.step_flag, X_AXIS, E_AXIS)) - NOMORE(HMI_ValueStruct.Max_Step, default_axis_steps_per_unit[HMI_flag.step_flag] * 2 * MINUNITMULT); + if (WITHIN(HMI_flag.step_axis, X_AXIS, E_AXIS)) + NOMORE(HMI_ValueStruct.Max_Step, default_axis_steps_per_unit[HMI_flag.step_axis] * 2 * MINUNITMULT); NOLESS(HMI_ValueStruct.Max_Step, MIN_STEP); // Step value DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 210, MBASE(select_step.now), HMI_ValueStruct.Max_Step); } } -void update_variable(void) { +void update_variable() { + #if HAS_HOTEND + static float last_temp_hotend_target = 0, last_temp_hotend_current = 0; + #endif + #if HAS_HEATED_BED + static float last_temp_bed_target = 0, last_temp_bed_current = 0; + #endif + #if HAS_FAN + static uint8_t last_fan_speed = 0; + #endif + /* Tune page temperature update */ if (checkkey == Tune) { - if (last_temp_hotend_target != thermalManager.temp_hotend[0].target) - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(2 + MROWS - index_tune), thermalManager.temp_hotend[0].target); - if (last_temp_bed_target != thermalManager.temp_bed.target) - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(3 + MROWS - index_tune), thermalManager.temp_bed.target); - if (last_fan_speed != thermalManager.fan_speed[0]) { - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(4 + MROWS - index_tune), thermalManager.fan_speed[0]); - last_fan_speed = thermalManager.fan_speed[0]; - } + #if HAS_HOTEND + if (last_temp_hotend_target != thermalManager.temp_hotend[0].target) + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(TUNE_CASE_TEMP + MROWS - index_tune), thermalManager.temp_hotend[0].target); + #endif + #if HAS_HEATED_BED + if (last_temp_bed_target != thermalManager.temp_bed.target) + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(TUNE_CASE_BED + MROWS - index_tune), thermalManager.temp_bed.target); + #endif + #if HAS_FAN + if (last_fan_speed != thermalManager.fan_speed[0]) { + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(TUNE_CASE_FAN + MROWS - index_tune), thermalManager.fan_speed[0]); + last_fan_speed = thermalManager.fan_speed[0]; + } + #endif } /* Temperature page temperature update */ if (checkkey == TemperatureID) { - if (last_temp_hotend_target != thermalManager.temp_hotend[0].target) - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(1), thermalManager.temp_hotend[0].target); - if (last_temp_bed_target != thermalManager.temp_bed.target) - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(2), thermalManager.temp_bed.target); - if (last_fan_speed != thermalManager.fan_speed[0]) { - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(3), thermalManager.fan_speed[0]); - last_fan_speed = thermalManager.fan_speed[0]; - } + #if HAS_HOTEND + if (last_temp_hotend_target != thermalManager.temp_hotend[0].target) + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(TEMP_CASE_TEMP), thermalManager.temp_hotend[0].target); + #endif + #if HAS_HEATED_BED + if (last_temp_bed_target != thermalManager.temp_bed.target) + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(TEMP_CASE_BED), thermalManager.temp_bed.target); + #endif + #if HAS_FAN + if (last_fan_speed != thermalManager.fan_speed[0]) { + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(TEMP_CASE_FAN), thermalManager.fan_speed[0]); + last_fan_speed = thermalManager.fan_speed[0]; + } + #endif } /* Bottom temperature update */ - if (last_temp_hotend_current != thermalManager.temp_hotend[0].celsius) { - DWIN_Draw_IntValue(true, true, 0, STAT_FONT, White, Background_black, 3, 33, 382, thermalManager.temp_hotend[0].celsius); - last_temp_hotend_current = thermalManager.temp_hotend[0].celsius; - } - if (last_temp_hotend_target != thermalManager.temp_hotend[0].target) { - DWIN_Draw_IntValue(true, true, 0, STAT_FONT, White, Background_black, 3, 33 + 4 * STAT_CHR_W + 6, 382, thermalManager.temp_hotend[0].target); - last_temp_hotend_target = thermalManager.temp_hotend[0].target; - } - if (last_temp_bed_current != thermalManager.temp_bed.celsius) { - DWIN_Draw_IntValue(true, true, 0, STAT_FONT, White, Background_black, 3, 178, 382, thermalManager.temp_bed.celsius); - last_temp_bed_current = thermalManager.temp_bed.celsius; - } - if (last_temp_bed_target != thermalManager.temp_bed.target) { - DWIN_Draw_IntValue(true, true, 0, STAT_FONT, White, Background_black, 3, 178 + 4 * STAT_CHR_W + 6, 382, thermalManager.temp_bed.target); - last_temp_bed_target = thermalManager.temp_bed.target; - } + #if HAS_HOTEND + if (last_temp_hotend_current != thermalManager.temp_hotend[0].celsius) { + DWIN_Draw_IntValue(true, true, 0, STAT_FONT, White, Background_black, 3, 33, 382, thermalManager.temp_hotend[0].celsius); + last_temp_hotend_current = thermalManager.temp_hotend[0].celsius; + } + if (last_temp_hotend_target != thermalManager.temp_hotend[0].target) { + DWIN_Draw_IntValue(true, true, 0, STAT_FONT, White, Background_black, 3, 33 + 4 * STAT_CHR_W + 6, 382, thermalManager.temp_hotend[0].target); + last_temp_hotend_target = thermalManager.temp_hotend[0].target; + } + #endif + #if HAS_HEATED_BED + if (last_temp_bed_current != thermalManager.temp_bed.celsius) { + DWIN_Draw_IntValue(true, true, 0, STAT_FONT, White, Background_black, 3, 178, 382, thermalManager.temp_bed.celsius); + last_temp_bed_current = thermalManager.temp_bed.celsius; + } + if (last_temp_bed_target != thermalManager.temp_bed.target) { + DWIN_Draw_IntValue(true, true, 0, STAT_FONT, White, Background_black, 3, 178 + 4 * STAT_CHR_W + 6, 382, thermalManager.temp_bed.target); + last_temp_bed_target = thermalManager.temp_bed.target; + } + #endif + static uint16_t last_speed = 0; if (last_speed != feedrate_percentage) { DWIN_Draw_IntValue(true, true, 0, STAT_FONT, White, Background_black, 3, 33 + 2 * STAT_CHR_W, 429, feedrate_percentage); last_speed = feedrate_percentage; } - if (last_zoffset != BABY_Z_VAR) { - DWIN_Draw_Signed_Float(STAT_FONT, Background_black, 2, 2, 178 + STAT_CHR_W, 429, BABY_Z_VAR * 100); - last_zoffset = BABY_Z_VAR; - } + #if HAS_ZOFFSET_ITEM + if (last_zoffset != BABY_Z_VAR) { + DWIN_Draw_Signed_Float(STAT_FONT, Background_black, 2, 2, 178 + STAT_CHR_W, 429, BABY_Z_VAR * 100); + last_zoffset = BABY_Z_VAR; + } + #endif } /** @@ -1553,38 +1721,37 @@ inline void make_name_without_ext(char *dst, char *src, size_t maxlen=MENU_CHAR_ while (pos--) dst[pos] = src[pos]; } -inline void HMI_SDCardInit(void) { card.cdroot(); } +inline void HMI_SDCardInit() { card.cdroot(); } -void MarlinUI::refresh() { - // The card was mounted or unmounted - // or some other status change occurred - // DWIN_lcd_sd_status = false; // On next DWIN_Update - // HMI_SDCardUpdate(); -} +void MarlinUI::refresh() { /* Nothing to see here */ } #define ICON_Folder ICON_More -char shift_name[LONG_FILENAME_LENGTH + 1]; -int8_t shift_amt; // = 0 -millis_t shift_ms; // = 0 +#if ENABLED(SCROLL_LONG_FILENAMES) -// Init the shift name based on the highlighted item -inline 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); + 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 + inline 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); + } } -} -inline void Init_SDItem_Shift() { - shift_amt = 0; - shift_ms = select_file.now > 0 && strlen(shift_name) > MENU_CHAR_LIMIT - ? millis() + 750UL : 0; -} + inline 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. @@ -1600,37 +1767,42 @@ inline void Draw_SDItem(const uint16_t item, int16_t row=-1) { card.getfilename_sorted(item - is_subdir); char * const name = card.longest_filename(); - // 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(); - } + #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); } -inline void Draw_SDItem_Shifted(int8_t &shift) { - // Limit to the number of chars past the cutoff - const size_t len = strlen(shift_name); - NOMORE(shift, _MAX((signed)len - MENU_CHAR_LIMIT, 0)); +#if ENABLED(SCROLL_LONG_FILENAMES) - // Shorten to the available space - const size_t lastchar = _MIN((signed)len, shift + MENU_CHAR_LIMIT); + inline void Draw_SDItem_Shifted(int8_t &shift) { + // Limit to the number of chars past the cutoff + const size_t len = strlen(shift_name); + NOMORE(shift, _MAX((signed)len - MENU_CHAR_LIMIT, 0)); - const char c = shift_name[lastchar]; - shift_name[lastchar] = '\0'; + // Shorten to the available space + const size_t lastchar = _MIN((signed)len, shift + MENU_CHAR_LIMIT); - 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]); + const char c = shift_name[lastchar]; + shift_name[lastchar] = '\0'; - shift_name[lastchar] = c; -} + 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 inline void Redraw_SD_List() { @@ -1645,10 +1817,12 @@ inline void Redraw_SD_List() { LOOP_L_N(i, _MIN(nr_sd_menu_items(), MROWS)) Draw_SDItem(i, i + 1); - Init_SDItem_Shift(); + TERN_(SCROLL_LONG_FILENAMES, Init_SDItem_Shift()); } -inline void SDCard_Up(void) { +bool DWIN_lcd_sd_status = false; + +inline void SDCard_Up() { card.cdup(); Redraw_SD_List(); DWIN_lcd_sd_status = false; // On next DWIN_Update @@ -1663,7 +1837,7 @@ inline void SDCard_Folder(char * const dirname) { // // Watch for media mount / unmount // -void HMI_SDCardUpdate(void) { +void HMI_SDCardUpdate() { if (HMI_flag.home_flag) return; if (DWIN_lcd_sd_status != card.isMounted()) { DWIN_lcd_sd_status = card.isMounted(); @@ -1681,40 +1855,50 @@ void HMI_SDCardUpdate(void) { // TODO: Move card removed abort handling // to CardReader::manage_media. card.flag.abort_sd_printing = true; - wait_for_heatup = false; - abort_flag = true; + wait_for_heatup = false; + dwin_abort_flag = true; } } DWIN_UpdateLCD(); } } -/* Start */ +/* Start Frame */ + void HMI_StartFrame(const bool with_update) { Goto_MainMenu(); - DWIN_Draw_Rectangle(1, Background_black, 0, 360, DWIN_WIDTH, DWIN_HEIGHT - 1); + // Clear the bottom area of the screen + DWIN_Draw_Rectangle(1, Background_black, 0, STATUS_Y, DWIN_WIDTH, DWIN_HEIGHT - 1); - DWIN_ICON_Show(ICON, ICON_HotendTemp, 13, 381); + // + // Status Area + // + #if HAS_HOTEND + DWIN_ICON_Show(ICON, ICON_HotendTemp, 13, 381); + DWIN_Draw_IntValue(true, true, 0, STAT_FONT, White, Background_black, 3, 33, 382, thermalManager.temp_hotend[0].celsius); + DWIN_Draw_String(false, false, STAT_FONT, White, Background_black, 33 + 3 * STAT_CHR_W + 5, 383, F("/")); + DWIN_Draw_IntValue(true, true, 0, STAT_FONT, White, Background_black, 3, 33 + 4 * STAT_CHR_W + 6, 382, thermalManager.temp_hotend[0].target); + #endif #if HOTENDS > 1 // DWIN_ICON_Show(ICON,ICON_HotendTemp, 13, 381); #endif - DWIN_ICON_Show(ICON, ICON_BedTemp, 158, 381); - DWIN_ICON_Show(ICON, ICON_Speed, 13, 429); - DWIN_ICON_Show(ICON, ICON_Zoffset, 158, 428); - // Draw initial Status Area - DWIN_Draw_IntValue(true, true, 0, STAT_FONT, White, Background_black, 3, 33, 382, thermalManager.temp_hotend[0].celsius); - DWIN_Draw_IntValue(true, true, 0, STAT_FONT, White, Background_black, 3, 33 + 4 * STAT_CHR_W + 6, 382, thermalManager.temp_hotend[0].target); - DWIN_Draw_IntValue(true, true, 0, STAT_FONT, White, Background_black, 3, 178, 382, thermalManager.temp_bed.celsius); - DWIN_Draw_IntValue(true, true, 0, STAT_FONT, White, Background_black, 3, 178 + 4 * STAT_CHR_W + 6, 382, thermalManager.temp_bed.target); + #if HAS_HEATED_BED + DWIN_ICON_Show(ICON, ICON_BedTemp, 158, 381); + DWIN_Draw_IntValue(true, true, 0, STAT_FONT, White, Background_black, 3, 178, 382, thermalManager.temp_bed.celsius); + DWIN_Draw_String(false, false, STAT_FONT, White, Background_black, 178 + 3 * STAT_CHR_W + 5, 383, F("/")); + DWIN_Draw_IntValue(true, true, 0, STAT_FONT, White, Background_black, 3, 178 + 4 * STAT_CHR_W + 6, 382, thermalManager.temp_bed.target); + #endif + DWIN_ICON_Show(ICON, ICON_Speed, 13, 429); DWIN_Draw_IntValue(true, true, 0, STAT_FONT, White, Background_black, 3, 33 + 2 * STAT_CHR_W, 429, feedrate_percentage); DWIN_Draw_String(false, false, STAT_FONT, White, Background_black, 33 + 5 * STAT_CHR_W + 2, 429, F("%")); - DWIN_Draw_Signed_Float(STAT_FONT, Background_black, 2, 2, 178, 429, BABY_Z_VAR * 100); - DWIN_Draw_String(false, false, STAT_FONT, White, Background_black, 33 + 3 * STAT_CHR_W + 5, 383, F("/")); - DWIN_Draw_String(false, false, STAT_FONT, White, Background_black, 178 + 3 * STAT_CHR_W + 5, 383, F("/")); + #if HAS_ZOFFSET_ITEM + DWIN_ICON_Show(ICON, ICON_Zoffset, 158, 428); + DWIN_Draw_Signed_Float(STAT_FONT, Background_black, 2, 2, 178, 429, BABY_Z_VAR * 100); + #endif if (with_update) { DWIN_UpdateLCD(); @@ -1774,12 +1958,12 @@ inline void Draw_Print_File_Menu() { } /* Main Process */ -void HMI_MainMenu(void) { +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(3)) { + if (select_page.inc(4)) { switch (select_page.now) { case 0: ICON_Print(); break; case 1: ICON_Print(); ICON_Prepare(); break; @@ -1834,27 +2018,29 @@ void HMI_MainMenu(void) { } // Select (and Print) File -void HMI_SelectFile(void) { +void HMI_SelectFile() { ENCODER_DiffState encoder_diffState = get_encoder_state(); const uint16_t hasUpDir = !card.flag.workDirIsRoot; if (encoder_diffState == ENCODER_DIFF_NO) { - 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 - int8_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 + #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 + int8_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; } @@ -1864,10 +2050,10 @@ void HMI_SelectFile(void) { const uint16_t fullCnt = nr_sd_menu_items(); if (encoder_diffState == ENCODER_DIFF_CW && fullCnt) { - if (select_file.inc(fullCnt)) { + if (select_file.inc(1 + fullCnt)) { const uint8_t itemnum = select_file.now - 1; // -1 for "Back" - if (shift_ms) { // If line was shifted - Erase_Menu_Text(select_file.now - 1 + MROWS - index_file); // Erase and + 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 @@ -1877,15 +2063,15 @@ void HMI_SelectFile(void) { } else { Move_Highlight(1, select_file.now + MROWS - index_file); // Just move highlight - Init_Shift_Name(); // ...and init the shift name + TERN_(SCROLL_LONG_FILENAMES, Init_Shift_Name()); // ...and init the shift name } - Init_SDItem_Shift(); + 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 (shift_ms) { // If line was shifted + 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 } @@ -1894,7 +2080,7 @@ void HMI_SelectFile(void) { Scroll_Menu(DWIN_SCROLL_DOWN); if (index_file == MROWS) { Draw_Back_First(); - shift_ms = 0; + TERN_(SCROLL_LONG_FILENAMES, shift_ms = 0); } else { Draw_SDItem(itemnum, 0); // Draw the item (and init shift name) @@ -1902,19 +2088,17 @@ void HMI_SelectFile(void) { } else { Move_Highlight(-1, select_file.now + MROWS - index_file); // Just move highlight - Init_Shift_Name(); // ...and init the shift name + TERN_(SCROLL_LONG_FILENAMES, Init_Shift_Name()); // ...and init the shift name } - Init_SDItem_Shift(); // Reset left. Init timer. + TERN_(SCROLL_LONG_FILENAMES, Init_SDItem_Shift()); // Reset left. Init timer. } } else if (encoder_diffState == ENCODER_DIFF_ENTER) { - if (select_file.now == 0) { - /* back */ + if (select_file.now == 0) { // Back select_page.set(0); Goto_MainMenu(); } - else if (hasUpDir && select_file.now == 1) { - /* CDUP */ + else if (hasUpDir && select_file.now == 1) { // CD-Up SDCard_Up(); goto HMI_SelectFileExit; } @@ -1933,8 +2117,8 @@ void HMI_SelectFile(void) { select_file.reset(); // Start choice and print SD file - HMI_flag.heat_flag = 1; - HMI_flag.print_finish = 0; + HMI_flag.heat_flag = true; + HMI_flag.print_finish = false; HMI_ValueStruct.show_mode = 0; card.openAndPrintFile(card.filename); @@ -1954,21 +2138,21 @@ void HMI_SelectFile(void) { } /* Printing */ -void HMI_Printing(void) { +void HMI_Printing() { ENCODER_DiffState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; - if (HMI_flag.confirm_flag) { + if (HMI_flag.done_confirm_flag) { if (encoder_diffState == ENCODER_DIFF_ENTER) { - HMI_flag.confirm_flag = 0; - abort_flag = 1; + HMI_flag.done_confirm_flag = false; + dwin_abort_flag = true; } return; } // Avoid flicker by updating only the previous menu if (encoder_diffState == ENCODER_DIFF_CW) { - if (select_print.inc(2)) { + if (select_print.inc(3)) { switch (select_print.now) { case 0: ICON_Tune(); break; case 1: @@ -1999,15 +2183,14 @@ void HMI_Printing(void) { } else if (encoder_diffState == ENCODER_DIFF_ENTER) { switch (select_print.now) { - case 0: // Setting + case 0: // Tune checkkey = Tune; HMI_ValueStruct.show_mode = 0; select_tune.reset(); - index_tune = 5; + index_tune = MROWS; Draw_Tune_Menu(); break; case 1: // Pause - /* pause */ if (HMI_flag.pause_flag) { ICON_Pause(); @@ -2015,23 +2198,26 @@ void HMI_Printing(void) { cmd[0] = '\0'; #if ENABLED(PAUSE_HEAT) - if (tempbed) sprintf_P(cmd, PSTR("M190 S%i\n"), tempbed); - if (temphot) sprintf_P(&cmd[strlen(cmd)], PSTR("M109 S%i\n"), temphot); + #if HAS_HEATED_BED + if (tempbed) sprintf_P(cmd, PSTR("M190 S%i\n"), tempbed); + #endif + #if HAS_HOTEND + if (temphot) sprintf_P(&cmd[strlen(cmd)], PSTR("M109 S%i\n"), temphot); + #endif #endif strcat_P(cmd, PSTR("M24")); queue.inject(cmd); } else { - HMI_flag.select_flag = 1; + HMI_flag.select_flag = true; checkkey = Print_window; Popup_window_PauseOrStop(); } break; case 2: // Stop - /* stop */ - HMI_flag.select_flag = 1; + HMI_flag.select_flag = true; checkkey = Print_window; Popup_window_PauseOrStop(); break; @@ -2043,7 +2229,7 @@ void HMI_Printing(void) { } /* Pause and Stop window */ -void HMI_PauseOrStop(void) { +void HMI_PauseOrStop() { ENCODER_DiffState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; @@ -2056,7 +2242,7 @@ void HMI_PauseOrStop(void) { else if (encoder_diffState == ENCODER_DIFF_ENTER) { if (select_print.now == 1) { // pause window if (HMI_flag.select_flag) { - pause_action_flag = 1; + HMI_flag.pause_action = true; ICON_Continue(); #if ENABLED(POWER_LOSS_RECOVERY) if (recovery.enabled) recovery.save(true); @@ -2084,10 +2270,10 @@ void HMI_PauseOrStop(void) { host_action_cancel(); #endif #ifdef EVENT_GCODE_SD_ABORT - Popup_Window_Home(); + Popup_Window_Home(true); queue.inject_P(PSTR(EVENT_GCODE_SD_ABORT)); #endif - abort_flag = true; + dwin_abort_flag = true; #endif } else { @@ -2114,20 +2300,20 @@ inline void Draw_Move_Menu() { #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(1, 231, 2, 265, 12); // "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" + DWIN_Frame_AreaCopy(1, 123, 192, 176, 202, LBLX, MBASE(4)); // "Extruder" #endif } Draw_Back_First(select_axis.now == 0); if (select_axis.now) Draw_Menu_Cursor(select_axis.now); - // Draw separators so it looks like a menu + // Draw separators and icons LOOP_L_N(i, 3 + ENABLED(HAS_HOTEND)) Draw_Menu_Line(i + 1, ICON_MoveX + i); } @@ -2144,13 +2330,13 @@ void HMI_AudioFeedback(const bool success=true) { } /* Prepare */ -void HMI_Prepare(void) { +void HMI_Prepare() { 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_prepare.inc(8)) { + if (select_prepare.inc(1 + PREPARE_CASE_TOTAL)) { if (select_prepare.now > MROWS && select_prepare.now > index_prepare) { index_prepare = select_prepare.now; @@ -2161,9 +2347,13 @@ void HMI_Prepare(void) { // Draw "More" icon for sub-menus if (index_prepare < 7) Draw_More_Icon(MROWS - index_prepare + 1); - if (index_prepare == 6) Prepare_Item_ABS(MROWS); - else if (index_prepare == 7) Prepare_Item_Cool(MROWS); - else if (index_prepare == 8) Prepare_Item_Lang(MROWS); + #if HAS_HOTEND + if (index_prepare == PREPARE_CASE_ABS) Item_Prepare_ABS(MROWS); + #endif + #if HAS_PREHEAT + if (index_prepare == PREPARE_CASE_COOL) Item_Prepare_Cool(MROWS); + #endif + if (index_prepare == PREPARE_CASE_LANG) Item_Prepare_Lang(MROWS); } else { Move_Highlight(1, select_prepare.now + MROWS - index_prepare); @@ -2183,9 +2373,9 @@ void HMI_Prepare(void) { if (index_prepare < 7) Draw_More_Icon(MROWS - index_prepare + 1); - if (index_prepare == 6) Prepare_Item_Move(0); - else if (index_prepare == 7) Prepare_Item_Disable(0); - else if (index_prepare == 8) Prepare_Item_Home(0); + if (index_prepare == 6) Item_Prepare_Move(0); + else if (index_prepare == 7) Item_Prepare_Disable(0); + else if (index_prepare == 8) Item_Prepare_Home(0); } else { Move_Highlight(-1, select_prepare.now + MROWS - index_prepare); @@ -2198,67 +2388,66 @@ void HMI_Prepare(void) { select_page.set(1); Goto_MainMenu(); break; - case 1: // axis move + case PREPARE_CASE_MOVE: // Axis move checkkey = AxisMove; select_axis.reset(); Draw_Move_Menu(); - queue.inject_P(PSTR("G92 E0")); - current_position.e = HMI_ValueStruct.Move_E_scale = 0; DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 216, MBASE(1), current_position.x * MINUNITMULT); DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 216, MBASE(2), current_position.y * MINUNITMULT); DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 216, MBASE(3), current_position.z * MINUNITMULT); #if HAS_HOTEND - DWIN_Draw_Signed_Float(font8x16, Background_black, 3, 1, 216, MBASE(4), current_position.e * MINUNITMULT); + queue.inject_P(PSTR("G92 E0")); + current_position.e = HMI_ValueStruct.Move_E_scale = 0; + DWIN_Draw_Signed_Float(font8x16, Background_black, 3, 1, 216, MBASE(4), 0); #endif break; - case 2: // close motion + case PREPARE_CASE_DISA: // Disable steppers queue.inject_P(PSTR("M84")); break; - case 3: // homing + case PREPARE_CASE_HOME: // Homing checkkey = Last_Prepare; index_prepare = MROWS; queue.inject_P(PSTR("G28")); // G28 will set home_flag Popup_Window_Home(); break; - case 4: // Z-offset - #if HAS_BED_PROBE - checkkey = Homeoffset; - HMI_ValueStruct.show_mode = -4; - HMI_ValueStruct.offset_value = probe.offset.z * 100; - DWIN_Draw_Signed_Float(font8x16, Select_Color, 2, 2, 202, MBASE(4 + MROWS - index_prepare), HMI_ValueStruct.offset_value); - EncoderRate.encoderRateEnabled = 1; - #else - // Apply workspace offset, making the current position 0,0,0 - queue.inject_P(PSTR("G92 X0 Y0 Z0")); - HMI_AudioFeedback(); - #endif - break; - case 5: // PLA preheat - thermalManager.setTargetHotend(ui.material_preset[0].hotend_temp, 0); - thermalManager.setTargetBed(ui.material_preset[0].bed_temp); - thermalManager.set_fan_speed(0, ui.material_preset[0].fan_speed); - break; - case 6: // ABS preheat - thermalManager.setTargetHotend(ui.material_preset[1].hotend_temp, 0); - thermalManager.setTargetBed(ui.material_preset[1].bed_temp); - thermalManager.set_fan_speed(0, ui.material_preset[1].fan_speed); - break; - case 7: // cool - thermalManager.zero_fan_speeds(); - thermalManager.disable_all_heaters(); - break; - case 8: // language - /* select language */ - HMI_flag.language_chinese ^= true; - if (HMI_flag.language_chinese) { - HMI_SetAndSaveLanguageChinese(); - DWIN_JPG_CacheTo1(Language_Chinese); - } - else { - HMI_SetAndSaveLanguageWestern(); - DWIN_JPG_CacheTo1(Language_English); - } + #if HAS_ZOFFSET_ITEM + case PREPARE_CASE_ZOFF: // Z-offset + #if EITHER(HAS_BED_PROBE, BABYSTEPPING) + 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); + EncoderRate.enabled = true; + #else + // Apply workspace offset, making the current position 0,0,0 + queue.inject_P(PSTR("G92 X0 Y0 Z0")); + HMI_AudioFeedback(); + #endif + break; + #endif + #if HAS_HOTEND + case PREPARE_CASE_PLA: // PLA preheat + thermalManager.setTargetHotend(ui.material_preset[0].hotend_temp, 0); + thermalManager.setTargetBed(ui.material_preset[0].bed_temp); + thermalManager.set_fan_speed(0, ui.material_preset[0].fan_speed); + break; + case PREPARE_CASE_ABS: // ABS preheat + thermalManager.setTargetHotend(ui.material_preset[1].hotend_temp, 0); + thermalManager.setTargetBed(ui.material_preset[1].bed_temp); + thermalManager.set_fan_speed(0, ui.material_preset[1].fan_speed); + break; + #endif + #if HAS_PREHEAT + case PREPARE_CASE_COOL: // 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 + HMI_ToggleLanguage(); Draw_Prepare_Menu(); break; default: break; @@ -2271,72 +2460,108 @@ void Draw_Temperature_Menu() { Clear_Main_Window(); if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 236, 2, 263, 13, 14, 8); - - DWIN_Frame_AreaCopy(1, 1, 134, 56, 146, LBLX, MBASE(1)); - DWIN_Frame_AreaCopy(1, 58, 134, 113, 146, LBLX, MBASE(2)); - DWIN_Frame_AreaCopy(1, 115, 134, 170, 146, LBLX, MBASE(3)); - DWIN_Frame_AreaCopy(1, 100, 89, 178, 101, LBLX, MBASE(4)); - DWIN_Frame_AreaCopy(1, 180, 89, 260, 100, LBLX, MBASE(5)); + DWIN_Frame_TitleCopy(1, 236, 2, 263, 13); // "Temperature" + #if HAS_HOTEND + DWIN_Frame_AreaCopy(1, 1, 134, 56, 146, LBLX, MBASE(TEMP_CASE_TEMP)); + #endif + #if HAS_HEATED_BED + DWIN_Frame_AreaCopy(1, 58, 134, 113, 146, LBLX, MBASE(TEMP_CASE_BED)); + #endif + #if HAS_FAN + DWIN_Frame_AreaCopy(1, 115, 134, 170, 146, LBLX, MBASE(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)); + #endif } else { #ifdef USE_STRING_HEADINGS Draw_Title(GET_TEXT_F(MSG_TEMPERATURE)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(1), GET_TEXT_F(MSG_UBL_SET_TEMP_HOTEND)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(2), GET_TEXT_F(MSG_UBL_SET_TEMP_BED)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(3), GET_TEXT_F(MSG_FAN_SPEED)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(4), F("PLA Preheat Settings")); - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(5), F("ABS Preheat Settings")); + #if HAS_HOTEND + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(TEMP_CASE_TEMP), GET_TEXT_F(MSG_UBL_SET_TEMP_HOTEND)); + #endif + #if HAS_HEATED_BED + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(TEMP_CASE_BED), GET_TEXT_F(MSG_UBL_SET_TEMP_BED)); + #endif + #if HAS_FAN + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(TEMP_CASE_FAN), GET_TEXT_F(MSG_FAN_SPEED)); + #endif + #if HAS_HOTEND + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(TEMP_CASE_PLA), F("PLA Preheat Settings")); + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(TEMP_CASE_ABS), F("ABS Preheat Settings")); + #endif #else - DWIN_Frame_AreaCopy(1, 56, 16, 141, 28, 14, 8); - DWIN_Frame_AreaCopy(1, 197, 104, 238, 114, LBLX, MBASE(1)); // Nozzle... - DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX + 44, MBASE(1)); // ...Temperature - DWIN_Frame_AreaCopy(1, 240, 104, 264, 114, LBLX, MBASE(2)); // Bed... - DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX + 27, MBASE(2)); // ...Temperature - DWIN_Frame_AreaCopy(1, 0, 119, 64, 132, LBLX, MBASE(3)); // Fan speed - DWIN_Frame_AreaCopy(1, 107, 76, 156, 86, LBLX, MBASE(4)); // Preheat... - DWIN_Frame_AreaCopy(1, 157, 76, 181, 86, LBLX + 52, MBASE(4)); // ...PLA - DWIN_Frame_AreaCopy(1, 131, 119, 182, 132, LBLX + 79, MBASE(4)); // PLA setting - DWIN_Frame_AreaCopy(1, 107, 76, 156, 86, LBLX, MBASE(5)); // Preheat... - DWIN_Frame_AreaCopy(1, 172, 76, 198, 86, LBLX + 52, MBASE(5)); // ...ABS - DWIN_Frame_AreaCopy(1, 131, 119, 182, 132, LBLX + 81, MBASE(5)); // ABS setting + DWIN_Frame_TitleCopy(1, 56, 16, 141, 28); // "Temperature" + #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 + #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 + #endif + #if HAS_FAN + DWIN_Frame_AreaCopy(1, 0, 119, 64, 132, LBLX, MBASE(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 + #endif #endif } Draw_Back_First(select_temp.now == 0); if (select_temp.now) Draw_Menu_Cursor(select_temp.now); - LOOP_L_N(i, 5) Draw_Menu_Line(i + 1, ICON_SetEndTemp + i); - - Draw_More_Icon(4); - Draw_More_Icon(5); - - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(1), thermalManager.temp_hotend[0].target); - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(2), thermalManager.temp_bed.target); - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(3), thermalManager.fan_speed[0]); + // Draw icons and lines + uint8_t i = 0; + #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, White, Background_black, 3, 216, MBASE(i), thermalManager.temp_hotend[0].target); + #endif + #if HAS_HEATED_BED + _TMENU_ICON(TEMP_CASE_BED); + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(i), thermalManager.temp_bed.target); + #endif + #if HAS_FAN + _TMENU_ICON(TEMP_CASE_FAN); + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(i), thermalManager.fan_speed[0]); + #endif + #if HAS_HOTEND + // PLA/ABS items have submenus + _TMENU_ICON(TEMP_CASE_PLA); + Draw_More_Icon(i); + _TMENU_ICON(TEMP_CASE_ABS); + Draw_More_Icon(i); + #endif } /* Control */ -void HMI_Control(void) { +void HMI_Control() { 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) { - #define CONTROL_ITEMS (5 + ENABLED(HAS_ONESTEP_LEVELING)) - if (select_control.inc(CONTROL_ITEMS)) { + if (select_control.inc(1 + CONTROL_CASE_TOTAL)) { if (select_control.now > MROWS && select_control.now > index_control) { index_control = select_control.now; Scroll_Menu(DWIN_SCROLL_UP); - Draw_Menu_Icon(MROWS, ICON_Temperature + select_control.now - 1); - Draw_More_Icon(1 + MROWS - index_control); // Temperature > - Draw_More_Icon(2 + MROWS - index_control); // Motion > + Draw_Menu_Icon(MROWS, ICON_Temperature + index_control - 1); + Draw_More_Icon(CONTROL_CASE_TEMP + MROWS - index_control); // Temperature > + Draw_More_Icon(CONTROL_CASE_MOVE + MROWS - index_control); // Motion > if (index_control > MROWS) { - Draw_More_Icon(6 + MROWS - index_control); // Info > + Draw_More_Icon(CONTROL_CASE_INFO + MROWS - index_control); // Info > if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 231, 104, 258, 116, LBLX, MBASE(5)); + DWIN_Frame_AreaCopy(1, 231, 104, 258, 116, LBLX, MBASE(CONTROL_CASE_INFO - 1)); else - DWIN_Frame_AreaCopy(1, 0, 104, 24, 114, LBLX, MBASE(5)); + DWIN_Frame_AreaCopy(1, 0, 104, 24, 114, LBLX, MBASE(CONTROL_CASE_INFO - 1)); } } else { @@ -2367,33 +2592,32 @@ void HMI_Control(void) { select_page.set(2); Goto_MainMenu(); break; - case 1: // temperature + case CONTROL_CASE_TEMP: // Temperature checkkey = TemperatureID; HMI_ValueStruct.show_mode = -1; select_temp.reset(); Draw_Temperature_Menu(); break; - case 2: // motion + case CONTROL_CASE_MOVE: // Motion checkkey = Motion; select_motion.reset(); Draw_Motion_Menu(); break; - case 3: #if ENABLED(EEPROM_SETTINGS) - { // write EEPROM + case CONTROL_CASE_SAVE: { // Write EEPROM const bool success = settings.save(); HMI_AudioFeedback(success); } break; - case 4: { // read EEPROM + case CONTROL_CASE_LOAD: { // Read EEPROM const bool success = settings.load(); HMI_AudioFeedback(success); } break; - case 5: // resume EEPROM + case CONTROL_CASE_RESET: // Reset EEPROM settings.reset(); HMI_AudioFeedback(); break; - case 6: // info #endif + case CONTROL_CASE_INFO: // Info checkkey = Info; Draw_Info_Menu(); break; @@ -2407,7 +2631,7 @@ void HMI_Control(void) { #if HAS_ONESTEP_LEVELING /* Leveling */ - void HMI_Leveling(void) { + void HMI_Leveling() { Popup_Window_Leveling(); DWIN_UpdateLCD(); queue.inject_P(PSTR("G28O\nG29")); @@ -2416,21 +2640,21 @@ void HMI_Control(void) { #endif /* Axis Move */ -void HMI_AxisMove(void) { +void HMI_AxisMove() { ENCODER_DiffState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; - #if HAS_HOTEND + #if ENABLED(PREVENT_COLD_EXTRUSION) // popup window resume if (HMI_flag.ETempTooLow_flag) { if (encoder_diffState == ENCODER_DIFF_ENTER) { - HMI_flag.ETempTooLow_flag = 0; - Draw_Move_Menu(); + HMI_flag.ETempTooLow_flag = false; current_position.e = HMI_ValueStruct.Move_E_scale = 0; + Draw_Move_Menu(); DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 216, MBASE(1), HMI_ValueStruct.Move_X_scale); DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 216, MBASE(2), HMI_ValueStruct.Move_Y_scale); DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 216, MBASE(3), HMI_ValueStruct.Move_Z_scale); - DWIN_Draw_Signed_Float(font8x16, Background_black, 3, 1, 216, MBASE(4), HMI_ValueStruct.Move_E_scale); + DWIN_Draw_Signed_Float(font8x16, Background_black, 3, 1, 216, MBASE(4), 0); DWIN_UpdateLCD(); } return; @@ -2439,7 +2663,7 @@ void HMI_AxisMove(void) { // Avoid flicker by updating only the previous menu if (encoder_diffState == ENCODER_DIFF_CW) { - if (select_axis.inc(4)) Move_Highlight(1, select_axis.now); + if (select_axis.inc(1 + 3 + ENABLED(HAS_HOTEND))) Move_Highlight(1, select_axis.now); } else if (encoder_diffState == ENCODER_DIFF_CCW) { if (select_axis.dec()) Move_Highlight(-1, select_axis.now); @@ -2456,26 +2680,26 @@ void HMI_AxisMove(void) { checkkey = Move_X; HMI_ValueStruct.Move_X_scale = current_position.x * MINUNITMULT; DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 216, MBASE(1), HMI_ValueStruct.Move_X_scale); - EncoderRate.encoderRateEnabled = 1; + EncoderRate.enabled = true; break; case 2: // Y axis move checkkey = Move_Y; HMI_ValueStruct.Move_Y_scale = current_position.y * MINUNITMULT; DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 216, MBASE(2), HMI_ValueStruct.Move_Y_scale); - EncoderRate.encoderRateEnabled = 1; + EncoderRate.enabled = true; break; case 3: // Z axis move checkkey = Move_Z; HMI_ValueStruct.Move_Z_scale = current_position.z * MINUNITMULT; DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 216, MBASE(3), HMI_ValueStruct.Move_Z_scale); - EncoderRate.encoderRateEnabled = 1; + EncoderRate.enabled = true; break; #if HAS_HOTEND case 4: // Extruder // window tips #ifdef PREVENT_COLD_EXTRUSION if (thermalManager.temp_hotend[0].celsius < EXTRUDE_MINTEMP) { - HMI_flag.ETempTooLow_flag = 1; + HMI_flag.ETempTooLow_flag = true; Popup_Window_ETempTooLow(); DWIN_UpdateLCD(); return; @@ -2484,7 +2708,7 @@ void HMI_AxisMove(void) { checkkey = Extruder; HMI_ValueStruct.Move_E_scale = current_position.e * MINUNITMULT; DWIN_Draw_Signed_Float(font8x16, Select_Color, 3, 1, 216, MBASE(4), HMI_ValueStruct.Move_E_scale); - EncoderRate.encoderRateEnabled = 1; + EncoderRate.enabled = true; break; #endif } @@ -2493,13 +2717,13 @@ void HMI_AxisMove(void) { } /* TemperatureID */ -void HMI_Temperature(void) { +void HMI_Temperature() { 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_temp.inc(5)) Move_Highlight(1, select_temp.now); + if (select_temp.inc(1 + TEMP_CASE_TOTAL)) Move_Highlight(1, select_temp.now); } else if (encoder_diffState == ENCODER_DIFF_CCW) { if (select_temp.dec()) Move_Highlight(-1, select_temp.now); @@ -2512,141 +2736,184 @@ void HMI_Temperature(void) { index_control = MROWS; Draw_Control_Menu(); break; - #if HAS_HOTEND - case 1: // nozzle temperature - checkkey = ETemp; - HMI_ValueStruct.E_Temp = thermalManager.temp_hotend[0].target; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(1), thermalManager.temp_hotend[0].target); - EncoderRate.encoderRateEnabled = 1; - break; - #endif - #if HAS_HEATED_BED - case 2: // bed temperature - checkkey = BedTemp; - HMI_ValueStruct.Bed_Temp = thermalManager.temp_bed.target; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(2), thermalManager.temp_bed.target); - EncoderRate.encoderRateEnabled = 1; - break; - #endif - #if HAS_FAN - case 3: // fan speed - checkkey = FanSpeed; - HMI_ValueStruct.Fan_speed = thermalManager.fan_speed[0]; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(3), thermalManager.fan_speed[0]); - EncoderRate.encoderRateEnabled = 1; - break; - #endif - #if HAS_HOTEND - case 4: // PLA preheat setting - checkkey = PLAPreheat; - select_PLA.reset(); - HMI_ValueStruct.show_mode = -2; - - Clear_Main_Window(); - - if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 59, 16, 139, 29, 14, 8); - - DWIN_Frame_AreaCopy(1, 100, 89, 124, 101, LBLX, MBASE(1)); - DWIN_Frame_AreaCopy(1, 1, 134, 56, 146, LBLX + 24, MBASE(1)); // PLA nozzle temp - DWIN_Frame_AreaCopy(1, 100, 89, 124, 101, LBLX, MBASE(2)); - DWIN_Frame_AreaCopy(1, 58, 134, 113, 146, LBLX + 24, MBASE(2)); // PLA bed temp - DWIN_Frame_AreaCopy(1, 100, 89, 124, 101, LBLX, MBASE(3)); - DWIN_Frame_AreaCopy(1, 115, 134, 170, 146, LBLX + 24, MBASE(3)); // PLA fan speed - DWIN_Frame_AreaCopy(1, 72, 148, 151, 162, LBLX, MBASE(4)); // save PLA configuration - } - else { - #ifdef USE_STRING_HEADINGS - Draw_Title("PLA Settings"); // TODO: GET_TEXT_F - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(1), F("Nozzle Temp")); - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(2), F("Bed Temp")); - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(3), GET_TEXT_F(MSG_FAN_SPEED)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(4), GET_TEXT_F(MSG_STORE_EEPROM)); - #else - DWIN_Frame_AreaCopy(1, 56, 16, 141, 28, 14, 8); - DWIN_Frame_AreaCopy(1, 157, 76, 181, 86, LBLX, MBASE(1)); - DWIN_Frame_AreaCopy(1, 197, 104, 238, 114, LBLX + 27, MBASE(1)); - DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX + 71, MBASE(1)); // PLA nozzle temp - DWIN_Frame_AreaCopy(1, 157, 76, 181, 86, LBLX, MBASE(2) + 3); - DWIN_Frame_AreaCopy(1, 240, 104, 264, 114, LBLX + 27, MBASE(2) + 3); - DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX + 54, MBASE(2) + 3); // PLA bed temp - DWIN_Frame_AreaCopy(1, 157, 76, 181, 86, LBLX, MBASE(3)); - DWIN_Frame_AreaCopy(1, 0, 119, 64, 132, LBLX + 27, MBASE(3)); // PLA fan speed - DWIN_Frame_AreaCopy(1, 97, 165, 229, 177, LBLX, MBASE(4)); // save PLA configuration - #endif - } - - Draw_Back_First(); - - Draw_Menu_Line(1, ICON_SetEndTemp); - Draw_Menu_Line(2, ICON_SetBedTemp); - Draw_Menu_Line(3, ICON_FanSpeed); + #if HAS_HOTEND + case TEMP_CASE_TEMP: // Nozzle temperature + checkkey = ETemp; + HMI_ValueStruct.E_Temp = thermalManager.temp_hotend[0].target; + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(1), thermalManager.temp_hotend[0].target); + EncoderRate.enabled = true; + break; + #endif + #if HAS_HEATED_BED + case TEMP_CASE_BED: // Bed temperature + checkkey = BedTemp; + HMI_ValueStruct.Bed_Temp = thermalManager.temp_bed.target; + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(2), thermalManager.temp_bed.target); + EncoderRate.enabled = true; + break; + #endif + #if HAS_FAN + case TEMP_CASE_FAN: // Fan speed + checkkey = FanSpeed; + HMI_ValueStruct.Fan_speed = thermalManager.fan_speed[0]; + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(3), thermalManager.fan_speed[0]); + EncoderRate.enabled = true; + break; + #endif + #if HAS_HOTEND + case TEMP_CASE_PLA: { // PLA preheat setting + checkkey = PLAPreheat; + select_PLA.reset(); + HMI_ValueStruct.show_mode = -2; + + Clear_Main_Window(); + + if (HMI_flag.language_chinese) { + 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 + #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 + #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 + #endif #if ENABLED(EEPROM_SETTINGS) - Draw_Menu_Line(4, ICON_WriteEEPROM); + DWIN_Frame_AreaCopy(1, 72, 148, 151, 162, LBLX, MBASE(PREHEAT_CASE_SAVE)); // Save PLA configuration + #endif + } + else { + #ifdef USE_STRING_HEADINGS + Draw_Title("PLA Settings"); // TODO: GET_TEXT_F + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(PREHEAT_CASE_TEMP), F("Nozzle Temp")); + #if HAS_HEATED_BED + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(PREHEAT_CASE_BED), F("Bed Temp")); + #endif + #if HAS_FAN + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(PREHEAT_CASE_FAN), GET_TEXT_F(MSG_FAN_SPEED)); + #endif + #if ENABLED(EEPROM_SETTINGS) + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(PREHEAT_CASE_SAVE), GET_TEXT_F(MSG_STORE_EEPROM)); + #endif + #else + DWIN_Frame_TitleCopy(1, 56, 16, 141, 28); // "PLA Settings" + 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 + #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 + #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 + #endif + #if ENABLED(EEPROM_SETTINGS) + DWIN_Frame_AreaCopy(1, 97, 165, 229, 177, LBLX, MBASE(PREHEAT_CASE_SAVE)); // Save PLA configuration + #endif #endif + } - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(1), ui.material_preset[0].hotend_temp); - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(2), ui.material_preset[0].bed_temp); - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(3), ui.material_preset[0].fan_speed); + Draw_Back_First(); - break; + uint8_t i = 0; + Draw_Menu_Line(++i, ICON_SetEndTemp); + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(i), ui.material_preset[0].hotend_temp); + #if HAS_HEATED_BED + Draw_Menu_Line(++i, ICON_SetBedTemp); + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(i), ui.material_preset[0].bed_temp); + #endif + #if HAS_FAN + Draw_Menu_Line(++i, ICON_FanSpeed); + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(i), ui.material_preset[0].fan_speed); + #endif + #if ENABLED(EEPROM_SETTINGS) + Draw_Menu_Line(++i, ICON_WriteEEPROM); + #endif + } break; - case 5: // ABS preheat setting - checkkey = ABSPreheat; - select_ABS.reset(); - HMI_ValueStruct.show_mode = -3; - - Clear_Main_Window(); - - if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 142, 16, 223, 29, 14, 8); - - DWIN_Frame_AreaCopy(1, 180, 89, 204, 100, LBLX, MBASE(1)); - DWIN_Frame_AreaCopy(1, 1, 134, 56, 146, LBLX + 24, MBASE(1)); // ABS nozzle temp - DWIN_Frame_AreaCopy(1, 180, 89, 204, 100, LBLX, MBASE(2)); - DWIN_Frame_AreaCopy(1, 58, 134, 113, 146, LBLX + 24, MBASE(2)); // ABS bed temp - DWIN_Frame_AreaCopy(1, 180, 89, 204, 100, LBLX, MBASE(3)); - DWIN_Frame_AreaCopy(1, 115, 134, 170, 146, LBLX + 24, MBASE(3)); // ABS fan speed - DWIN_Frame_AreaCopy(1, 72, 148, 151, 162, LBLX, MBASE(4)); - DWIN_Frame_AreaCopy(1, 180, 89, 204, 100, LBLX + 28, MBASE(4) + 2); // save ABS configuration - } - else { - #ifdef USE_STRING_HEADINGS - Draw_Title("ABS Settings"); // TODO: GET_TEXT_F - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(1), F("Nozzle Temp")); - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(2), F("Bed Temp")); - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(3), GET_TEXT_F(MSG_FAN_SPEED)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(4), GET_TEXT_F(MSG_STORE_EEPROM)); - #else - DWIN_Frame_AreaCopy(1, 56, 16, 141, 28, 14, 8); - DWIN_Frame_AreaCopy(1, 172, 76, 198, 86, LBLX, MBASE(1)); - DWIN_Frame_AreaCopy(1, 197, 104, 238, 114, LBLX + 27, MBASE(1)); - DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX + 71, MBASE(1)); // ABS nozzle temp - DWIN_Frame_AreaCopy(1, 172, 76, 198, 86, LBLX, MBASE(2) + 3); - DWIN_Frame_AreaCopy(1, 240, 104, 264, 114, LBLX + 27, MBASE(2) + 3); - DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX + 54, MBASE(2) + 3); // ABS bed temp - DWIN_Frame_AreaCopy(1, 172, 76, 198, 86, LBLX, MBASE(3)); - DWIN_Frame_AreaCopy(1, 0, 119, 64, 132, LBLX + 27, MBASE(3)); // ABS fan speed - DWIN_Frame_AreaCopy(1, 97, 165, 229, 177, LBLX, MBASE(4)); - DWIN_Frame_AreaCopy(1, 172, 76, 198, 86, LBLX + 33, MBASE(4)); // save ABS configuration - #endif - } + case TEMP_CASE_ABS: { // ABS preheat setting + checkkey = ABSPreheat; + select_ABS.reset(); + HMI_ValueStruct.show_mode = -3; - Draw_Back_First(); + Clear_Main_Window(); - Draw_Menu_Line(1, ICON_SetEndTemp); - Draw_Menu_Line(2, ICON_SetBedTemp); - Draw_Menu_Line(3, ICON_FanSpeed); + if (HMI_flag.language_chinese) { + DWIN_Frame_TitleCopy(1, 142, 16, 223, 29); // "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 + #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 + #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 + #endif #if ENABLED(EEPROM_SETTINGS) - Draw_Menu_Line(4, ICON_WriteEEPROM); + 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 + #endif + } + else { + #ifdef USE_STRING_HEADINGS + Draw_Title("ABS Settings"); // TODO: GET_TEXT_F + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(PREHEAT_CASE_TEMP), F("Nozzle Temp")); + #if HAS_HEATED_BED + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(PREHEAT_CASE_BED), F("Bed Temp")); + #endif + #if HAS_FAN + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(PREHEAT_CASE_FAN), GET_TEXT_F(MSG_FAN_SPEED)); + #endif + #if ENABLED(EEPROM_SETTINGS) + DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(PREHEAT_CASE_SAVE), GET_TEXT_F(MSG_STORE_EEPROM)); + #endif + #else + DWIN_Frame_TitleCopy(1, 56, 16, 141, 28); // "ABS Settings" + 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 + #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 + #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 + #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 + #endif #endif + } - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(1), ui.material_preset[1].hotend_temp); - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(2), ui.material_preset[1].bed_temp); - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(3), ui.material_preset[1].fan_speed); + Draw_Back_First(); - break; - #endif // HAS_HOTEND + uint8_t i = 0; + Draw_Menu_Line(++i, ICON_SetEndTemp); + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(i), ui.material_preset[1].hotend_temp); + #if HAS_HEATED_BED + Draw_Menu_Line(++i, ICON_SetBedTemp); + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(i), ui.material_preset[1].bed_temp); + #endif + #if HAS_FAN + Draw_Menu_Line(++i, ICON_FanSpeed); + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(i), ui.material_preset[1].fan_speed); + #endif + #if ENABLED(EEPROM_SETTINGS) + Draw_Menu_Line(++i, ICON_WriteEEPROM); + #endif + + } break; + + #endif // HAS_HOTEND } } DWIN_UpdateLCD(); @@ -2659,18 +2926,18 @@ inline void Draw_Max_Speed_Menu() { DWIN_Frame_TitleCopy(1, 1, 16, 28, 28); // "Max Speed (mm/s)" auto say_max_speed = [](const uint16_t row) { - DWIN_Frame_AreaCopy(1, 173, 133, 228, 147, LBLX, row); // "Max speed" + DWIN_Frame_AreaCopy(1, 173, 133, 228, 147, LBLX, row); // "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(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 #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(MBASE(4)); // "Max speed" + DWIN_Frame_AreaCopy(1, 18, 150, 25, 160, LBLX + 58, MBASE(4) + 3); // E #endif } else { @@ -2745,7 +3012,7 @@ inline void Draw_Max_Accel_Menu() { DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(4), F("Max Accel E")); #endif #else - DWIN_Frame_TitleCopy(1, 144, 16, 189, 26); // "Acceleration" + DWIN_Frame_TitleCopy(1, 144, 16, 189, 26); // "Acceleration" 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" @@ -2883,13 +3150,13 @@ inline void Draw_Steps_Menu() { } /* Motion */ -void HMI_Motion(void) { +void HMI_Motion() { 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_motion.inc(4)) Move_Highlight(1, select_motion.now); + if (select_motion.inc(1 + MOTION_CASE_TOTAL)) Move_Highlight(1, select_motion.now); } else if (encoder_diffState == ENCODER_DIFF_CCW) { if (select_motion.dec()) Move_Highlight(-1, select_motion.now); @@ -2898,26 +3165,28 @@ void HMI_Motion(void) { switch (select_motion.now) { case 0: // Back checkkey = Control; - select_control.set(2); + select_control.set(CONTROL_CASE_MOVE); index_control = MROWS; Draw_Control_Menu(); break; - case 1: // max speed + case MOTION_CASE_RATE: // Max speed checkkey = MaxSpeed; select_speed.reset(); Draw_Max_Speed_Menu(); break; - case 2: // max acceleration + case MOTION_CASE_ACCEL: // Max acceleration checkkey = MaxAcceleration; select_acc.reset(); Draw_Max_Accel_Menu(); break; - case 3: // max jerk speed - checkkey = MaxJerk; - select_jerk.reset(); - Draw_Max_Jerk_Menu(); - break; - case 4: // transmission ratio + #if HAS_CLASSIC_JERK + case MOTION_CASE_JERK: // Max jerk + checkkey = MaxJerk; + select_jerk.reset(); + Draw_Max_Jerk_Menu(); + break; + #endif + case MOTION_CASE_STEPS: // Steps per mm checkkey = Step; select_step.reset(); Draw_Steps_Menu(); @@ -2929,13 +3198,13 @@ void HMI_Motion(void) { } /* Info */ -void HMI_Info(void) { +void HMI_Info() { ENCODER_DiffState encoder_diffState = get_encoder_state(); if (encoder_diffState == ENCODER_DIFF_NO) return; if (encoder_diffState == ENCODER_DIFF_ENTER) { #if HAS_ONESTEP_LEVELING checkkey = Control; - select_control.set(CONTROL_ITEMS); + select_control.set(CONTROL_CASE_INFO); Draw_Control_Menu(); #else select_page.set(3); @@ -2946,17 +3215,16 @@ void HMI_Info(void) { } /* Tune */ -void HMI_Tune(void) { +void HMI_Tune() { 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_tune.inc(6)) { + if (select_tune.inc(1 + TUNE_CASE_TOTAL)) { if (select_tune.now > MROWS && select_tune.now > index_tune) { index_tune = select_tune.now; Scroll_Menu(DWIN_SCROLL_UP); - Prepare_Item_Lang(5); } else { Move_Highlight(1, select_tune.now + MROWS - index_tune); @@ -2982,186 +3250,180 @@ void HMI_Tune(void) { Goto_PrintProcess(); } break; - case 1: // Print speed + case TUNE_CASE_SPEED: // Print speed checkkey = PrintSpeed; HMI_ValueStruct.print_speed = feedrate_percentage; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(1 + MROWS - index_tune), feedrate_percentage); - EncoderRate.encoderRateEnabled = 1; - break; - #if HAS_HOTEND - case 2: // Nozzle temp - checkkey = ETemp; - HMI_ValueStruct.E_Temp = thermalManager.temp_hotend[0].target; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(2 + MROWS - index_tune), thermalManager.temp_hotend[0].target); - EncoderRate.encoderRateEnabled = 1; - break; - #endif - #if HAS_HEATED_BED - case 3: // Bed temp - checkkey = BedTemp; - HMI_ValueStruct.Bed_Temp = thermalManager.temp_bed.target; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(3 + MROWS - index_tune), thermalManager.temp_bed.target); - EncoderRate.encoderRateEnabled = 1; - break; - #endif - #if HAS_FAN - case 4: // Fan speed - checkkey = FanSpeed; - HMI_ValueStruct.Fan_speed = thermalManager.fan_speed[0]; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(4 + MROWS - index_tune), thermalManager.fan_speed[0]); - EncoderRate.encoderRateEnabled = 1; - break; - #endif - case 5: // Z-offset - checkkey = Homeoffset; - HMI_ValueStruct.offset_value = BABY_Z_VAR * 100; - DWIN_Draw_Signed_Float(font8x16, Select_Color, 2, 2, 202, MBASE(5 + MROWS - index_tune), HMI_ValueStruct.offset_value); - EncoderRate.encoderRateEnabled = 1; + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(TUNE_CASE_SPEED + MROWS - index_tune), feedrate_percentage); + EncoderRate.enabled = true; break; - case 6: // Language - // Select language - HMI_flag.language_chinese ^= true; - - Clear_Main_Window(); - - if (HMI_flag.language_chinese) { - HMI_SetAndSaveLanguageChinese(); - DWIN_JPG_CacheTo1(Language_Chinese); - } - else { - HMI_SetAndSaveLanguageWestern(); - DWIN_JPG_CacheTo1(Language_English); - } - - Draw_Tune_Menu(); + #if HAS_HOTEND + case TUNE_CASE_TEMP: // Nozzle temp + checkkey = ETemp; + HMI_ValueStruct.E_Temp = thermalManager.temp_hotend[0].target; + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(TUNE_CASE_TEMP + MROWS - index_tune), thermalManager.temp_hotend[0].target); + EncoderRate.enabled = true; + break; + #endif + #if HAS_HEATED_BED + case TUNE_CASE_BED: // Bed temp + checkkey = BedTemp; + HMI_ValueStruct.Bed_Temp = thermalManager.temp_bed.target; + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(TUNE_CASE_BED + MROWS - index_tune), thermalManager.temp_bed.target); + EncoderRate.enabled = true; + break; + #endif + #if HAS_FAN + case TUNE_CASE_FAN: // Fan speed + checkkey = FanSpeed; + HMI_ValueStruct.Fan_speed = thermalManager.fan_speed[0]; + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(TUNE_CASE_FAN + MROWS - index_tune), thermalManager.fan_speed[0]); + EncoderRate.enabled = true; + break; + #endif + #if HAS_ZOFFSET_ITEM + case TUNE_CASE_ZOFF: // Z-offset + #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); + EncoderRate.enabled = true; + #else + // Apply workspace offset, making the current position 0,0,0 + queue.inject_P(PSTR("G92 X0 Y0 Z0")); + HMI_AudioFeedback(); + #endif break; - + #endif default: break; } } DWIN_UpdateLCD(); } -/* PLA Preheat */ -void HMI_PLAPreheatSetting(void) { - ENCODER_DiffState encoder_diffState = get_encoder_state(); - if (encoder_diffState == ENCODER_DIFF_NO) return; +#if HAS_PREHEAT - // Avoid flicker by updating only the previous menu - if (encoder_diffState == ENCODER_DIFF_CW) { - if (select_PLA.inc(4)) Move_Highlight(1, select_PLA.now); - } - else if (encoder_diffState == ENCODER_DIFF_CCW) { - if (select_PLA.dec()) Move_Highlight(-1, select_PLA.now); - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { - switch (select_PLA.now) { - case 0: // Back - checkkey = TemperatureID; - select_temp.now = 4; - HMI_ValueStruct.show_mode = -1; - Draw_Temperature_Menu(); - break; + /* PLA Preheat */ + void HMI_PLAPreheatSetting() { + 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_PLA.inc(1 + PREHEAT_CASE_TOTAL)) Move_Highlight(1, select_PLA.now); + } + else if (encoder_diffState == ENCODER_DIFF_CCW) { + if (select_PLA.dec()) Move_Highlight(-1, select_PLA.now); + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + switch (select_PLA.now) { + case 0: // Back + checkkey = TemperatureID; + select_temp.now = TEMP_CASE_PLA; + HMI_ValueStruct.show_mode = -1; + Draw_Temperature_Menu(); + break; #if HAS_HOTEND - case 1: // set nozzle temperature + 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, White, Select_Color, 3, 216, MBASE(1), ui.material_preset[0].hotend_temp); - EncoderRate.encoderRateEnabled = 1; + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(PREHEAT_CASE_TEMP), ui.material_preset[0].hotend_temp); + EncoderRate.enabled = true; break; #endif #if HAS_HEATED_BED - case 2: // set bed temperature + 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, White, Select_Color, 3, 216, MBASE(2), ui.material_preset[0].bed_temp); - EncoderRate.encoderRateEnabled = 1; + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(PREHEAT_CASE_BED), ui.material_preset[0].bed_temp); + EncoderRate.enabled = true; break; #endif #if HAS_FAN - case 3: // set fan speed + 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, White, Select_Color, 3, 216, MBASE(3), ui.material_preset[0].fan_speed); - EncoderRate.encoderRateEnabled = 1; + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(PREHEAT_CASE_FAN), ui.material_preset[0].fan_speed); + EncoderRate.enabled = true; break; #endif - #if ENABLED(EEPROM_SETTINGS) - case 4: { // Save PLA configuration - const bool success = settings.save(); - HMI_AudioFeedback(success); - } break; - #endif - default: break; + #if ENABLED(EEPROM_SETTINGS) + case 4: { // Save PLA configuration + const bool success = settings.save(); + HMI_AudioFeedback(success); + } break; + #endif + default: break; + } } + DWIN_UpdateLCD(); } - DWIN_UpdateLCD(); -} -/* ABS Preheat */ -void HMI_ABSPreheatSetting(void) { - ENCODER_DiffState encoder_diffState = get_encoder_state(); - if (encoder_diffState == ENCODER_DIFF_NO) return; + /* ABS Preheat */ + void HMI_ABSPreheatSetting() { + 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_ABS.inc(4)) Move_Highlight(1, select_ABS.now); - } - else if (encoder_diffState == ENCODER_DIFF_CCW) { - if (select_ABS.dec()) Move_Highlight(-1, select_ABS.now); - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { - switch (select_ABS.now) { - case 0: // Back - checkkey = TemperatureID; - select_temp.now = 5; - HMI_ValueStruct.show_mode = -1; - Draw_Temperature_Menu(); - break; + // Avoid flicker by updating only the previous menu + if (encoder_diffState == ENCODER_DIFF_CW) { + if (select_ABS.inc(1 + PREHEAT_CASE_TOTAL)) Move_Highlight(1, select_ABS.now); + } + else if (encoder_diffState == ENCODER_DIFF_CCW) { + if (select_ABS.dec()) Move_Highlight(-1, select_ABS.now); + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + switch (select_ABS.now) { + case 0: // Back + checkkey = TemperatureID; + select_temp.now = TEMP_CASE_ABS; + HMI_ValueStruct.show_mode = -1; + Draw_Temperature_Menu(); + break; #if HAS_HOTEND - case 1: // set nozzle temperature + 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, White, Select_Color, 3, 216, MBASE(1), ui.material_preset[1].hotend_temp); - EncoderRate.encoderRateEnabled = 1; + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(PREHEAT_CASE_TEMP), ui.material_preset[1].hotend_temp); + EncoderRate.enabled = true; break; #endif #if HAS_HEATED_BED - case 2: // set bed temperature + 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, White, Select_Color, 3, 216, MBASE(2), ui.material_preset[1].bed_temp); - EncoderRate.encoderRateEnabled = 1; + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(PREHEAT_CASE_BED), ui.material_preset[1].bed_temp); + EncoderRate.enabled = true; break; #endif #if HAS_FAN - case 3: // set fan speed + 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, White, Select_Color, 3, 216, MBASE(3), ui.material_preset[1].fan_speed); - EncoderRate.encoderRateEnabled = 1; + DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(PREHEAT_CASE_FAN), ui.material_preset[1].fan_speed); + EncoderRate.enabled = true; break; #endif - #if ENABLED(EEPROM_SETTINGS) - case 4: { // save ABS configuration - const bool success = settings.save(); - HMI_AudioFeedback(success); - } break; - #endif - default: break; + #if ENABLED(EEPROM_SETTINGS) + case PREHEAT_CASE_SAVE: { // Save ABS configuration + const bool success = settings.save(); + HMI_AudioFeedback(success); + } break; + #endif + default: break; + } } + DWIN_UpdateLCD(); } - DWIN_UpdateLCD(); -} + +#endif /* Max Speed */ -void HMI_MaxSpeed(void) { +void HMI_MaxSpeed() { 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_speed.inc(4)) Move_Highlight(1, select_speed.now); + if (select_speed.inc(1 + 3 + ENABLED(HAS_HOTEND))) Move_Highlight(1, select_speed.now); } else if (encoder_diffState == ENCODER_DIFF_CCW) { if (select_speed.dec()) Move_Highlight(-1, select_speed.now); @@ -3169,14 +3431,14 @@ void HMI_MaxSpeed(void) { else if (encoder_diffState == ENCODER_DIFF_ENTER) { if (WITHIN(select_speed.now, 1, 4)) { checkkey = MaxSpeed_value; - HMI_flag.feedspeed_flag = AxisEnum(select_speed.now - 1); - HMI_ValueStruct.Max_Feedspeed = planner.settings.max_feedrate_mm_s[HMI_flag.feedspeed_flag]; + 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, White, Select_Color, 4, 210, MBASE(select_speed.now), HMI_ValueStruct.Max_Feedspeed); - EncoderRate.encoderRateEnabled = 1; + EncoderRate.enabled = true; } else { // Back checkkey = Motion; - select_motion.now = 1; + select_motion.now = MOTION_CASE_RATE; Draw_Motion_Menu(); } } @@ -3184,13 +3446,13 @@ void HMI_MaxSpeed(void) { } /* Max Acceleration */ -void HMI_MaxAcceleration(void) { +void HMI_MaxAcceleration() { 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_acc.inc(4)) Move_Highlight(1, select_acc.now); + if (select_acc.inc(1 + 3 + ENABLED(HAS_HOTEND))) Move_Highlight(1, select_acc.now); } else if (encoder_diffState == ENCODER_DIFF_CCW) { if (select_acc.dec()) Move_Highlight(-1, select_acc.now); @@ -3198,57 +3460,59 @@ void HMI_MaxAcceleration(void) { else if (encoder_diffState == ENCODER_DIFF_ENTER) { if (WITHIN(select_acc.now, 1, 4)) { checkkey = MaxAcceleration_value; - HMI_flag.acc_flag = AxisEnum(select_acc.now - 1); - HMI_ValueStruct.Max_Acceleration = planner.settings.max_acceleration_mm_per_s2[HMI_flag.acc_flag]; + 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, White, Select_Color, 4, 210, MBASE(select_acc.now), HMI_ValueStruct.Max_Acceleration); - EncoderRate.encoderRateEnabled = 1; + EncoderRate.enabled = true; } else { // Back checkkey = Motion; - select_motion.now = 2; + select_motion.now = MOTION_CASE_ACCEL; Draw_Motion_Menu(); } } DWIN_UpdateLCD(); } -/* Max Jerk */ -void HMI_MaxJerk(void) { - ENCODER_DiffState encoder_diffState = get_encoder_state(); - if (encoder_diffState == ENCODER_DIFF_NO) return; +#if HAS_CLASSIC_JERK + /* Max Jerk */ + void HMI_MaxJerk() { + 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_jerk.inc(4)) Move_Highlight(1, select_jerk.now); - } - else if (encoder_diffState == ENCODER_DIFF_CCW) { - if (select_jerk.dec()) Move_Highlight(-1, select_jerk.now); - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { - if (WITHIN(select_jerk.now, 1, 4)) { - checkkey = MaxJerk_value; - HMI_flag.jerk_flag = AxisEnum(select_jerk.now - 1); - HMI_ValueStruct.Max_Jerk = planner.max_jerk[HMI_flag.jerk_flag] * MINUNITMULT; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 4, 210, MBASE(select_jerk.now), HMI_ValueStruct.Max_Jerk); - EncoderRate.encoderRateEnabled = 1; + // Avoid flicker by updating only the previous menu + if (encoder_diffState == ENCODER_DIFF_CW) { + if (select_jerk.inc(1 + 3 + ENABLED(HAS_HOTEND))) Move_Highlight(1, select_jerk.now); } - else { // Back - checkkey = Motion; - select_motion.now = 3; - Draw_Motion_Menu(); + else if (encoder_diffState == ENCODER_DIFF_CCW) { + if (select_jerk.dec()) Move_Highlight(-1, select_jerk.now); + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + if (WITHIN(select_jerk.now, 1, 4)) { + checkkey = MaxJerk_value; + HMI_flag.jerk_axis = AxisEnum(select_jerk.now - 1); + HMI_ValueStruct.Max_Jerk = planner.max_jerk[HMI_flag.jerk_axis] * MINUNITMULT; + DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 210, MBASE(select_jerk.now), HMI_ValueStruct.Max_Jerk); + EncoderRate.enabled = true; + } + else { // Back + checkkey = Motion; + select_motion.now = MOTION_CASE_JERK; + Draw_Motion_Menu(); + } } + DWIN_UpdateLCD(); } - DWIN_UpdateLCD(); -} +#endif // HAS_CLASSIC_JERK /* Step */ -void HMI_Step(void) { +void HMI_Step() { 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_step.inc(4)) Move_Highlight(1, select_step.now); + if (select_step.inc(1 + 3 + ENABLED(HAS_HOTEND))) Move_Highlight(1, select_step.now); } else if (encoder_diffState == ENCODER_DIFF_CCW) { if (select_step.dec()) Move_Highlight(-1, select_step.now); @@ -3256,21 +3520,21 @@ void HMI_Step(void) { else if (encoder_diffState == ENCODER_DIFF_ENTER) { if (WITHIN(select_step.now, 1, 4)) { checkkey = Step_value; - HMI_flag.step_flag = AxisEnum(select_step.now - 1); - HMI_ValueStruct.Max_Step = planner.settings.axis_steps_per_mm[HMI_flag.step_flag] * MINUNITMULT; + HMI_flag.step_axis = AxisEnum(select_step.now - 1); + HMI_ValueStruct.Max_Step = planner.settings.axis_steps_per_mm[HMI_flag.step_axis] * MINUNITMULT; DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 210, MBASE(select_step.now), HMI_ValueStruct.Max_Step); - EncoderRate.encoderRateEnabled = 1; + EncoderRate.enabled = true; } else { // Back checkkey = Motion; - select_motion.now = 4; + select_motion.now = MOTION_CASE_STEPS; Draw_Motion_Menu(); } } DWIN_UpdateLCD(); } -void HMI_Init(void) { +void HMI_Init() { HMI_SDCardInit(); for (uint16_t t = 0; t <= 100; t += 2) { @@ -3283,13 +3547,13 @@ void HMI_Init(void) { HMI_SetLanguage(); } -void DWIN_Update(void) { +void DWIN_Update() { EachMomentUpdate(); // Status update HMI_SDCardUpdate(); // SD card update DWIN_HandleScreen(); // Rotary encoder update } -void EachMomentUpdate(void) { +void EachMomentUpdate() { static millis_t next_rts_update_ms = 0; const millis_t ms = millis(); if (PENDING(ms, next_rts_update_ms)) return; @@ -3300,9 +3564,9 @@ void EachMomentUpdate(void) { if (checkkey == PrintProcess) { // if print done - if (HMI_flag.print_finish && !HMI_flag.confirm_flag) { - HMI_flag.print_finish = 0; - HMI_flag.confirm_flag = 1; + if (HMI_flag.print_finish && !HMI_flag.done_confirm_flag) { + HMI_flag.print_finish = false; + HMI_flag.done_confirm_flag = true; TERN_(POWER_LOSS_RECOVERY, recovery.cancel()); @@ -3313,7 +3577,7 @@ void EachMomentUpdate(void) { Draw_Print_ProgressBar(); // show print done confirm - DWIN_Draw_Rectangle(1, Background_black, 0, 250, 271, 360); + DWIN_Draw_Rectangle(1, Background_black, 0, 250, DWIN_WIDTH - 1, STATUS_Y); DWIN_ICON_Show(ICON, HMI_flag.language_chinese ? ICON_Confirm_C : ICON_Confirm_E, 86, 283); } else if (HMI_flag.pause_flag != printingIsPaused()) { @@ -3324,11 +3588,15 @@ void EachMomentUpdate(void) { } // pause after homing - if (pause_action_flag && printingIsPaused() && !planner.has_blocks_queued()) { - pause_action_flag = 0; + if (HMI_flag.pause_action && printingIsPaused() && !planner.has_blocks_queued()) { + HMI_flag.pause_action = false; #if ENABLED(PAUSE_HEAT) - tempbed = thermalManager.temp_bed.target; - temphot = thermalManager.temp_hotend[0].target; + #if HAS_HEATED_BED + tempbed = thermalManager.temp_bed.target; + #endif + #if HAS_HOTEND + temphot = thermalManager.temp_hotend[0].target; + #endif thermalManager.disable_all_heaters(); #endif queue.inject_P(PSTR("G1 F1200 X0 Y0")); @@ -3348,6 +3616,7 @@ void EachMomentUpdate(void) { duration_t elapsed = print_job_timer.duration(); // print timer // 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; @@ -3356,14 +3625,14 @@ void EachMomentUpdate(void) { // Estimate remaining time every 20 seconds static millis_t next_remain_time_update = 0; - if (Percentrecord > 1 && ELAPSED(ms, next_remain_time_update) && HMI_flag.heat_flag == 0) { + if (Percentrecord > 1 && ELAPSED(ms, next_remain_time_update) && !HMI_flag.heat_flag) { remain_time = (elapsed.value - dwin_heat_time) / (Percentrecord * 0.01f) - (elapsed.value - dwin_heat_time); next_remain_time_update += 20 * 1000UL; Draw_Print_ProgressRemain(); } } - else if (abort_flag && !HMI_flag.home_flag) { // Print Stop - abort_flag = 0; + else if (dwin_abort_flag && !HMI_flag.home_flag) { // Print Stop + dwin_abort_flag = false; HMI_ValueStruct.print_speed = feedrate_percentage = 100; dwin_zoffset = TERN0(HAS_BED_PROBE, probe.offset.z); @@ -3378,6 +3647,7 @@ void EachMomentUpdate(void) { } #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.load(); @@ -3403,8 +3673,8 @@ void EachMomentUpdate(void) { // with the active filename which can come from CardReader. card.getfilename_sorted(SD_ORDER(i, fileCnt)); if (!strcmp(card.filename, &recovery.info.sd_filename[1])) { // Resume print before power failure while have the same file - recovery_flag = 1; - HMI_flag.select_flag = 1; + recovery_flag = true; + HMI_flag.select_flag = true; Popup_Window_Resume(); draw_first_option(false); char * const name = card.longest_filename(); @@ -3422,7 +3692,7 @@ void EachMomentUpdate(void) { ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); if (encoder_diffState != ENCODER_DIFF_NO) { if (encoder_diffState == ENCODER_DIFF_ENTER) { - recovery_flag = 0; + recovery_flag = false; if (HMI_flag.select_flag) break; TERN_(POWER_LOSS_RECOVERY, recovery.cancel()); HMI_StartFrame(true); @@ -3445,7 +3715,7 @@ void EachMomentUpdate(void) { DWIN_UpdateLCD(); } -void DWIN_HandleScreen(void) { +void DWIN_HandleScreen() { switch (checkkey) { case MainMenu: HMI_MainMenu(); break; case SelectFile: HMI_SelectFile(); break; @@ -3459,8 +3729,10 @@ void DWIN_HandleScreen(void) { case Motion: HMI_Motion(); break; case Info: HMI_Info(); break; case Tune: HMI_Tune(); break; - case PLAPreheat: HMI_PLAPreheatSetting(); break; - case ABSPreheat: HMI_ABSPreheatSetting(); break; + #if HAS_PREHEAT + case PLAPreheat: HMI_PLAPreheatSetting(); break; + case ABSPreheat: HMI_ABSPreheatSetting(); break; + #endif case MaxSpeed: HMI_MaxSpeed(); break; case MaxAcceleration: HMI_MaxAcceleration(); break; case MaxJerk: HMI_MaxJerk(); break; @@ -3472,11 +3744,13 @@ void DWIN_HandleScreen(void) { case Extruder: HMI_Move_E(); break; case ETemp: HMI_ETemp(); break; #endif - case Homeoffset: HMI_Zoffset(); break; + #if EITHER(HAS_BED_PROBE, BABYSTEPPING) + case Homeoffset: HMI_Zoffset(); break; + #endif #if HAS_HEATED_BED case BedTemp: HMI_BedTemp(); break; #endif - #if HAS_FAN + #if HAS_PREHEAT case FanSpeed: HMI_FanSpeed(); break; #endif case PrintSpeed: HMI_PrintSpeed(); break; @@ -3488,11 +3762,11 @@ void DWIN_HandleScreen(void) { } } -void DWIN_CompletedHoming(void) { +void DWIN_CompletedHoming() { HMI_flag.home_flag = false; if (checkkey == Last_Prepare) { checkkey = Prepare; - select_prepare.now = 3; + select_prepare.now = PREPARE_CASE_HOME; index_prepare = MROWS; Draw_Prepare_Menu(); } @@ -3504,7 +3778,7 @@ void DWIN_CompletedHoming(void) { } } -void DWIN_CompletedLeveling(void) { +void DWIN_CompletedLeveling() { if (checkkey == Leveling) Goto_MainMenu(); } diff --git a/Marlin/src/lcd/dwin/e3v2/dwin.h b/Marlin/src/lcd/dwin/e3v2/dwin.h index abdf343a9ded..fedb87afdd81 100644 --- a/Marlin/src/lcd/dwin/e3v2/dwin.h +++ b/Marlin/src/lcd/dwin/e3v2/dwin.h @@ -29,9 +29,16 @@ #include "rotary_encoder.h" #include "../../../libs/BL24CXX.h" -#include +#include "../../../inc/MarlinConfigPre.h" -enum processID { +#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 + +enum processID : uint8_t { // Process ID MainMenu, SelectFile, @@ -44,7 +51,7 @@ enum processID { Motion, Info, Tune, - #if HAS_HOTEND + #if HAS_PREHEAT PLAPreheat, ABSPreheat, #endif @@ -218,7 +225,7 @@ enum processID { #define BarFill_Color 0x10E4 // fill color of progress bar #define Select_Color 0x33BB // selected color -extern int checkkey, last_checkkey; +extern uint8_t checkkey; extern float zprobe_zoffset; extern char print_filename[16]; @@ -227,7 +234,7 @@ extern millis_t dwin_heat_time; typedef struct { TERN_(HAS_HOTEND, int16_t E_Temp = 0); TERN_(HAS_HEATED_BED, int16_t Bed_Temp = 0); - TERN_(HAS_FAN, int16_t Fan_speed = 0); + TERN_(HAS_PREHEAT, int16_t Fan_speed = 0); int16_t print_speed = 100; float Max_Feedspeed = 0; float Max_Acceleration = 0; @@ -236,7 +243,7 @@ typedef struct { float Move_X_scale = 0; float Move_Y_scale = 0; float Move_Z_scale = 0; - #if EXTRUDERS + #if HAS_HOTEND float Move_E_scale = 0; #endif float offset_value = 0; @@ -246,33 +253,27 @@ typedef struct { typedef struct { bool language_chinese; // 0: EN, 1: CN bool pause_flag:1; + bool pause_action:1; bool print_finish:1; - bool confirm_flag:1; + bool done_confirm_flag:1; bool select_flag:1; bool home_flag:1; bool heat_flag:1; // 0: heating done 1: during heating - #if HAS_HOTEND + #if ENABLED(PREVENT_COLD_EXTRUSION) bool ETempTooLow_flag:1; #endif #if HAS_LEVELING bool leveling_offset_flag:1; #endif #if HAS_FAN - AxisEnum feedspeed_flag; + AxisEnum feedspeed_axis; #endif - AxisEnum acc_flag; - AxisEnum jerk_flag; - AxisEnum step_flag; + AxisEnum acc_axis, jerk_axis, step_axis; } HMI_Flag; extern HMI_value_t HMI_ValueStruct; extern HMI_Flag HMI_flag; -// Language -void HMI_SetLanguage(void); -void HMI_SetAndSaveLanguageWestern(void); -void HMI_SetAndSaveLanguageChinese(void); - // Show ICO void ICON_Print(bool show); void ICON_Prepare(bool show); @@ -285,44 +286,47 @@ void ICON_Pause(bool show); void ICON_Continue(bool show); void ICON_Stop(bool show); -// Popup window tips +#if HAS_HOTEND || HAS_HEATED_BED + // Popup message window + void DWIN_Popup_Temperature(const bool toohigh); +#endif + #if HAS_HOTEND - void Popup_Window_Temperature(const bool toohigh); - void Popup_Window_ETempTooLow(void); + void Popup_Window_ETempTooLow(); #endif -void Popup_Window_Resume(void); -void Popup_Window_Home(void); -void Popup_Window_Leveling(void); +void Popup_Window_Resume(); +void Popup_Window_Home(const bool parking=false); +void Popup_Window_Leveling(); -void Goto_PrintProcess(void); -void Goto_MainMenu(void); +void Goto_PrintProcess(); +void Goto_MainMenu(); // Variable control -void HMI_Move_X(void); -void HMI_Move_Y(void); -void HMI_Move_Z(void); -void HMI_Move_E(void); +void HMI_Move_X(); +void HMI_Move_Y(); +void HMI_Move_Z(); +void HMI_Move_E(); -void HMI_Zoffset(void); +void HMI_Zoffset(); -TERN_(HAS_HOTEND, void HMI_ETemp(void)); -TERN_(HAS_HEATED_BED, void HMI_BedTemp(void)); -TERN_(HAS_FAN, void HMI_FanSpeed(void)); +TERN_(HAS_HOTEND, void HMI_ETemp()); +TERN_(HAS_HEATED_BED, void HMI_BedTemp()); +TERN_(HAS_FAN, void HMI_FanSpeed()); -void HMI_PrintSpeed(void); +void HMI_PrintSpeed(); -void HMI_MaxFeedspeedXYZE(void); -void HMI_MaxAccelerationXYZE(void); -void HMI_MaxJerkXYZE(void); -void HMI_StepXYZE(void); +void HMI_MaxFeedspeedXYZE(); +void HMI_MaxAccelerationXYZE(); +void HMI_MaxJerkXYZE(); +void HMI_StepXYZE(); -void update_variable(void); +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); // SD Card -void HMI_SDCardInit(void); -void HMI_SDCardUpdate(void); +void HMI_SDCardInit(); +void HMI_SDCardUpdate(); // Main Process void Icon_print(bool value); @@ -333,32 +337,32 @@ void Icon_leveling(bool value); // Other bool Pause_HeatStatus(); void HMI_StartFrame(const bool with_update); // Startup screen -void HMI_MainMenu(void); // Main process screen -void HMI_SelectFile(void); // File page -void HMI_Printing(void); // Print page -void HMI_Prepare(void); // Prepare page -void HMI_Control(void); // Control page -void HMI_Leveling(void); // Level the page -void HMI_AxisMove(void); // Axis movement menu -void HMI_Temperature(void); // Temperature menu -void HMI_Motion(void); // Sports menu -void HMI_Info(void); // Information menu -void HMI_Tune(void); // Adjust the menu - -#if HAS_HOTEND - void HMI_PLAPreheatSetting(void); // PLA warm-up setting - void HMI_ABSPreheatSetting(void); // ABS warm-up setting +void HMI_MainMenu(); // Main process screen +void HMI_SelectFile(); // File page +void HMI_Printing(); // Print page +void HMI_Prepare(); // Prepare page +void HMI_Control(); // Control page +void HMI_Leveling(); // Level the page +void HMI_AxisMove(); // Axis movement menu +void HMI_Temperature(); // Temperature menu +void HMI_Motion(); // Sports menu +void HMI_Info(); // Information menu +void HMI_Tune(); // Adjust the menu + +#if HAS_PREHEAT + void HMI_PLAPreheatSetting(); // PLA warm-up setting + void HMI_ABSPreheatSetting(); // ABS warm-up setting #endif -void HMI_MaxSpeed(void); // Maximum speed submenu -void HMI_MaxAcceleration(void); // Maximum acceleration submenu -void HMI_MaxJerk(void); // Maximum jerk speed submenu -void HMI_Step(void); // Transmission ratio +void HMI_MaxSpeed(); // Maximum speed submenu +void HMI_MaxAcceleration(); // Maximum acceleration submenu +void HMI_MaxJerk(); // Maximum jerk speed submenu +void HMI_Step(); // Transmission ratio -void HMI_Init(void); -void DWIN_Update(void); -void EachMomentUpdate(void); -void DWIN_HandleScreen(void); +void HMI_Init(); +void DWIN_Update(); +void EachMomentUpdate(); +void DWIN_HandleScreen(); -void DWIN_CompletedHoming(void); -void DWIN_CompletedLeveling(void); +void DWIN_CompletedHoming(); +void DWIN_CompletedLeveling(); diff --git a/Marlin/src/lcd/dwin/e3v2/rotary_encoder.cpp b/Marlin/src/lcd/dwin/e3v2/rotary_encoder.cpp index dbbd356eff2d..b1d905d9adcd 100644 --- a/Marlin/src/lcd/dwin/e3v2/rotary_encoder.cpp +++ b/Marlin/src/lcd/dwin/e3v2/rotary_encoder.cpp @@ -124,7 +124,7 @@ ENCODER_DiffState Encoder_ReceiveAnalyze(void) { int32_t encoderMultiplier = 1; // if must encoder rati multiplier - if (EncoderRate.encoderRateEnabled) { + if (EncoderRate.enabled) { const float abs_diff = ABS(temp_diff), encoderMovementSteps = abs_diff / (ENCODER_PULSES_PER_STEP); if (EncoderRate.lastEncoderTime) { diff --git a/Marlin/src/lcd/dwin/e3v2/rotary_encoder.h b/Marlin/src/lcd/dwin/e3v2/rotary_encoder.h index fb8102f8b22a..93e54839d625 100644 --- a/Marlin/src/lcd/dwin/e3v2/rotary_encoder.h +++ b/Marlin/src/lcd/dwin/e3v2/rotary_encoder.h @@ -44,7 +44,7 @@ #define BUTTON_PRESSED(BN) !READ(BTN_## BN) typedef struct { - bool encoderRateEnabled = 0; + bool enabled = false; int encoderMoveValue = 0; millis_t lastEncoderTime = 0; } ENCODER_Rate; diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index e0fa6fa98f53..d2145bcc804a 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -576,7 +576,7 @@ volatile bool Temperature::raw_temps_ready = false; #define MAX_CYCLE_TIME_PID_AUTOTUNE 20L #endif if ((ms - _MIN(t1, t2)) > (MAX_CYCLE_TIME_PID_AUTOTUNE * 60L * 1000L)) { - TERN_(DWIN_CREALITY_LCD, Popup_Window_Temperature(0)); + TERN_(DWIN_CREALITY_LCD, DWIN_Popup_Temperature(0)); TERN_(EXTENSIBLE_UI, ExtUI::onPidTuning(ExtUI::result_t::PID_TUNING_TIMEOUT)); SERIAL_ECHOLNPGM(STR_PID_TIMEOUT); break; @@ -812,12 +812,16 @@ 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) { - TERN_(DWIN_CREALITY_LCD, Popup_Window_Temperature(1)); + #if ENABLED(DWIN_CREALITY_LCD) && (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) { - TERN_(DWIN_CREALITY_LCD, Popup_Window_Temperature(0)); + #if ENABLED(DWIN_CREALITY_LCD) && (HAS_HOTEND || HAS_HEATED_BED) + DWIN_Popup_Temperature(0); + #endif _temp_error(heater_id, PSTR(STR_T_MINTEMP), GET_TEXT(MSG_ERR_MINTEMP)); } @@ -1055,7 +1059,7 @@ void Temperature::manage_heater() { // 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? - TERN_(DWIN_CREALITY_LCD, Popup_Window_Temperature(0)); + 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 @@ -1098,7 +1102,7 @@ void Temperature::manage_heater() { // Make sure temperature is increasing if (watch_bed.elapsed(ms)) { // Time to check the bed? if (degBed() < watch_bed.target) { // Failed to increase enough? - TERN_(DWIN_CREALITY_LCD, Popup_Window_Temperature(0)); + 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 @@ -2023,7 +2027,7 @@ void Temperature::init() { state = TRRunaway; case TRRunaway: - TERN_(DWIN_CREALITY_LCD, Popup_Window_Temperature(0)); + TERN_(DWIN_CREALITY_LCD, DWIN_Popup_Temperature(0)); _temp_error(heater_id, str_t_thermal_runaway, GET_TEXT(MSG_THERMAL_RUNAWAY)); } } @@ -2440,14 +2444,8 @@ void Temperature::tick() { #if DISABLED(SLOW_PWM_HEATERS) - #if HAS_HOTEND || HAS_HEATED_BED || HAS_HEATED_CHAMBER - constexpr uint8_t pwm_mask = - #if ENABLED(SOFT_PWM_DITHER) - _BV(SOFT_PWM_SCALE) - 1 - #else - 0 - #endif - ; + #if ANY(HAS_HOTEND, HAS_HEATED_BED, HAS_HEATED_CHAMBER, FAN_SOFT_PWM) + constexpr uint8_t pwm_mask = TERN0(SOFT_PWM_DITHER, _BV(SOFT_PWM_SCALE) - 1); #define _PWM_MOD(N,S,T) do{ \ const bool on = S.add(pwm_mask, T.soft_pwm_amount); \ WRITE_HEATER_##N(on); \ diff --git a/buildroot/share/PlatformIO/scripts/common-dependencies.h b/buildroot/share/PlatformIO/scripts/common-dependencies.h index c41027003e9e..e27e628b9a0d 100644 --- a/buildroot/share/PlatformIO/scripts/common-dependencies.h +++ b/buildroot/share/PlatformIO/scripts/common-dependencies.h @@ -89,10 +89,6 @@ #define HAS_GCODE_M876 #endif -#if PREHEAT_COUNT - #define HAS_PREHEAT_COUNT -#endif - #if EXTRUDERS #define HAS_EXTRUDERS #if EXTRUDERS > 1 diff --git a/platformio.ini b/platformio.ini index d0a4cb7b10ea..bf43936df682 100644 --- a/platformio.ini +++ b/platformio.ini @@ -153,7 +153,6 @@ default_src_filter = + - - + - - - - - - - - @@ -330,7 +329,6 @@ HOST_KEEPALIVE_FEATURE = src_filter=+ REPETIER_GCODE_M360 = src_filter=+ HAS_GCODE_M876 = src_filter=+ HAS_RESUME_CONTINUE = src_filter=+ -HAS_PREHEAT_COUNT = src_filter=+ HAS_LCD_CONTRAST = src_filter=+ LCD_SET_PROGRESS_MANUALLY = src_filter=+ TOUCH_SCREEN_CALIBRATION = src_filter=+ From 24d8daa01bfbb18b039045775f8fc7a33608d923 Mon Sep 17 00:00:00 2001 From: deram Date: Thu, 17 Sep 2020 13:41:13 +0300 Subject: [PATCH 28/44] SHOW_REMAINING_TIME for HD44780 character LCD (#19416) --- Marlin/Configuration_adv.h | 31 +++++++++++---------- Marlin/src/inc/SanityCheck.h | 6 ++-- Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp | 29 ++++++++++++++++--- 3 files changed, 44 insertions(+), 22 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index d46ba55a922e..214bf4afdda1 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1105,23 +1105,26 @@ #define BOOTSCREEN_TIMEOUT 4000 // (ms) Total Duration to display the boot screen(s) #endif -#if HAS_GRAPHICAL_LCD && EITHER(SDSUPPORT, LCD_SET_PROGRESS_MANUALLY) - //#define PRINT_PROGRESS_SHOW_DECIMALS // Show progress with decimal digits - //#define SHOW_REMAINING_TIME // Display estimated time to completion +#if EITHER(SDSUPPORT, LCD_SET_PROGRESS_MANUALLY) && (HAS_GRAPHICAL_LCD || HAS_CHARACTER_LCD) + //#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 + //#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 + + #if HAS_GRAPHICAL_LCD + //#define PRINT_PROGRESS_SHOW_DECIMALS // Show progress with decimal digits #endif -#endif -#if HAS_CHARACTER_LCD && EITHER(SDSUPPORT, LCD_SET_PROGRESS_MANUALLY) - //#define LCD_PROGRESS_BAR // Show a progress bar on HD44780 LCDs for SD printing - #if ENABLED(LCD_PROGRESS_BAR) - #define PROGRESS_BAR_BAR_TIME 2000 // (ms) Amount of time to show the bar - #define PROGRESS_BAR_MSG_TIME 3000 // (ms) Amount of time to show the status message - #define PROGRESS_MSG_EXPIRE 0 // (ms) Amount of time to retain the status message (0=forever) - //#define PROGRESS_MSG_ONCE // Show the message for MSG_TIME then clear it - //#define LCD_PROGRESS_BAR_TEST // Add a menu item to test the progress bar + #if HAS_CHARACTER_LCD + //#define LCD_PROGRESS_BAR // Show a progress bar on HD44780 LCDs for SD printing + #if ENABLED(LCD_PROGRESS_BAR) + #define PROGRESS_BAR_BAR_TIME 2000 // (ms) Amount of time to show the bar + #define PROGRESS_BAR_MSG_TIME 3000 // (ms) Amount of time to show the status message + #define PROGRESS_MSG_EXPIRE 0 // (ms) Amount of time to retain the status message (0=forever) + //#define PROGRESS_MSG_ONCE // Show the message for MSG_TIME then clear it + //#define LCD_PROGRESS_BAR_TEST // Add a menu item to test the progress bar + #endif #endif #endif diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 1ee082720d7d..9f15d7e5e3e3 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -692,8 +692,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) && NONE(HAS_GRAPHICAL_LCD, HAS_GRAPHICAL_TFT, EXTENSIBLE_UI) - #error "LCD_SET_PROGRESS_MANUALLY requires LCD_PROGRESS_BAR, Graphical LCD, TFT, or EXTENSIBLE_UI." +#elif ENABLED(LCD_SET_PROGRESS_MANUALLY) && NONE(HAS_GRAPHICAL_LCD, HAS_GRAPHICAL_TFT, HAS_CHARACTER_LCD, EXTENSIBLE_UI) + #error "LCD_SET_PROGRESS_MANUALLY requires LCD_PROGRESS_BAR, Character LCD, Graphical LCD, TFT, or EXTENSIBLE_UI." #endif #if !HAS_LCD_MENU && ENABLED(SD_REPRINT_LAST_SELECTED_FILE) @@ -3055,8 +3055,6 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #if !HAS_GRAPHICAL_LCD #if ENABLED(PRINT_PROGRESS_SHOW_DECIMALS) #error "PRINT_PROGRESS_SHOW_DECIMALS currently requires a Graphical LCD." - #elif ENABLED(SHOW_REMAINING_TIME) - #error "SHOW_REMAINING_TIME currently requires a Graphical LCD." #endif #endif diff --git a/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp b/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp index 0a1177d63ee9..3dc0925b432f 100644 --- a/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp +++ b/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp @@ -845,10 +845,31 @@ void MarlinUI::draw_status_screen() { lcd_put_wchar('%'); char buffer[14]; - duration_t elapsed = print_job_timer.duration(); - const uint8_t len = elapsed.toDigital(buffer), - timepos = LCD_WIDTH - len - 1; - lcd_put_wchar(timepos, 2, LCD_STR_CLOCK[0]); + uint8_t timepos = 0; + #if ENABLED(SHOW_REMAINING_TIME) + const bool show_remain = TERN1(ROTATE_PROGRESS_DISPLAY, blink) && (printingIsActive() || marlin_state == MF_SD_COMPLETE); + if (show_remain) { + #if ENABLED(USE_M73_REMAINING_TIME) + duration_t remaining = get_remaining_time(); + #else + uint8_t progress = get_progress_percent(); + uint32_t elapsed = print_job_timer.duration(); + duration_t remaining = (progress > 0) ? ((elapsed * 25600 / progress) >> 8) - elapsed : 0; + #endif + const uint8_t len = remaining.toDigital(buffer); + timepos = LCD_WIDTH - 1 - len; + lcd_put_wchar(timepos, 2, 'R'); + } + #else + constexpr bool show_remain = false; + #endif + + if (!show_remain) { + duration_t elapsed = print_job_timer.duration(); + const uint8_t len = elapsed.toDigital(buffer); + timepos = LCD_WIDTH - 1 - len; + lcd_put_wchar(timepos, 2, LCD_STR_CLOCK[0]); + } lcd_put_u8str(buffer); #if LCD_WIDTH >= 20 From c539254101f33b0782dca6fa7e00275e033c6ba3 Mon Sep 17 00:00:00 2001 From: Marcio Teixeira Date: Mon, 14 Sep 2020 16:32:54 -0600 Subject: [PATCH 29/44] Add warning to ExtUI Bed Mesh Screen. (#19397) - Show a warning on the Mesh Bed Leveling screen if some points aren't probed. --- .../ftdi_eve_touch_ui/language/language_en.h | 1 + .../screens/bed_mesh_screen.cpp | 27 ++++++-- .../ftdi_eve_touch_ui/screens/screen_data.h | 64 ++++++++++--------- .../lib/ftdi_eve_touch_ui/screens/screens.h | 1 + 4 files changed, 58 insertions(+), 35 deletions(-) diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/language/language_en.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/language/language_en.h index e465aa0b93a7..bd64032729fd 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/language/language_en.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/language/language_en.h @@ -145,6 +145,7 @@ namespace Language_en { PROGMEM Language_Str MSG_TOUCH_CALIBRATION_PROMPT = u8"Touch the dots to calibrate"; PROGMEM Language_Str MSG_AUTOLEVEL_X_AXIS = u8"Level X Axis"; PROGMEM Language_Str MSG_BED_MAPPING_DONE = u8"Bed mapping finished"; + PROGMEM Language_Str MSG_BED_MAPPING_INCOMPLETE = u8"Not all points probed"; PROGMEM Language_Str MSG_LEVELING = u8"Leveling"; PROGMEM Language_Str MSG_SHOW_MESH = u8"Show Bed Mesh"; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bed_mesh_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bed_mesh_screen.cpp index eea2268c5b9c..5f7c8d3b9990 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bed_mesh_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bed_mesh_screen.cpp @@ -223,7 +223,7 @@ bool BedMeshScreen::tagToPoint(uint8_t tag, uint8_t &x, uint8_t &y) { void BedMeshScreen::onEntry() { screen_data.BedMeshScreen.highlightedTag = 0; screen_data.BedMeshScreen.count = GRID_MAX_POINTS; - screen_data.BedMeshScreen.showMappingDone = false; + screen_data.BedMeshScreen.message = screen_data.BedMeshScreen.MSG_NONE; BaseScreen::onEntry(); } @@ -253,8 +253,10 @@ void BedMeshScreen::drawHighlightedPointValue() { .tag(1).button( OKAY_POS, GET_TEXT_F(MSG_BUTTON_OKAY)) .tag(0); - if (screen_data.BedMeshScreen.showMappingDone) { - cmd.text(MESSAGE_POS, GET_TEXT_F(MSG_BED_MAPPING_DONE)); + switch(screen_data.BedMeshScreen.message) { + case screen_data.BedMeshScreen.MSG_MESH_COMPLETE: cmd.text(MESSAGE_POS, GET_TEXT_F(MSG_BED_MAPPING_DONE)); break; + case screen_data.BedMeshScreen.MSG_MESH_INCOMPLETE: cmd.text(MESSAGE_POS, GET_TEXT_F(MSG_BED_MAPPING_INCOMPLETE)); break; + default: break; } } @@ -307,15 +309,30 @@ void BedMeshScreen::onMeshUpdate(const int8_t, const int8_t, const float) { onRefresh(); } +bool BedMeshScreen::isMeshComplete(ExtUI::bed_mesh_t data) { + for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++) { + for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++) { + if (isnan(data[x][y])) { + return false; + } + } + } + return true; +} + void BedMeshScreen::onMeshUpdate(const int8_t x, const int8_t y, const ExtUI::probe_state_t state) { switch(state) { case ExtUI::MESH_START: screen_data.BedMeshScreen.count = 0; - screen_data.BedMeshScreen.showMappingDone = false; + screen_data.BedMeshScreen.message = screen_data.BedMeshScreen.MSG_NONE; break; case ExtUI::MESH_FINISH: + if (screen_data.BedMeshScreen.count == GRID_MAX_POINTS && isMeshComplete(ExtUI::getMeshArray())) { + screen_data.BedMeshScreen.message = screen_data.BedMeshScreen.MSG_MESH_COMPLETE; + } else { + screen_data.BedMeshScreen.message = screen_data.BedMeshScreen.MSG_MESH_INCOMPLETE; + } screen_data.BedMeshScreen.count = GRID_MAX_POINTS; - screen_data.BedMeshScreen.showMappingDone = true; break; case ExtUI::PROBE_START: screen_data.BedMeshScreen.highlightedTag = pointToTag(x, y); diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screen_data.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screen_data.h index 39e9ce4bc568..a274fef9e747 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screen_data.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screen_data.h @@ -52,42 +52,46 @@ union screen_data_t { uint8_t num_page; uint8_t cur_page; #if ENABLED(SCROLL_LONG_FILENAMES) && (FTDI_API_LEVEL >= 810) - uint16_t scroll_pos; - uint16_t scroll_max; + uint16_t scroll_pos; + uint16_t scroll_max; #endif } FilesScreen; struct { struct base_numeric_adjustment_t placeholder; float e_rel[ExtUI::extruderCount]; } MoveAxisScreen; -#if HAS_MESH - struct { - bool showMappingDone; - uint8_t count; - uint8_t highlightedTag; - } BedMeshScreen; -#endif -#if ENABLED(TOUCH_UI_DEVELOPER_MENU) - struct { - uint32_t next_watchdog_trigger; - const char* message; - } StressTestScreen; -#endif -#if ENABLED(TOUCH_UI_COCOA_PRESS) - struct { - uint32_t start_ms; - } PreheatTimerScreen; -#endif -#if ENABLED(BABYSTEPPING) - struct { - struct base_numeric_adjustment_t placeholder; - xyz_int_t rel; - #if EXTRUDERS > 1 - bool link_nozzles; - #endif - bool show_offsets; - } NudgeNozzleScreen; -#endif + #if HAS_MESH + struct { + enum : uint8_t { + MSG_NONE, + MSG_MESH_COMPLETE, + MSG_MESH_INCOMPLETE + } message; + uint8_t count; + uint8_t highlightedTag; + } BedMeshScreen; + #endif + #if ENABLED(TOUCH_UI_DEVELOPER_MENU) + struct { + uint32_t next_watchdog_trigger; + const char* message; + } StressTestScreen; + #endif + #if ENABLED(TOUCH_UI_COCOA_PRESS) + struct { + uint32_t start_ms; + } PreheatTimerScreen; + #endif + #if ENABLED(BABYSTEPPING) + struct { + struct base_numeric_adjustment_t placeholder; + xyz_int_t rel; + #if EXTRUDERS > 1 + bool link_nozzles; + #endif + bool show_offsets; + } NudgeNozzleScreen; + #endif }; extern screen_data_t screen_data; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h index ec8df2760789..b425c4fa45fb 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h @@ -533,6 +533,7 @@ class StepsScreen : public BaseNumericAdjustmentScreen, public CachedScreen Date: Thu, 17 Sep 2020 07:52:47 -0300 Subject: [PATCH 30/44] Fix MKS UI SPI flash typo (#19410) --- Marlin/src/lcd/extui/lib/mks_ui/SPIFlashStorage.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/extui/lib/mks_ui/SPIFlashStorage.cpp b/Marlin/src/lcd/extui/lib/mks_ui/SPIFlashStorage.cpp index 9d3adc1bab93..ad116d5045df 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/SPIFlashStorage.cpp +++ b/Marlin/src/lcd/extui/lib/mks_ui/SPIFlashStorage.cpp @@ -221,7 +221,7 @@ void SPIFlashStorage::flushPage() { #if HAS_SPI_FLASH_COMPRESSION // Restart the compressed buffer, keep the pointers of the uncompressed buffer m_compressedDataUsed = 0; - #elif + #else m_pageDataUsed = 0; #endif m_currentPage++; From da1a60aeb6b1701941066d3e5a9abd62b5551526 Mon Sep 17 00:00:00 2001 From: jahartley <52391697+jahartley@users.noreply.github.com> Date: Thu, 17 Sep 2020 07:01:10 -0400 Subject: [PATCH 31/44] Expose JOYSTICK_DEBUG to the general user (#19394) Co-authored-by: Scott Lahteine --- Marlin/Configuration_adv.h | 1 + Marlin/src/feature/joystick.h | 2 -- 2 files changed, 1 insertion(+), 2 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 214bf4afdda1..35b1dcc563ef 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -3339,6 +3339,7 @@ #define JOY_X_LIMITS { 5600, 8190-100, 8190+100, 10800 } // min, deadzone start, deadzone end, max #define JOY_Y_LIMITS { 5600, 8250-100, 8250+100, 11000 } #define JOY_Z_LIMITS { 4800, 8080-100, 8080+100, 11550 } + //#define JOYSTICK_DEBUG #endif /** diff --git a/Marlin/src/feature/joystick.h b/Marlin/src/feature/joystick.h index ca46834578cc..1d25a30cc24d 100644 --- a/Marlin/src/feature/joystick.h +++ b/Marlin/src/feature/joystick.h @@ -30,8 +30,6 @@ #include "../core/macros.h" #include "../module/temperature.h" -//#define JOYSTICK_DEBUG - class Joystick { friend class Temperature; private: From 62206c03864746456f09767d4af351820b30a43a Mon Sep 17 00:00:00 2001 From: InsanityAutomation <38436470+InsanityAutomation@users.noreply.github.com> Date: Thu, 17 Sep 2020 07:36:21 -0400 Subject: [PATCH 32/44] Host Action: Start (#19398) --- Marlin/src/feature/host_actions.cpp | 3 +++ Marlin/src/feature/host_actions.h | 3 +++ Marlin/src/inc/Conditionals_adv.h | 3 +++ Marlin/src/lcd/language/language_en.h | 1 + Marlin/src/lcd/menu/menu_main.cpp | 8 ++++++++ 5 files changed, 18 insertions(+) diff --git a/Marlin/src/feature/host_actions.cpp b/Marlin/src/feature/host_actions.cpp index 9539c82b6454..30126392207d 100644 --- a/Marlin/src/feature/host_actions.cpp +++ b/Marlin/src/feature/host_actions.cpp @@ -62,6 +62,9 @@ void host_action(PGM_P const pstr, const bool eol) { #ifdef ACTION_ON_CANCEL void host_action_cancel() { host_action(PSTR(ACTION_ON_CANCEL)); } #endif +#ifdef ACTION_ON_START + void host_action_start() { host_action(PSTR(ACTION_ON_START)); } +#endif #if ENABLED(HOST_PROMPT_SUPPORT) diff --git a/Marlin/src/feature/host_actions.h b/Marlin/src/feature/host_actions.h index a6ad2c048505..09eeed23e215 100644 --- a/Marlin/src/feature/host_actions.h +++ b/Marlin/src/feature/host_actions.h @@ -44,6 +44,9 @@ void host_action(PGM_P const pstr, const bool eol=true); #ifdef ACTION_ON_CANCEL void host_action_cancel(); #endif +#ifdef ACTION_ON_START + void host_action_start(); +#endif #if ENABLED(HOST_PROMPT_SUPPORT) diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h index ff13d2897df2..73e034d05f2f 100644 --- a/Marlin/src/inc/Conditionals_adv.h +++ b/Marlin/src/inc/Conditionals_adv.h @@ -196,6 +196,9 @@ #ifndef ACTION_ON_CANCEL #define ACTION_ON_CANCEL "cancel" #endif + #ifndef ACTION_ON_START + #define ACTION_ON_START "start" + #endif #ifndef ACTION_ON_KILL #define ACTION_ON_KILL "poweroff" #endif diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index fc9e065abe0d..04c58fd22a1d 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -366,6 +366,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_STOP_PRINT = _UxGT("Stop Print"); PROGMEM Language_Str MSG_PRINTING_OBJECT = _UxGT("Printing Object"); PROGMEM Language_Str MSG_CANCEL_OBJECT = _UxGT("Cancel Object"); diff --git a/Marlin/src/lcd/menu/menu_main.cpp b/Marlin/src/lcd/menu/menu_main.cpp index 8908f49fb22f..334d998d5c6f 100644 --- a/Marlin/src/lcd/menu/menu_main.cpp +++ b/Marlin/src/lcd/menu/menu_main.cpp @@ -54,6 +54,10 @@ #include "../../feature/password/password.h" #endif +#ifdef ACTION_ON_START + #include "../../feature/host_actions.h" +#endif + void menu_tune(); void menu_cancelobject(); void menu_motion(); @@ -158,6 +162,10 @@ void menu_main() { if (TERN0(MACHINE_CAN_PAUSE, printingIsPaused())) ACTION_ITEM(MSG_RESUME_PRINT, ui.resume_print); + #ifdef ACTION_ON_START + ACTION_ITEM(MSG_HOST_START_PRINT, host_action_start); + #endif + SUBMENU(MSG_MOTION, menu_motion); } From 5b56d6698a2a9b78a5dd40446bcb606cbfff010d Mon Sep 17 00:00:00 2001 From: Victor Oliveira Date: Thu, 17 Sep 2020 08:52:21 -0300 Subject: [PATCH 33/44] Move screen for Color UI (#19386) --- .../src/lcd/tft/bitmaps/btn_64x52_rounded.bmp | Bin 0 -> 10040 bytes Marlin/src/lcd/tft/bitmaps/home.bmp | Bin 0 -> 12344 bytes .../lcd/tft/images/btn_rounded_64x52x4.cpp | 82 ++++ Marlin/src/lcd/tft/images/home_64x64x4.cpp | 94 ++++ Marlin/src/lcd/tft/tft_color.h | 10 +- Marlin/src/lcd/tft/tft_image.cpp | 2 + Marlin/src/lcd/tft/tft_image.h | 6 + Marlin/src/lcd/tft/touch.cpp | 11 + Marlin/src/lcd/tft/touch.h | 5 + Marlin/src/lcd/tft/ui_320x240.cpp | 3 + Marlin/src/lcd/tft/ui_320x240.h | 2 + Marlin/src/lcd/tft/ui_480x320.cpp | 435 ++++++++++++++++++ Marlin/src/lcd/tft/ui_480x320.h | 2 + Marlin/src/lcd/ultralcd.h | 4 + .../src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h | 12 +- 15 files changed, 662 insertions(+), 6 deletions(-) create mode 100644 Marlin/src/lcd/tft/bitmaps/btn_64x52_rounded.bmp create mode 100644 Marlin/src/lcd/tft/bitmaps/home.bmp create mode 100644 Marlin/src/lcd/tft/images/btn_rounded_64x52x4.cpp create mode 100644 Marlin/src/lcd/tft/images/home_64x64x4.cpp diff --git a/Marlin/src/lcd/tft/bitmaps/btn_64x52_rounded.bmp b/Marlin/src/lcd/tft/bitmaps/btn_64x52_rounded.bmp new file mode 100644 index 0000000000000000000000000000000000000000..04e879dbb0d8ff6406b5808f0e3cdcba32af85fb GIT binary patch literal 10040 zcmeI2OG{fp7>3jSh|)h$+8`{3Z=(1tRbAyb?WP7Gfr@bKp5=9e}B%<=JYp-`X^Spq6*ZEf{T zAfE59&HO1y*4EapudhMf*w|nTQH9_?KR+i)nXC(|LltPQ3AtT0kh0koJN0ntyGLO`m0b?eomvmyjChk8vRwM zDnF;uUtTK}BaQwlRF$98=r6C8ijhWt6{^b5`9k#9_W3zr*3;&O&!08-FaE*rbUHC* zboP&g&nxt|{3HB3k-?h86k}1axv`LhQ%}7FUDL!64B}J+V1m~2@9(`m#PC9oE_lU-e1v;&S((*q1( zK*HMvwN|TvD*S6qy;7+}^6Kh}O``Mp0S*aZ@`Ad)zHXf#5Pv(4j*iIVUvF=3W2Djo zEP*BmArK!Y9b+9lAgk3X%Cn=y`3?A4fEK_zZPUI$()k3bX@R31T4SHSfVObmiN zM7RhNo>A~3M`FT(1aA;dcpwB8O-K|Fi0&5(n@;sicTZ2x4D3<~Jyq2;e|`Voe^>qW z5AlCQ{O;H-;ao%bi{1PC$?+RChvR4N|N4vg+wI`;=+UFU4{ZVduR~t2{o&O>IF1?q zJ0^;u91}9`7z$AjFvHKJ4Gj%D0)<@+BoDd@(vYn(>kZ(WL+6$&=^LpU=w5LKI)o z0!uym{K6%|!ouR?F(~neEG685&V?X zr%z8!O_>w({mq*<7cX9v-O#2#Gm)>-Gf;a$Z6Kr)&>Oyy?XV^6|mIrFMjr~;NW0FRsuf^ zP9f|hsy}}GcxY%SL9)c@s_8HOZ{NN>e*8EsEiF4cTRE$xq@>WCpPzR{tL?YOPs~pd zF%lIE>yMViT93rP%jM*7t;BB(P!8$5cc^f1_~F5l6bN0#pWG7X>!PBf8#iw7>Kzb% zz~E<1D=aM39__I|ivwfo>gpmRBYE`*c<^4%ZX6%D>u&sG&0DnJ!he{ZRSQd|rltl4 z26DR3$jBf;Ap#QdAQ&?%F4=|oSdenCivUi+qLq&-2?x_ zhYztT>lkYnXV|5srNza?7cX9r$-y_&{2VjUZfgy*(gx~|Do{0!vFd6X9)}y7)d@v>i0pjwY8Pp{@B=b$`$;~%nYbXYD@6*AW)&8pulOWVQXuP7vEFVDX!Jbn69AD&lIfmib%1Qmqa=vZEYm-zjwLQ6{vmLDA* zb>%i%crCxbR1j{{-{0>RyiFH@wANq$8 z#j55jHu5Vfz{!S1HkBMK8NB7?WzL3VENzEpMtk{%3gl;?C0EZc4s2fJkkN>%I&Wj% z!ulg^=NHp)WZ>5j{(Fa98Oc>~g3u?icGpY%)?h4r>p#G6LF)tcmBar3^A5+qc0^VJ literal 0 HcmV?d00001 diff --git a/Marlin/src/lcd/tft/images/btn_rounded_64x52x4.cpp b/Marlin/src/lcd/tft/images/btn_rounded_64x52x4.cpp new file mode 100644 index 000000000000..69a045d85af1 --- /dev/null +++ b/Marlin/src/lcd/tft/images/btn_rounded_64x52x4.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 . + * + */ + +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_GRAPHICAL_TFT + +extern const uint8_t btn_rounded_64x52x4[1664] = { + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x88, + 0x88, 0x88, 0x79, 0xce, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xeb, 0x87, 0x77, 0x78, + 0x88, 0x78, 0xcf, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfb, 0x66, 0x78, + 0x88, 0x8d, 0xff, 0xb8, 0x54, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x45, 0x7b, 0xff, 0xc6, 0x67, + 0x87, 0xbf, 0xf7, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x6f, 0xf9, 0x56, + 0x87, 0xef, 0x84, 0x44, 0x45, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x58, 0xfd, 0x46, + 0x87, 0xff, 0x54, 0x44, 0x56, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0xff, 0x45, + 0x87, 0xff, 0x44, 0x45, 0x67, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x76, 0xff, 0x45, + 0x87, 0xff, 0x44, 0x56, 0x77, 0x77, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x77, 0x77, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x77, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x77, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xef, 0x84, 0x56, 0x77, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7a, 0xfe, 0x44, + 0x87, 0xaf, 0xf6, 0x56, 0x77, 0x77, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x77, 0x9f, 0xf9, 0x44, + 0x87, 0x7d, 0xff, 0xb8, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x78, 0x9c, 0xff, 0xd4, 0x45, + 0x87, 0x76, 0xbf, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfb, 0x54, 0x45, + 0x87, 0x76, 0x56, 0xad, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xdb, 0x64, 0x44, 0x46, + 0x87, 0x77, 0x65, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x56, + 0x88, 0x77, 0x76, 0x55, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x55, 0x67, + 0x88, 0x77, 0x77, 0x66, 0x65, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x56, 0x66, 0x78, + 0x88, 0x88, 0x77, 0x77, 0x76, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x67, 0x77, 0x78, +}; + +#endif // HAS_GRAPHICAL_TFT diff --git a/Marlin/src/lcd/tft/images/home_64x64x4.cpp b/Marlin/src/lcd/tft/images/home_64x64x4.cpp new file mode 100644 index 000000000000..107c76e54ef3 --- /dev/null +++ b/Marlin/src/lcd/tft/images/home_64x64x4.cpp @@ -0,0 +1,94 @@ +/** + * 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 . + * + */ + +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_GRAPHICAL_TFT + +extern const uint8_t home_64x64x4[2048] = { + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0x77, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x67, 0x88, 0x76, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x86, 0x9d, 0xff, 0xea, 0x67, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x69, 0xff, 0xff, 0xff, 0xc6, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x86, 0x9f, 0xff, 0xff, 0xff, 0xfc, 0x67, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x69, 0xff, 0xff, 0xff, 0xff, 0xff, 0xc6, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x86, 0x9f, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfc, 0x67, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x69, 0xff, 0xff, 0xff, 0xeb, 0xff, 0xff, 0xff, 0xc6, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x86, 0x9f, 0xff, 0xff, 0xff, 0x40, 0xbf, 0xff, 0xff, 0xfc, 0x67, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x69, 0xff, 0xff, 0xff, 0xf6, 0x54, 0xa, 0xff, 0xff, 0xff, 0xc6, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x86, 0x9f, 0xff, 0xff, 0xff, 0x57, 0xff, 0x80, 0xaf, 0xff, 0xff, 0xfc, 0x67, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x69, 0xff, 0xff, 0xff, 0xf5, 0x6f, 0xff, 0xf9, 0xa, 0xff, 0xff, 0xff, 0xc6, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x86, 0x9f, 0xff, 0xff, 0xff, 0x56, 0xff, 0xff, 0xff, 0x90, 0xaf, 0xff, 0xff, 0xfc, 0x67, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x69, 0xff, 0xff, 0xff, 0xf5, 0x6f, 0xff, 0xff, 0xff, 0xf9, 0xa, 0xff, 0xff, 0xff, 0xc6, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x86, 0x9f, 0xff, 0xff, 0xff, 0x56, 0xff, 0xff, 0xff, 0xff, 0xff, 0x90, 0xaf, 0xff, 0xff, 0xfc, 0x67, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x69, 0xff, 0xff, 0xff, 0xf5, 0x6f, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf9, 0xa, 0xff, 0xff, 0xff, 0xc6, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x86, 0x9f, 0xff, 0xff, 0xff, 0x56, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x90, 0xaf, 0xff, 0xff, 0xfc, 0x67, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x69, 0xff, 0xff, 0xff, 0xf5, 0x6f, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf9, 0xa, 0xff, 0xff, 0xff, 0xc6, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x86, 0x9f, 0xff, 0xff, 0xff, 0x56, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x90, 0xaf, 0xff, 0xff, 0xfc, 0x67, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x69, 0xff, 0xff, 0xff, 0xf5, 0x6f, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf9, 0xa, 0xff, 0xff, 0xff, 0xc6, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x86, 0x9f, 0xff, 0xff, 0xff, 0x56, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x90, 0xbf, 0xff, 0xff, 0xfc, 0x67, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x69, 0xff, 0xff, 0xff, 0xf5, 0x6f, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf9, 0xa, 0xff, 0xff, 0xff, 0xc6, 0x78, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x86, 0x9f, 0xff, 0xff, 0xff, 0x56, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x90, 0xaf, 0xff, 0xff, 0xfc, 0x67, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x69, 0xff, 0xff, 0xff, 0xf5, 0x6f, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf9, 0xa, 0xff, 0xff, 0xff, 0xc6, 0x78, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x86, 0x9f, 0xff, 0xff, 0xff, 0x56, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x90, 0xaf, 0xff, 0xff, 0xfc, 0x67, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x69, 0xff, 0xff, 0xff, 0xf5, 0x6f, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf9, 0xa, 0xff, 0xff, 0xff, 0xc6, 0x78, 0x88, 0x88, + 0x88, 0x86, 0x9f, 0xff, 0xff, 0xff, 0x56, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x90, 0xaf, 0xff, 0xff, 0xfc, 0x67, 0x88, 0x88, + 0x88, 0x69, 0xff, 0xff, 0xff, 0xf5, 0x6f, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf9, 0xb, 0xff, 0xff, 0xff, 0xc6, 0x78, 0x88, + 0x87, 0x7f, 0xff, 0xff, 0xff, 0x66, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x90, 0xbf, 0xff, 0xff, 0xfb, 0x68, 0x88, + 0x87, 0x7f, 0xff, 0xff, 0xf7, 0x3c, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf4, 0xb, 0xff, 0xff, 0xfd, 0x67, 0x88, + 0x87, 0x3d, 0xff, 0xff, 0x75, 0x59, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0x30, 0xbf, 0xff, 0xfa, 0x68, 0x88, + 0x88, 0x44, 0xce, 0xd7, 0x58, 0x49, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0x74, 0x19, 0xee, 0xa6, 0x88, 0x88, + 0x88, 0x73, 0x24, 0x56, 0x88, 0x49, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0x78, 0x52, 0x35, 0x68, 0x88, 0x88, + 0x88, 0x87, 0x66, 0x78, 0x88, 0x49, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0x78, 0x87, 0x67, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x49, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x49, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x49, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf9, 0x55, 0x55, 0x55, 0x5d, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x49, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x92, 0x44, 0x44, 0x44, 0x12, 0xef, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x49, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x77, 0x88, 0x88, 0x88, 0x72, 0xbf, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x49, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x97, 0x88, 0x88, 0x88, 0x84, 0xbf, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x49, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x96, 0x88, 0x88, 0x88, 0x84, 0xbf, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x49, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x96, 0x88, 0x88, 0x88, 0x84, 0xbf, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x49, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x96, 0x88, 0x88, 0x88, 0x84, 0xbf, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x49, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x96, 0x88, 0x88, 0x88, 0x84, 0xbf, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x49, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x96, 0x88, 0x88, 0x88, 0x84, 0xbf, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x49, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x96, 0x88, 0x88, 0x88, 0x84, 0xbf, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x49, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x96, 0x88, 0x88, 0x88, 0x84, 0xbf, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x49, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x96, 0x88, 0x88, 0x88, 0x84, 0xbf, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x49, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x96, 0x88, 0x88, 0x88, 0x84, 0xbf, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x49, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x96, 0x88, 0x88, 0x88, 0x84, 0xbf, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x49, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x96, 0x88, 0x88, 0x88, 0x84, 0xbf, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf7, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x64, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x96, 0x88, 0x88, 0x88, 0x84, 0xcf, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xb6, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x83, 0x4c, 0xee, 0xee, 0xee, 0xee, 0xee, 0xff, 0x97, 0x88, 0x88, 0x88, 0x84, 0xae, 0xee, 0xee, 0xee, 0xee, 0xee, 0xea, 0x67, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0x32, 0x44, 0x44, 0x44, 0x44, 0x33, 0x57, 0x88, 0x88, 0x88, 0x88, 0x86, 0x43, 0x34, 0x44, 0x44, 0x44, 0x34, 0x55, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x76, 0x55, 0x55, 0x55, 0x55, 0x55, 0x67, 0x88, 0x88, 0x88, 0x88, 0x87, 0x65, 0x55, 0x55, 0x55, 0x55, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88 +}; + +#endif // HAS_GRAPHICAL_TFT diff --git a/Marlin/src/lcd/tft/tft_color.h b/Marlin/src/lcd/tft/tft_color.h index d2c5d8e7db7e..14906a1bcf66 100644 --- a/Marlin/src/lcd/tft/tft_color.h +++ b/Marlin/src/lcd/tft/tft_color.h @@ -42,6 +42,7 @@ #define COLOR_SCARLET 0xF904 // #FF2020 #define COLOR_LIME 0x7E00 // #00FF00 #define COLOR_BLUE 0x001F // #0000FF +#define COLOR_LIGHT_BLUE 0x061F // #00C3FF #define COLOR_YELLOW 0xFFE0 // #FFFF00 #define COLOR_MAGENTA 0xF81F // #FF00FF #define COLOR_FUCHSIA 0xF81F // #FF00FF @@ -66,10 +67,11 @@ #define COLOR_DARK_PURPLE 0x9930 // #992380 - -#define COLOR_BACKGROUND 0x20AC // #1E156E -#define COLOR_SELECTION_BG 0x9930 // #992380 -#define COLOR_WEBSITE_URL 0x03B7 +#ifndef COLOR_BACKGROUND + #define COLOR_BACKGROUND 0x20AC // #1E156E +#endif +#define COLOR_SELECTION_BG 0x9930 // #992380 +#define COLOR_WEBSITE_URL 0x03B7 #define COLOR_INACTIVE COLOR_GREY #define COLOR_COLD COLOR_AQUA diff --git a/Marlin/src/lcd/tft/tft_image.cpp b/Marlin/src/lcd/tft/tft_image.cpp index ff60bee9a9df..27749cb7f3ae 100644 --- a/Marlin/src/lcd/tft/tft_image.cpp +++ b/Marlin/src/lcd/tft/tft_image.cpp @@ -45,6 +45,8 @@ const tImage Fan_Slow1_64x64x4 = { (void *)fan_slow1_64x64x4, 64, 64, GREYS const tImage Fan_Fast0_64x64x4 = { (void *)fan_fast0_64x64x4, 64, 64, GREYSCALE4 }; const tImage Fan_Fast1_64x64x4 = { (void *)fan_fast1_64x64x4, 64, 64, GREYSCALE4 }; const tImage SD_64x64x4 = { (void *)sd_64x64x4, 64, 64, GREYSCALE4 }; +const tImage Home_64x64x4 = { (void *)home_64x64x4, 64, 64, GREYSCALE4 }; +const tImage BtnRounded_64x52x4 = { (void *)btn_rounded_64x52x4, 64, 52, GREYSCALE4 }; const tImage Menu_64x64x4 = { (void *)menu_64x64x4, 64, 64, GREYSCALE4 }; const tImage Settings_64x64x4 = { (void *)settings_64x64x4, 64, 64, GREYSCALE4 }; const tImage Confirm_64x64x4 = { (void *)confirm_64x64x4, 64, 64, GREYSCALE4 }; diff --git a/Marlin/src/lcd/tft/tft_image.h b/Marlin/src/lcd/tft/tft_image.h index cf48065968b1..1f13967ba248 100644 --- a/Marlin/src/lcd/tft/tft_image.h +++ b/Marlin/src/lcd/tft/tft_image.h @@ -39,6 +39,8 @@ extern const uint8_t fan0_64x64x4[], fan1_64x64x4[]; extern const uint8_t fan_slow0_64x64x4[], fan_slow1_64x64x4[]; extern const uint8_t fan_fast0_64x64x4[], fan_fast1_64x64x4[]; extern const uint8_t sd_64x64x4[]; +extern const uint8_t home_64x64x4[]; +extern const uint8_t btn_rounded_64x52x4[]; extern const uint8_t menu_64x64x4[]; extern const uint8_t settings_64x64x4[]; extern const uint8_t confirm_64x64x4[]; @@ -90,6 +92,8 @@ enum MarlinImage : uint8_t { imgRefresh, imgLeveling, imgSlider, + imgHome, + imgBtn52Rounded, imgCount, noImage = imgCount, imgPageUp = imgLeft, @@ -136,6 +140,8 @@ extern const tImage Fan_Slow1_64x64x4; extern const tImage Fan_Fast0_64x64x4; extern const tImage Fan_Fast1_64x64x4; extern const tImage SD_64x64x4; +extern const tImage Home_64x64x4; +extern const tImage BtnRounded_64x52x4; extern const tImage Menu_64x64x4; extern const tImage Settings_64x64x4; extern const tImage Confirm_64x64x4; diff --git a/Marlin/src/lcd/tft/touch.cpp b/Marlin/src/lcd/tft/touch.cpp index d2b860ab155f..d19cc4bf1d95 100644 --- a/Marlin/src/lcd/tft/touch.cpp +++ b/Marlin/src/lcd/tft/touch.cpp @@ -35,6 +35,7 @@ #include "tft.h" +bool Touch::enabled = true; int16_t Touch::x, Touch::y; touch_control_t Touch::controls[]; touch_control_t *Touch::current_control; @@ -54,6 +55,7 @@ void Touch::init() { calibration_reset(); reset(); io.Init(); + enable(); } void Touch::add_control(TouchControlType type, uint16_t x, uint16_t y, uint16_t width, uint16_t height, int32_t data) { @@ -72,6 +74,8 @@ void Touch::idle() { uint16_t i; int16_t _x, _y; + if (!enabled) return; + if (now == millis()) return; now = millis(); @@ -253,6 +257,13 @@ void Touch::touch(touch_control_t *control) { case UBL: hold(control, UBL_REPEAT_DELAY); ui.encoderPosition += control->data; break; #endif + case MOVE_AXIS: + ui.goto_screen((screenFunc_t)ui.move_axis_screen); + break; + + // TODO: TOUCH could receive data to pass to the callback + case BUTTON: ((screenFunc_t)control->data)(); break; + default: break; } } diff --git a/Marlin/src/lcd/tft/touch.h b/Marlin/src/lcd/tft/touch.h index f3e53ae461c5..7d8f222918db 100644 --- a/Marlin/src/lcd/tft/touch.h +++ b/Marlin/src/lcd/tft/touch.h @@ -79,6 +79,8 @@ enum TouchControlType : uint16_t { FEEDRATE, FLOWRATE, UBL, + MOVE_AXIS, + BUTTON, }; typedef void (*screenFunc_t)(); @@ -132,6 +134,7 @@ class Touch { private: static TOUCH_DRIVER io; static int16_t x, y; + static bool enabled; static touch_control_t controls[MAX_CONTROLS]; static touch_control_t *current_control; @@ -162,6 +165,8 @@ class Touch { static void clear() { controls_count = 0; } static void idle(); static bool is_clicked() { return touch_control_type == CLICK; } + static void disable() { enabled = false; } + static void enable() { enabled = true; } static void add_control(TouchControlType type, uint16_t x, uint16_t y, uint16_t width, uint16_t height, int32_t data = 0); diff --git a/Marlin/src/lcd/tft/ui_320x240.cpp b/Marlin/src/lcd/tft/ui_320x240.cpp index a4ac1465ea25..2f4c90e17083 100644 --- a/Marlin/src/lcd/tft/ui_320x240.cpp +++ b/Marlin/src/lcd/tft/ui_320x240.cpp @@ -650,4 +650,7 @@ void menu_item(const uint8_t row, bool sel ) { TERN_(TOUCH_SCREEN, touch.add_control(sel ? CLICK : MENU_ITEM, 0, 2 + 34 * row, 320, 32, encoderTopLine + row)); } +void MarlinUI::move_axis_screen() { +} + #endif // HAS_UI_320x240 diff --git a/Marlin/src/lcd/tft/ui_320x240.h b/Marlin/src/lcd/tft/ui_320x240.h index ed69acbcd2e9..c9822f11cc69 100644 --- a/Marlin/src/lcd/tft/ui_320x240.h +++ b/Marlin/src/lcd/tft/ui_320x240.h @@ -73,6 +73,8 @@ const tImage Images[imgCount] = { Refresh_32x32x4, Leveling_32x32x4, Slider8x16x4, + Home_64x64x4, + BtnRounded_64x52x4, }; #if HAS_TEMP_CHAMBER && HOTENDS > 1 diff --git a/Marlin/src/lcd/tft/ui_480x320.cpp b/Marlin/src/lcd/tft/ui_480x320.cpp index c9f0bfd0e9b1..d6409c1dca7e 100644 --- a/Marlin/src/lcd/tft/ui_480x320.cpp +++ b/Marlin/src/lcd/tft/ui_480x320.cpp @@ -291,6 +291,7 @@ void MarlinUI::draw_status_screen() { offset += 32 - tft_string.width(); } tft.add_text(455 - tft_string.width() - offset, 3, is_homed ? COLOR_AXIS_HOMED : COLOR_AXIS_NOT_HOMED, tft_string); + TERN_(TOUCH_SCREEN, touch.add_control(MOVE_AXIS, 4, 132, TFT_WIDTH - 8, 34)); // feed rate tft.canvas(96, 180, 100, 32); @@ -654,4 +655,438 @@ void menu_item(const uint8_t row, bool sel ) { TERN_(TOUCH_SCREEN, touch.add_control(sel ? CLICK : MENU_ITEM, 0, 4 + 45 * row, TFT_WIDTH, 43, encoderTopLine + row)); } +#if ENABLED(BABYSTEP_ZPROBE_OFFSET) + #include "../../feature/babystep.h" +#endif + +#if HAS_BED_PROBE + #include "../../module/probe.h" +#endif + +#define Z_SELECTION_Z 1 +#define Z_SELECTION_Z_PROBE -1 + +struct MotionAxisState { + xy_int_t xValuePos, yValuePos, zValuePos, eValuePos, stepValuePos, zTypePos, eNamePos; + float currentStepSize = 10.0; + int z_selection = Z_SELECTION_Z; + uint8_t e_selection = 0; + bool homming = false; + bool blocked = false; + char message[32]; +}; + +MotionAxisState motionAxisState; + +#define E_BTN_COLOR COLOR_YELLOW +#define X_BTN_COLOR COLOR_CORAL_RED +#define Y_BTN_COLOR COLOR_VIVID_GREEN +#define Z_BTN_COLOR COLOR_LIGHT_BLUE + +#define BTN_WIDTH 64 +#define BTN_HEIGHT 52 +#define X_MARGIN 20 +#define Y_MARGIN 15 + +static void quick_feedback() { + #if HAS_CHIRP + ui.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 +} + +#define CUR_STEP_VALUE_WIDTH 104 +static void drawCurStepValue() { + tft_string.set((uint8_t *)ftostr52sp(motionAxisState.currentStepSize)); + tft_string.add("mm"); + tft.canvas(motionAxisState.stepValuePos.x, motionAxisState.stepValuePos.y, CUR_STEP_VALUE_WIDTH, BTN_HEIGHT); + tft.set_background(COLOR_BACKGROUND); + tft.add_text(tft_string.center(CUR_STEP_VALUE_WIDTH), 0, COLOR_AXIS_HOMED, tft_string); +} + +static void drawCurZSelection() { + tft_string.set("Z"); + tft.canvas(motionAxisState.zTypePos.x, motionAxisState.zTypePos.y, tft_string.width(), 34); + tft.set_background(COLOR_BACKGROUND); + tft.add_text(0, 0, Z_BTN_COLOR, tft_string); + tft.queue.sync(); + tft_string.set("Offset"); + tft.canvas(motionAxisState.zTypePos.x, motionAxisState.zTypePos.y + 34, tft_string.width(), 34); + tft.set_background(COLOR_BACKGROUND); + if (motionAxisState.z_selection == Z_SELECTION_Z_PROBE) { + tft.add_text(0, 0, Z_BTN_COLOR, tft_string); + } +} + +static void drawCurESelection() { + tft.canvas(motionAxisState.eNamePos.x, motionAxisState.eNamePos.y, BTN_WIDTH, BTN_HEIGHT); + tft.set_background(COLOR_BACKGROUND); + tft_string.set("E"); + tft.add_text(0, 0, E_BTN_COLOR , tft_string); + tft.add_text(tft_string.width(), 0, E_BTN_COLOR, ui8tostr3rj(motionAxisState.e_selection)); +} + +static void drawMessage(const char *msg) { + tft.canvas(X_MARGIN, TFT_HEIGHT - Y_MARGIN - 34, TFT_HEIGHT / 2, 34); + tft.set_background(COLOR_BACKGROUND); + tft.add_text(0, 0, COLOR_YELLOW, msg); +} + +static void drawAxisValue(AxisEnum axis) { + const float value = + #if HAS_BED_PROBE + axis == Z_AXIS && motionAxisState.z_selection == Z_SELECTION_Z_PROBE ? + probe.offset.z : + #endif + NATIVE_TO_LOGICAL( + ui.manual_move.processing ? destination[axis] : current_position[axis] + TERN0(IS_KINEMATIC, ui.manual_move.offset), + axis + ); + xy_int_t pos; + uint16_t color; + switch (axis) { + case X_AXIS: pos = motionAxisState.xValuePos; color = X_BTN_COLOR; break; + case Y_AXIS: pos = motionAxisState.yValuePos; color = Y_BTN_COLOR; break; + case Z_AXIS: pos = motionAxisState.zValuePos; color = Z_BTN_COLOR; break; + case E_AXIS: pos = motionAxisState.eValuePos; color = E_BTN_COLOR; break; + default: return; + } + tft.canvas(pos.x, pos.y, BTN_WIDTH + X_MARGIN, BTN_HEIGHT); + tft.set_background(COLOR_BACKGROUND); + tft_string.set(ftostr52sp(value)); + tft.add_text(0, 0, color, tft_string); +} + +static void moveAxis(AxisEnum axis, const int8_t direction) { + quick_feedback(); + + if (axis == E_AXIS && thermalManager.temp_hotend[motionAxisState.e_selection].celsius < EXTRUDE_MINTEMP) { + drawMessage("Too cold"); + return; + } + + const float diff = motionAxisState.currentStepSize * direction; + + if (axis == Z_AXIS && motionAxisState.z_selection == Z_SELECTION_Z_PROBE) { + #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, + 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 + , new_probe_offset + ); + if (WITHIN(new_offs, Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX)) { + babystep.add_steps(Z_AXIS, babystep_increment); + if (do_probe) + probe.offset.z = new_offs; + else + TERN(BABYSTEP_HOTEND_Z_OFFSET, hotend_offset[active_extruder].z = new_offs, NOOP); + drawMessage(""); // clear the error + drawAxisValue(axis); + } + else { + drawMessage(GET_TEXT(MSG_LCD_SOFT_ENDSTOPS)); + } + #elif HAS_BED_PROBE + // only change probe.offset.z + probe.offset.z += diff; + if (direction < 0 && current_position[axis] < Z_PROBE_OFFSET_RANGE_MIN) { + current_position[axis] = Z_PROBE_OFFSET_RANGE_MIN; + drawMessage(GET_TEXT(MSG_LCD_SOFT_ENDSTOPS)); + } + else if (direction > 0 && current_position[axis] > Z_PROBE_OFFSET_RANGE_MAX) { + current_position[axis] = Z_PROBE_OFFSET_RANGE_MAX; + drawMessage(GET_TEXT(MSG_LCD_SOFT_ENDSTOPS)); + } + else { + drawMessage(""); // clear the error + } + drawAxisValue(axis); + #endif + return; + } + + if (!ui.manual_move.processing) { + // Start with no limits to movement + float min = current_position[axis] - 1000, + max = current_position[axis] + 1000; + + // Limit to software endstops, if enabled + #if HAS_SOFTWARE_ENDSTOPS + if (soft_endstops_enabled) switch (axis) { + case X_AXIS: + TERN_(MIN_SOFTWARE_ENDSTOP_X, min = soft_endstop.min.x); + TERN_(MAX_SOFTWARE_ENDSTOP_X, max = soft_endstop.max.x); + break; + case Y_AXIS: + TERN_(MIN_SOFTWARE_ENDSTOP_Y, min = soft_endstop.min.y); + TERN_(MAX_SOFTWARE_ENDSTOP_Y, max = soft_endstop.max.y); + break; + case Z_AXIS: + TERN_(MIN_SOFTWARE_ENDSTOP_Z, min = soft_endstop.min.z); + TERN_(MAX_SOFTWARE_ENDSTOP_Z, max = soft_endstop.max.z); + default: break; + } + #endif // HAS_SOFTWARE_ENDSTOPS + + // Delta limits XY based on the current offset from center + // This assumes the center is 0,0 + #if ENABLED(DELTA) + if (axis != Z_AXIS && axis != E_AXIS) { + max = SQRT(sq((float)(DELTA_PRINTABLE_RADIUS)) - sq(current_position[Y_AXIS - axis])); // (Y_AXIS - axis) == the other axis + min = -max; + } + #endif + + // Get the new position + #if IS_KINEMATIC + ui.manual_move.offset += diff; + if (direction < 0) + NOLESS(ui.manual_move.offset, min - current_position[axis]); + else + NOMORE(ui.manual_move.offset, max - current_position[axis]); + #else + current_position[axis] += diff; + if (direction < 0 && current_position[axis] < min) { + current_position[axis] = min; + drawMessage(GET_TEXT(MSG_LCD_SOFT_ENDSTOPS)); + } + else if (direction > 0 && current_position[axis] > max) { + current_position[axis] = max; + drawMessage(GET_TEXT(MSG_LCD_SOFT_ENDSTOPS)); + } + else { + drawMessage(""); // clear the error + } + #endif + + ui.manual_move.soon(axis + #if MULTI_MANUAL + , motionAxisState.e_selection + #endif + ); + } + + drawAxisValue(axis); +} + +static void e_plus() { + moveAxis(E_AXIS, 1); +} + +static void e_minus() { + moveAxis(E_AXIS, -1); +} + +static void x_minus() { + moveAxis(X_AXIS, -1); +} + +static void x_plus() { + moveAxis(X_AXIS, 1); +} + +static void y_plus() { + moveAxis(Y_AXIS, 1); +} + +static void y_minus() { + moveAxis(Y_AXIS, -1); +} + +static void z_plus() { + moveAxis(Z_AXIS, 1); +} + +static void z_minus() { + moveAxis(Z_AXIS, -1); +} + +static void e_select() { + motionAxisState.e_selection++; + if (motionAxisState.e_selection >= EXTRUDERS) { + motionAxisState.e_selection = 0; + } + + quick_feedback(); + drawCurESelection(); + drawAxisValue(E_AXIS); +} + +static void do_home() { + quick_feedback(); + drawMessage(GET_TEXT(MSG_LEVEL_BED_HOMING)); + queue.inject_P(G28_STR); + // Disable touch until home is done + touch.disable(); + drawAxisValue(E_AXIS); + drawAxisValue(X_AXIS); + drawAxisValue(Y_AXIS); + drawAxisValue(Z_AXIS); +} + +static void step_size() { + motionAxisState.currentStepSize = motionAxisState.currentStepSize / 10.0; + if (motionAxisState.currentStepSize < 0.0015) motionAxisState.currentStepSize = 10.0; + quick_feedback(); + drawCurStepValue(); +} + +#if HAS_BED_PROBE + static void z_select() { + motionAxisState.z_selection *= -1; + quick_feedback(); + drawCurZSelection(); + drawAxisValue(Z_AXIS); + } +#endif + +static void disable_steppers() { + quick_feedback(); + queue.inject_P(PSTR("M84")); +} + +static void drawBtn(int x, int y, const char* label, int32_t data, MarlinImage img, uint16_t bgColor, bool enabled = true) { + uint16_t width = Images[imgBtn52Rounded].width; + uint16_t height = Images[imgBtn52Rounded].height; + + tft.queue.sync(); //need sync to change font + + if (!enabled) bgColor = COLOR_CONTROL_DISABLED; + + tft.canvas(x, y, width, height); + tft.set_background(COLOR_BACKGROUND); + tft.add_image(0, 0, imgBtn52Rounded, bgColor, COLOR_BACKGROUND, COLOR_DARKGREY); + + if (label != NULL) { + tft.set_font(Helvetica12Bold); + tft_string.set_font(Helvetica12Bold); + tft_string.set(label); + tft_string.trim(); + tft.add_text(tft_string.center(width), height / 2 - tft_string.font_height() / 2, bgColor, tft_string); + + tft.queue.sync(); + tft_string.set_font(Helvetica18); + tft.set_font(Helvetica18); + } + else { + tft.add_image(0, 0, img, bgColor, COLOR_BACKGROUND, COLOR_DARKGREY); + } + + if (enabled) touch.add_control(BUTTON, x, y, width, height, data); +} + +void MarlinUI::move_axis_screen() { + // Reset + motionAxisState.blocked = false; + touch.enable(); + + ui.clear_lcd(); + + TERN_(TOUCH_SCREEN, touch.clear()); + + const bool busy = printingIsActive(); + + // if we have baby step and we are printing, select baby step + if (busy && ENABLED(BABYSTEP_ZPROBE_OFFSET)) motionAxisState.z_selection = Z_SELECTION_Z_PROBE; + + // ROW 1 -> E- Y- CurY Z+ + int x = X_MARGIN, y = Y_MARGIN, spacing = 0; + + drawBtn(x, y, "E+", (int32_t)e_plus, imgUp, E_BTN_COLOR, !busy); + + spacing = (TFT_WIDTH - X_MARGIN * 2 - 3 * BTN_WIDTH) / 2; + x += BTN_WIDTH + spacing; + drawBtn(x, y, "Y+", (int32_t)y_plus, imgUp, Y_BTN_COLOR, !busy); + + // Cur Y + x += BTN_WIDTH; + motionAxisState.yValuePos.x = x + 2; + motionAxisState.yValuePos.y = y; + drawAxisValue(Y_AXIS); + + x += spacing; + drawBtn(x, y, "Z+", (int32_t)z_plus, imgUp, Z_BTN_COLOR, !busy || ENABLED(BABYSTEP_ZPROBE_OFFSET)); //only enabled when not busy or have baby step + + // ROW 2 -> "Ex" X- HOME X+ "Z" + y += BTN_HEIGHT + (TFT_HEIGHT - Y_MARGIN * 2 - 4 * BTN_HEIGHT) / 3; + x = X_MARGIN; + spacing = (TFT_WIDTH - X_MARGIN * 2 - 5 * BTN_WIDTH) / 4; + + motionAxisState.eNamePos.x = x; + motionAxisState.eNamePos.y = y; + drawCurESelection(); + if (!busy) touch.add_control(BUTTON, x, y, BTN_WIDTH, BTN_HEIGHT, (int32_t)e_select); + + x += BTN_WIDTH + spacing; + drawBtn(x, y, "X-", (int32_t)x_minus, imgLeft, X_BTN_COLOR, !busy); + + x += BTN_WIDTH + spacing; //imgHome is 64x64 + add_control(TFT_WIDTH / 2 - Images[imgHome].width / 2, y - (Images[imgHome].width - BTN_HEIGHT) / 2, BUTTON, (int32_t)do_home, imgHome, !busy); + + x += BTN_WIDTH + spacing; + uint16_t xplus_x = x; + drawBtn(x, y, "X+", (int32_t)x_plus, imgRight, X_BTN_COLOR, !busy); + + x += BTN_WIDTH + spacing; + motionAxisState.zTypePos.x = x; + motionAxisState.zTypePos.y = y; + drawCurZSelection(); + #if HAS_BED_PROBE + if (!busy) touch.add_control(BUTTON, x, y, BTN_WIDTH, 34 * 2, (int32_t)z_select); + #endif + + // ROW 3 -> E- CurX Y- Z- + y += BTN_HEIGHT + (TFT_HEIGHT - Y_MARGIN * 2 - 4 * BTN_HEIGHT) / 3; + x = X_MARGIN; + spacing = (TFT_WIDTH - X_MARGIN * 2 - 3 * BTN_WIDTH) / 2; + + drawBtn(x, y, "E-", (int32_t)e_minus, imgDown, E_BTN_COLOR, !busy); + + // Cur E + motionAxisState.eValuePos.x = x; + motionAxisState.eValuePos.y = y + BTN_HEIGHT + 2; + drawAxisValue(E_AXIS); + + // Cur X + motionAxisState.xValuePos.x = BTN_WIDTH + (TFT_WIDTH - X_MARGIN * 2 - 5 * BTN_WIDTH) / 4; //X- pos + motionAxisState.xValuePos.y = y - 10; + drawAxisValue(X_AXIS); + + x += BTN_WIDTH + spacing; + drawBtn(x, y, "Y-", (int32_t)y_minus, imgDown, Y_BTN_COLOR, !busy); + + x += BTN_WIDTH + spacing; + drawBtn(x, y, "Z-", (int32_t)z_minus, imgDown, Z_BTN_COLOR, !busy || ENABLED(BABYSTEP_ZPROBE_OFFSET)); //only enabled when not busy or have baby step + + // Cur Z + motionAxisState.zValuePos.x = x; + motionAxisState.zValuePos.y = y + BTN_HEIGHT + 2; + drawAxisValue(Z_AXIS); + + // ROW 4 -> step_size disable steppers back + y = TFT_HEIGHT - Y_MARGIN - 32; // + x = TFT_WIDTH / 2 - CUR_STEP_VALUE_WIDTH / 2; + motionAxisState.stepValuePos.x = x; + motionAxisState.stepValuePos.y = y; + if (!busy) { + drawCurStepValue(); + touch.add_control(BUTTON, motionAxisState.stepValuePos.x, motionAxisState.stepValuePos.y, CUR_STEP_VALUE_WIDTH, BTN_HEIGHT, (int32_t)step_size); + } + + // alinged with x+ + drawBtn(xplus_x, TFT_HEIGHT - Y_MARGIN - BTN_HEIGHT, "off", (int32_t)disable_steppers, imgCancel, COLOR_WHITE, !busy); + + add_control(TFT_WIDTH - X_MARGIN - BTN_WIDTH, y, BACK, imgBack); +} + +#undef BTN_WIDTH +#undef BTN_HEIGHT + #endif // HAS_UI_480x320 diff --git a/Marlin/src/lcd/tft/ui_480x320.h b/Marlin/src/lcd/tft/ui_480x320.h index d803df4a247d..053ee78158cb 100644 --- a/Marlin/src/lcd/tft/ui_480x320.h +++ b/Marlin/src/lcd/tft/ui_480x320.h @@ -73,6 +73,8 @@ const tImage Images[imgCount] = { Refresh_32x32x4, Leveling_32x32x4, Slider8x16x4, + Home_64x64x4, + BtnRounded_64x52x4, }; #if HAS_TEMP_CHAMBER && HOTENDS > 1 diff --git a/Marlin/src/lcd/ultralcd.h b/Marlin/src/lcd/ultralcd.h index ee7f50dabf72..59e7cbe7d1ce 100644 --- a/Marlin/src/lcd/ultralcd.h +++ b/Marlin/src/lcd/ultralcd.h @@ -682,6 +682,10 @@ class MarlinUI { static void touch_calibration(); #endif + #if HAS_GRAPHICAL_TFT + static void move_axis_screen(); + #endif + private: #if HAS_DISPLAY 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 1295c7c46b12..f9652f39348b 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h @@ -325,13 +325,21 @@ #define LCD_PINS_RS PC6 #elif ENABLED(TFT_480x320_SPI) + #ifndef XPT2046_X_CALIBRATION #define XPT2046_X_CALIBRATION -17253 + #endif + #ifndef XPT2046_Y_CALIBRATION #define XPT2046_Y_CALIBRATION 11579 + #endif + #ifndef XPT2046_X_OFFSET #define XPT2046_X_OFFSET 514 + #endif + #ifndef XPT2046_Y_OFFSET #define XPT2046_Y_OFFSET -24 + #endif - #define TFT_DRIVER ST7796 - #define TFT_BUFFER_SIZE 14400 + #define TFT_DRIVER ST7796 + #define TFT_BUFFER_SIZE 14400 #endif From 648269e0ec02887d353ec972359cbf30fd72ebbe Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 18 Sep 2020 00:13:20 +0000 Subject: [PATCH 34/44] [cron] Bump distribution date (2020-09-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 0ae661f1b18e..ed8314a3a5fd 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-09-17" + #define STRING_DISTRIBUTION_DATE "2020-09-18" #endif /** From 55ba5044ef493e2651c5a34951d6c0973aab9e1b Mon Sep 17 00:00:00 2001 From: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com> Date: Fri, 18 Sep 2020 02:45:56 -0700 Subject: [PATCH 35/44] Fix missing include (#19418) Co-authored-by: ellensp <530024+ellensp@users.noreply.github.com> --- Marlin/src/gcode/bedlevel/G35.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/Marlin/src/gcode/bedlevel/G35.cpp b/Marlin/src/gcode/bedlevel/G35.cpp index 7595067dbf85..926e6e82c535 100755 --- a/Marlin/src/gcode/bedlevel/G35.cpp +++ b/Marlin/src/gcode/bedlevel/G35.cpp @@ -29,6 +29,10 @@ #include "../../module/probe.h" #include "../../feature/bedlevel/bedlevel.h" +#if HAS_MULTI_HOTEND + #include "../../module/tool_change.h" +#endif + #define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE) #include "../../core/debug_out.h" From e65deacabb4ada7dd13c6e5edfeb207e80f2a3f6 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 19 Sep 2020 00:13:10 +0000 Subject: [PATCH 36/44] [cron] Bump distribution date (2020-09-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 ed8314a3a5fd..0faa1f8b28e4 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-09-18" + #define STRING_DISTRIBUTION_DATE "2020-09-19" #endif /** From 4628f0e237d452a7c6633c3d6127a460b3bb477b Mon Sep 17 00:00:00 2001 From: Cole Markham Date: Sat, 19 Sep 2020 08:14:34 -0500 Subject: [PATCH 37/44] Fix CoreXY compile with backlash cal. (#19422) --- Marlin/src/gcode/calibrate/M425.cpp | 2 +- Marlin/src/inc/Conditionals_post.h | 5 +---- Marlin/src/lcd/menu/menu_backlash.cpp | 2 +- 3 files changed, 3 insertions(+), 6 deletions(-) diff --git a/Marlin/src/gcode/calibrate/M425.cpp b/Marlin/src/gcode/calibrate/M425.cpp index 3e54186a5fa3..40441ac08d16 100644 --- a/Marlin/src/gcode/calibrate/M425.cpp +++ b/Marlin/src/gcode/calibrate/M425.cpp @@ -56,7 +56,7 @@ void GcodeSuite::M425() { }; LOOP_XYZ(a) { - if (AXIS_CAN_CALIBRATE(a) && parser.seen(XYZ_CHAR(a))) { + if (axis_can_calibrate(a) && parser.seen(XYZ_CHAR(a))) { planner.synchronize(); backlash.distance_mm[a] = parser.has_value() ? parser.value_linear_units() : backlash.get_measurement(AxisEnum(a)); noArgs = false; diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 71ae4bb28539..2b232623a33b 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -159,10 +159,7 @@ // Calibration codes only for non-core axes #if EITHER(BACKLASH_GCODE, CALIBRATION_GCODE) #if EITHER(IS_CORE, MARKFORGED_XY) - #define X_AXIS_INDEX 0 - #define Y_AXIS_INDEX 1 - #define Z_AXIS_INDEX 2 - #define CAN_CALIBRATE(A,B) (A##_AXIS_INDEX == B##_INDEX) + #define CAN_CALIBRATE(A,B) (_AXIS(A) == B) #else #define CAN_CALIBRATE(A,B) 1 #endif diff --git a/Marlin/src/lcd/menu/menu_backlash.cpp b/Marlin/src/lcd/menu/menu_backlash.cpp index 0e1bfb591099..9d0b970ae1d3 100644 --- a/Marlin/src/lcd/menu/menu_backlash.cpp +++ b/Marlin/src/lcd/menu/menu_backlash.cpp @@ -50,4 +50,4 @@ void menu_backlash() { END_MENU(); } -#endif // HAS_LCD_MENU && BACKLASH_COMPENSATION +#endif // HAS_LCD_MENU && BACKLASH_GCODE From 435e1535cc6f3b06d82a62cbb2697281f7cedbc8 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 19 Sep 2020 07:56:01 -0500 Subject: [PATCH 38/44] Change some dwin defines --- Marlin/src/lcd/dwin/e3v2/dwin.cpp | 446 +++++++++++++++--------------- Marlin/src/lcd/dwin/e3v2/dwin.h | 18 +- 2 files changed, 232 insertions(+), 232 deletions(-) diff --git a/Marlin/src/lcd/dwin/e3v2/dwin.cpp b/Marlin/src/lcd/dwin/e3v2/dwin.cpp index d45511f5bc84..ca3a5cccffc6 100644 --- a/Marlin/src/lcd/dwin/e3v2/dwin.cpp +++ b/Marlin/src/lcd/dwin/e3v2/dwin.cpp @@ -99,9 +99,9 @@ #define USE_STRING_HEADINGS -#define MENU_FONT font8x16 -#define STAT_FONT font10x20 -#define HEADER_FONT font10x20 +#define DWIN_FONT_MENU font8x16 +#define DWIN_FONT_STAT font10x20 +#define DWIN_FONT_HEAD font10x20 #define MENU_CHAR_LIMIT 24 #define STATUS_Y 360 @@ -229,19 +229,19 @@ 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, White, bColor, x - 6, y, F("-")); - DWIN_Draw_FloatValue(true, true, 0, size, White, bColor, iNum, fNum, x, y, -value); + DWIN_Draw_String(false, 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, White, bColor, x - 6, y, F(" ")); - DWIN_Draw_FloatValue(true, true, 0, size, White, bColor, iNum, fNum, x, y, value); + DWIN_Draw_String(false, true, size, Color_White, bColor, x - 6, y, F(" ")); + DWIN_Draw_FloatValue(true, true, 0, size, Color_White, bColor, iNum, fNum, x, y, value); } } void ICON_Print() { if (select_page.now == 0) { DWIN_ICON_Show(ICON, ICON_Print_1, 17, 130); - DWIN_Draw_Rectangle(0, White, 17, 130, 126, 229); + DWIN_Draw_Rectangle(0, Color_White, 17, 130, 126, 229); if (HMI_flag.language_chinese) DWIN_Frame_AreaCopy(1, 1, 447, 28, 460, 58, 201); else @@ -259,7 +259,7 @@ void ICON_Print() { void ICON_Prepare() { if (select_page.now == 1) { DWIN_ICON_Show(ICON, ICON_Prepare_1, 145, 130); - DWIN_Draw_Rectangle(0, White, 145, 130, 254, 229); + DWIN_Draw_Rectangle(0, Color_White, 145, 130, 254, 229); if (HMI_flag.language_chinese) DWIN_Frame_AreaCopy(1, 31, 447, 58, 460, 186, 201); else @@ -277,7 +277,7 @@ void ICON_Prepare() { void ICON_Control() { if (select_page.now == 2) { DWIN_ICON_Show(ICON, ICON_Control_1, 17, 246); - DWIN_Draw_Rectangle(0, White, 17, 246, 126, 345); + DWIN_Draw_Rectangle(0, Color_White, 17, 246, 126, 345); if (HMI_flag.language_chinese) DWIN_Frame_AreaCopy(1, 61, 447, 88, 460, 58, 318); else @@ -295,7 +295,7 @@ void ICON_Control() { void ICON_StartInfo(bool show) { if (show) { DWIN_ICON_Show(ICON, ICON_Info_1, 145, 246); - DWIN_Draw_Rectangle(0, White, 145, 246, 254, 345); + DWIN_Draw_Rectangle(0, Color_White, 145, 246, 254, 345); if (HMI_flag.language_chinese) DWIN_Frame_AreaCopy(1, 91, 447, 118, 460, 186, 318); else @@ -313,7 +313,7 @@ void ICON_StartInfo(bool show) { void ICON_Leveling(bool show) { if (show) { DWIN_ICON_Show(ICON, ICON_Leveling_1, 145, 246); - DWIN_Draw_Rectangle(0, White, 145, 246, 254, 345); + DWIN_Draw_Rectangle(0, Color_White, 145, 246, 254, 345); if (HMI_flag.language_chinese) DWIN_Frame_AreaCopy(1, 211, 447, 238, 460, 186, 318); else @@ -331,7 +331,7 @@ void ICON_Leveling(bool show) { void ICON_Tune() { if (select_print.now == 0) { DWIN_ICON_Show(ICON, ICON_Setup_1, 8, 252); - DWIN_Draw_Rectangle(0, White, 8, 252, 87, 351); + DWIN_Draw_Rectangle(0, Color_White, 8, 252, 87, 351); if (HMI_flag.language_chinese) DWIN_Frame_AreaCopy(1, 121, 447, 148, 458, 34, 325); else @@ -349,7 +349,7 @@ void ICON_Tune() { void ICON_Pause() { if (select_print.now == 1) { DWIN_ICON_Show(ICON, ICON_Pause_1, 96, 252); - DWIN_Draw_Rectangle(0, White, 96, 252, 175, 351); + DWIN_Draw_Rectangle(0, Color_White, 96, 252, 175, 351); if (HMI_flag.language_chinese) DWIN_Frame_AreaCopy(1, 181, 447, 208, 459, 124, 325); else @@ -367,7 +367,7 @@ void ICON_Pause() { void ICON_Continue() { if (select_print.now == 1) { DWIN_ICON_Show(ICON, ICON_Continue_1, 96, 252); - DWIN_Draw_Rectangle(0, White, 96, 252, 175, 351); + DWIN_Draw_Rectangle(0, Color_White, 96, 252, 175, 351); if (HMI_flag.language_chinese) DWIN_Frame_AreaCopy(1, 1, 447, 28, 460, 124, 325); else @@ -385,7 +385,7 @@ void ICON_Continue() { void ICON_Stop() { if (select_print.now == 2) { DWIN_ICON_Show(ICON, ICON_Stop_1, 184, 252); - DWIN_Draw_Rectangle(0, White, 184, 252, 263, 351); + DWIN_Draw_Rectangle(0, Color_White, 184, 252, 263, 351); if (HMI_flag.language_chinese) DWIN_Frame_AreaCopy(1, 151, 447, 178, 459, 210, 325); else @@ -401,19 +401,19 @@ void ICON_Stop() { } inline void Clear_Title_Bar() { - DWIN_Draw_Rectangle(1, Background_blue, 0, 0, DWIN_WIDTH, 30); + DWIN_Draw_Rectangle(1, Color_Bg_Blue, 0, 0, DWIN_WIDTH, 30); } inline void Draw_Title(const char * const title) { - DWIN_Draw_String(false, false, HEADER_FONT, White, Background_blue, 14, 4, (char*)title); + DWIN_Draw_String(false, false, DWIN_FONT_HEAD, Color_White, Color_Bg_Blue, 14, 4, (char*)title); } inline void Draw_Title(const __FlashStringHelper * title) { - DWIN_Draw_String(false, false, HEADER_FONT, White, Background_blue, 14, 4, (char*)title); + DWIN_Draw_String(false, false, DWIN_FONT_HEAD, Color_White, Color_Bg_Blue, 14, 4, (char*)title); } inline void Clear_Menu_Area() { - DWIN_Draw_Rectangle(1, Background_black, 0, 31, DWIN_WIDTH, STATUS_Y); + DWIN_Draw_Rectangle(1, Color_Bg_Black, 0, 31, DWIN_WIDTH, STATUS_Y); } inline void Clear_Main_Window() { @@ -423,11 +423,11 @@ inline void Clear_Main_Window() { inline void Clear_Popup_Area() { Clear_Title_Bar(); - DWIN_Draw_Rectangle(1, Background_black, 0, 31, DWIN_WIDTH, DWIN_HEIGHT); + DWIN_Draw_Rectangle(1, Color_Bg_Black, 0, 31, DWIN_WIDTH, DWIN_HEIGHT); } void Draw_Popup_Bkgd_105() { - DWIN_Draw_Rectangle(1, Background_window, 14, 105, 258, 374); + DWIN_Draw_Rectangle(1, Color_Bg_Window, 14, 105, 258, 374); } inline void Draw_More_Icon(const uint8_t line) { @@ -440,7 +440,7 @@ inline void Draw_Menu_Cursor(const uint8_t line) { } inline void Erase_Menu_Cursor(const uint8_t line) { - DWIN_Draw_Rectangle(1, Background_black, 0, MBASE(line) - 18, 14, MBASE(line + 1) - 20); + DWIN_Draw_Rectangle(1, Color_Bg_Black, 0, MBASE(line) - 18, 14, MBASE(line + 1) - 20); } inline void Move_Highlight(const int16_t from, const uint16_t newline) { @@ -454,7 +454,7 @@ inline void Add_Menu_Line() { } inline void Scroll_Menu(const uint8_t dir) { - DWIN_Frame_AreaMove(1, dir, MLINE, Background_black, 0, 31, DWIN_WIDTH, 349); + DWIN_Frame_AreaMove(1, dir, MLINE, Color_Bg_Black, 0, 31, DWIN_WIDTH, 349); switch (dir) { case DWIN_SCROLL_DOWN: Move_Highlight(-1, 0); break; case DWIN_SCROLL_UP: Add_Menu_Line(); break; @@ -470,11 +470,11 @@ inline void Draw_Menu_Icon(const uint8_t line, const uint8_t icon) { } inline void Erase_Menu_Text(const uint8_t line) { - DWIN_Draw_Rectangle(1, Background_black, LBLX, MBASE(line) - 14, 271, MBASE(line) + 28); + DWIN_Draw_Rectangle(1, Color_Bg_Black, LBLX, MBASE(line) - 14, 271, MBASE(line) + 28); } inline void Draw_Menu_Line(const uint8_t line, const uint8_t icon=0, const char * const label=nullptr) { - if (label) DWIN_Draw_String(false, false, font8x16, White, Background_black, LBLX, MBASE(line) - 1, (char*)label); + if (label) DWIN_Draw_String(false, false, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(line) - 1, (char*)label); if (icon) Draw_Menu_Icon(line, icon); DWIN_Draw_Line(Line_Color, 16, MBASE(line) + 33, 256, MBASE(line) + 34); } @@ -583,7 +583,7 @@ inline void Item_Prepare_Home(const uint8_t row) { if (HMI_flag.language_chinese) { #if HAS_BED_PROBE DWIN_Frame_AreaCopy(1, 174, 164, 223, 177, LBLX, MBASE(row)); - DWIN_Draw_Signed_Float(font8x16, Background_black, 2, 2, 202, MBASE(row), BABY_Z_VAR * 100); + DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 2, 2, 202, MBASE(row), BABY_Z_VAR * 100); #else DWIN_Frame_AreaCopy(1, 43, 89, 98, 101, LBLX, MBASE(row)); #endif @@ -591,7 +591,7 @@ inline void Item_Prepare_Home(const uint8_t row) { else { #if HAS_BED_PROBE DWIN_Frame_AreaCopy(1, 93, 179, 141, 189, LBLX, MBASE(row)); // "Z-Offset" - DWIN_Draw_Signed_Float(font8x16, Background_black, 2, 2, 202, MBASE(row), BABY_Z_VAR * 100); + DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 2, 2, 202, MBASE(row), BABY_Z_VAR * 100); #else DWIN_Frame_AreaCopy(1, 1, 76, 106, 86, LBLX, MBASE(row)); // "..." #endif @@ -638,11 +638,11 @@ inline void Item_Prepare_Home(const uint8_t row) { inline void Item_Prepare_Lang(const uint8_t row) { if (HMI_flag.language_chinese) { DWIN_Frame_AreaCopy(1, 239, 134, 266, 146, LBLX, MBASE(row)); - DWIN_Draw_String(false, false, font8x16, White, Background_black, 226, MBASE(row), F("CN")); + DWIN_Draw_String(false, false, font8x16, Color_White, Color_Bg_Black, 226, MBASE(row), F("CN")); } else { DWIN_Frame_AreaCopy(1, 0, 194, 121, 207, LBLX, MBASE(row)); // "Language selection" - DWIN_Draw_String(false, false, font8x16, White, Background_black, 226, MBASE(row), F("EN")); + DWIN_Draw_String(false, false, font8x16, Color_White, Color_Bg_Black, 226, MBASE(row), F("EN")); } Draw_Menu_Icon(row, ICON_Language); } @@ -716,14 +716,14 @@ inline void Draw_Control_Menu() { else { #ifdef USE_STRING_HEADINGS Draw_Title(GET_TEXT_F(MSG_CONTROL)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(CONTROL_CASE_TEMP), GET_TEXT_F(MSG_TEMPERATURE)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(CONTROL_CASE_MOVE), GET_TEXT_F(MSG_MOTION)); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(CONTROL_CASE_TEMP), GET_TEXT_F(MSG_TEMPERATURE)); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(CONTROL_CASE_MOVE), GET_TEXT_F(MSG_MOTION)); #if ENABLED(EEPROM_SETTINGS) - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(CONTROL_CASE_SAVE), GET_TEXT_F(MSG_STORE_EEPROM)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(CONTROL_CASE_LOAD), GET_TEXT_F(MSG_LOAD_EEPROM)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(CONTROL_CASE_RESET), GET_TEXT_F(MSG_RESTORE_DEFAULTS)); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(CONTROL_CASE_SAVE), GET_TEXT_F(MSG_STORE_EEPROM)); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(CONTROL_CASE_LOAD), GET_TEXT_F(MSG_LOAD_EEPROM)); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(CONTROL_CASE_RESET), GET_TEXT_F(MSG_RESTORE_DEFAULTS)); #endif - if (CVISI(CONTROL_CASE_INFO)) DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(CONTROL_CASE_INFO), F("Info")); + if (CVISI(CONTROL_CASE_INFO)) DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(CONTROL_CASE_INFO), F("Info")); #else DWIN_Frame_TitleCopy(1, 128, 2, 176, 12); // "Control" DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX, CLINE(CONTROL_CASE_TEMP)); // Temperature > @@ -784,17 +784,17 @@ inline void Draw_Tune_Menu() { else { #ifdef USE_STRING_HEADINGS Draw_Title(GET_TEXT_F(MSG_TUNE)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(TUNE_CASE_SPEED), GET_TEXT_F(MSG_SPEED)); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(TUNE_CASE_SPEED), GET_TEXT_F(MSG_SPEED)); #if HAS_HOTEND - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(TUNE_CASE_TEMP), GET_TEXT_F(MSG_UBL_SET_TEMP_HOTEND)); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(TUNE_CASE_TEMP), GET_TEXT_F(MSG_UBL_SET_TEMP_HOTEND)); #endif #if HAS_HEATED_BED - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(TUNE_CASE_BED), GET_TEXT_F(MSG_UBL_SET_TEMP_BED)); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(TUNE_CASE_BED), GET_TEXT_F(MSG_UBL_SET_TEMP_BED)); #endif #if HAS_FAN - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(TUNE_CASE_FAN), GET_TEXT_F(MSG_FAN_SPEED)); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(TUNE_CASE_FAN), GET_TEXT_F(MSG_FAN_SPEED)); #endif - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(TUNE_CASE_ZOFF), GET_TEXT_F(MSG_ZPROBE_ZOFFSET)); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(TUNE_CASE_ZOFF), GET_TEXT_F(MSG_ZPROBE_ZOFFSET)); #else DWIN_Frame_AreaCopy(1, 94, 2, 126, 12, 14, 9); DWIN_Frame_AreaCopy(1, 1, 179, 92, 190, LBLX, MBASE(TUNE_CASE_SPEED)); // Print speed @@ -819,23 +819,23 @@ inline 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, White, Background_black, 3, 216, MBASE(TUNE_CASE_SPEED), feedrate_percentage); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(TUNE_CASE_SPEED), feedrate_percentage); #if HAS_HOTEND Draw_Menu_Line(TUNE_CASE_TEMP, ICON_HotendTemp); - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(TUNE_CASE_TEMP), thermalManager.temp_hotend[0].target); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(TUNE_CASE_TEMP), thermalManager.temp_hotend[0].target); #endif #if HAS_HEATED_BED Draw_Menu_Line(TUNE_CASE_BED, ICON_BedTemp); - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(TUNE_CASE_BED), thermalManager.temp_bed.target); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(TUNE_CASE_BED), thermalManager.temp_bed.target); #endif #if HAS_FAN Draw_Menu_Line(TUNE_CASE_FAN, ICON_FanSpeed); - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(TUNE_CASE_FAN), thermalManager.fan_speed[0]); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(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, Background_black, 2, 2, 202, MBASE(TUNE_CASE_ZOFF), BABY_Z_VAR * 100); + DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 2, 2, 202, MBASE(TUNE_CASE_ZOFF), BABY_Z_VAR * 100); #endif } @@ -886,12 +886,12 @@ inline void Draw_Motion_Menu() { else { #ifdef USE_STRING_HEADINGS Draw_Title(GET_TEXT_F(MSG_MOTION)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(MOTION_CASE_RATE), F("Feedrate")); - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(MOTION_CASE_ACCEL), GET_TEXT_F(MSG_ACCELERATION)); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(MOTION_CASE_RATE), F("Feedrate")); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(MOTION_CASE_ACCEL), GET_TEXT_F(MSG_ACCELERATION)); #if HAS_CLASSIC_JERK - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(MOTION_CASE_JERK), GET_TEXT_F(MSG_JERK)); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(MOTION_CASE_JERK), GET_TEXT_F(MSG_JERK)); #endif - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(MOTION_CASE_STEPS), GET_TEXT_F(MSG_STEPS_PER_MM)); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(MOTION_CASE_STEPS), GET_TEXT_F(MSG_STEPS_PER_MM)); #else DWIN_Frame_TitleCopy(1, 144, 16, 189, 26); // "Motion" draw_max_en(MBASE(MOTION_CASE_RATE)); draw_speed_en(27, MBASE(MOTION_CASE_RATE)); // "Max Speed" @@ -932,8 +932,8 @@ inline void Draw_Motion_Menu() { DWIN_Frame_AreaCopy(1, 189, 389, 271, 402, 95, 310); } else { - DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, 36, 300, F("Nozzle or Bed temperature")); - DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, 92, 300, F("is too high")); + 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")); } } else { @@ -943,8 +943,8 @@ inline void Draw_Motion_Menu() { DWIN_Frame_AreaCopy(1, 189, 389, 271, 402, 95, 310); } else { - DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, 36, 300, F("Nozzle or Bed temperature")); - DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, 92, 300, F("is too low")); + 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")); } } } @@ -952,7 +952,7 @@ inline void Draw_Motion_Menu() { #endif inline void Draw_Popup_Bkgd_60() { - DWIN_Draw_Rectangle(1, Background_window, 14, 60, 258, 330); + DWIN_Draw_Rectangle(1, Color_Bg_Window, 14, 60, 258, 330); } #if HAS_HOTEND @@ -967,7 +967,7 @@ inline void Draw_Popup_Bkgd_60() { DWIN_ICON_Show(ICON, ICON_Confirm_C, 86, 280); } else { - DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, 20, 235, F("Nozzle is too cold")); + DWIN_Draw_String(false, true, font8x16, Popup_Text_Color, Color_Bg_Window, 20, 235, F("Nozzle is too cold")); DWIN_ICON_Show(ICON, ICON_Confirm_E, 86, 280); } } @@ -984,9 +984,9 @@ void Popup_Window_Resume() { DWIN_ICON_Show(ICON, ICON_Cancel_C, 146, 307); } else { - DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, (272 - 8 * 14) / 2, 115, F("Continue Print")); - DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, (272 - 8 * 22) / 2, 192, F("It looks like the last")); - DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, (272 - 8 * 22) / 2, 212, F("file was interrupted.")); + 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_ICON_Show(ICON, ICON_Continue_E, 26, 307); DWIN_ICON_Show(ICON, ICON_Cancel_E, 146, 307); } @@ -1002,8 +1002,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, Font_window, Background_window, (272 - 8 * (parking ? 7 : 10)) / 2, 230, parking ? F("Parking") : F("Homing XYZ")); - DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, (272 - 8 * 23) / 2, 260, F("Please wait until done.")); + 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.")); } } @@ -1018,8 +1018,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, Font_window, Background_window, (272 - 8 * 13) / 2, 230, GET_TEXT_F(MSG_BED_LEVELING)); - DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, (272 - 8 * 23) / 2, 260, F("Please wait until done.")); + 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.")); } } @@ -1027,8 +1027,8 @@ void Popup_Window_Home(const bool parking/*=false*/) { void Draw_Select_Highlight(const bool sel) { HMI_flag.select_flag = sel; - const uint16_t c1 = sel ? Select_Color : Background_window, - c2 = sel ? Background_window : Select_Color; + const uint16_t c1 = sel ? Select_Color : Color_Bg_Window, + c2 = sel ? Color_Bg_Window : Select_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); @@ -1046,8 +1046,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, Font_window, Background_window, (272 - 8 * 11) / 2, 150, GET_TEXT_F(MSG_PAUSE_PRINT)); - else if (select_print.now == 2) DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, (272 - 8 * 10) / 2, 150, GET_TEXT_F(MSG_STOP_PRINT)); + 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)); DWIN_ICON_Show(ICON, ICON_Confirm_E, 26, 280); DWIN_ICON_Show(ICON, ICON_Cancel_E, 146, 280); } @@ -1070,21 +1070,21 @@ void Draw_Printing_Screen() { void Draw_Print_ProgressBar() { DWIN_ICON_Show(ICON, ICON_Bar, 15, 93); DWIN_Draw_Rectangle(1, BarFill_Color, 16 + Percentrecord * 240 / 100, 93, 256, 113); - DWIN_Draw_IntValue(true, true, 0, font8x16, Percent_Color, Background_black, 2, 117, 133, Percentrecord); - DWIN_Draw_String(false, false, font8x16, Percent_Color, Background_black, 133, 133, F("%")); + DWIN_Draw_IntValue(true, true, 0, font8x16, Percent_Color, Color_Bg_Black, 2, 117, 133, Percentrecord); + DWIN_Draw_String(false, 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, White, Background_black, 2, 42, 212, elapsed.value / 3600); - DWIN_Draw_String(false, false, font8x16, White, Background_black, 58, 212, F(":")); - DWIN_Draw_IntValue(true, true, 1, font8x16, White, Background_black, 2, 66, 212, (elapsed.value % 3600) / 60); + 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_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, White, Background_black, 2, 176, 212, remain_time / 3600); - DWIN_Draw_String(false, false, font8x16, White, Background_black, 192, 212, F(":")); - DWIN_Draw_IntValue(true, true, 1, font8x16, White, Background_black, 2, 200, 212, (remain_time % 3600) / 60); + 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_IntValue(true, true, 1, font8x16, Color_White, Color_Bg_Black, 2, 200, 212, (remain_time % 3600) / 60); } void Goto_PrintProcess() { @@ -1100,7 +1100,7 @@ void Goto_PrintProcess() { // Copy into filebuf string before entry char * const name = card.longest_filename(); const int8_t npos = _MAX(0, DWIN_WIDTH - strlen(name) * MENU_CHR_W) / 2; - DWIN_Draw_String(false, false, font8x16, White, Background_black, npos, 60, name); + DWIN_Draw_String(false, 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); @@ -1155,7 +1155,7 @@ void HMI_Move_X() { else if (encoder_diffState == ENCODER_DIFF_ENTER) { checkkey = AxisMove; EncoderRate.enabled = false; - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 216, MBASE(1), HMI_ValueStruct.Move_X_scale); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 216, MBASE(1), HMI_ValueStruct.Move_X_scale); if (!planner.is_full()) { // Wait for planner moves to finish! planner.synchronize(); @@ -1167,7 +1167,7 @@ void HMI_Move_X() { NOLESS(HMI_ValueStruct.Move_X_scale, (X_MIN_POS) * MINUNITMULT); NOMORE(HMI_ValueStruct.Move_X_scale, (X_MAX_POS) * MINUNITMULT); current_position.x = HMI_ValueStruct.Move_X_scale / 10; - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 216, MBASE(1), HMI_ValueStruct.Move_X_scale); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 1, 216, MBASE(1), HMI_ValueStruct.Move_X_scale); DWIN_UpdateLCD(); } } @@ -1184,7 +1184,7 @@ void HMI_Move_Y() { else if (encoder_diffState == ENCODER_DIFF_ENTER) { checkkey = AxisMove; EncoderRate.enabled = false; - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 216, MBASE(2), HMI_ValueStruct.Move_Y_scale); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 216, MBASE(2), HMI_ValueStruct.Move_Y_scale); if (!planner.is_full()) { // Wait for planner moves to finish! planner.synchronize(); @@ -1196,7 +1196,7 @@ void HMI_Move_Y() { NOLESS(HMI_ValueStruct.Move_Y_scale, (Y_MIN_POS) * MINUNITMULT); NOMORE(HMI_ValueStruct.Move_Y_scale, (Y_MAX_POS) * MINUNITMULT); current_position.y = HMI_ValueStruct.Move_Y_scale / 10; - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 216, MBASE(2), HMI_ValueStruct.Move_Y_scale); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 1, 216, MBASE(2), HMI_ValueStruct.Move_Y_scale); DWIN_UpdateLCD(); } } @@ -1213,7 +1213,7 @@ void HMI_Move_Z() { else if (encoder_diffState == ENCODER_DIFF_ENTER) { checkkey = AxisMove; EncoderRate.enabled = false; - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 216, MBASE(3), HMI_ValueStruct.Move_Z_scale); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 216, MBASE(3), HMI_ValueStruct.Move_Z_scale); if (!planner.is_full()) { // Wait for planner moves to finish! planner.synchronize(); @@ -1225,7 +1225,7 @@ void HMI_Move_Z() { NOLESS(HMI_ValueStruct.Move_Z_scale, Z_MIN_POS * MINUNITMULT); NOMORE(HMI_ValueStruct.Move_Z_scale, Z_MAX_POS * MINUNITMULT); current_position.z = HMI_ValueStruct.Move_Z_scale / 10; - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 216, MBASE(3), HMI_ValueStruct.Move_Z_scale); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 1, 216, MBASE(3), HMI_ValueStruct.Move_Z_scale); DWIN_UpdateLCD(); } } @@ -1246,7 +1246,7 @@ void HMI_Move_Z() { checkkey = AxisMove; EncoderRate.enabled = false; last_E_scale = HMI_ValueStruct.Move_E_scale; - DWIN_Draw_Signed_Float(font8x16, Background_black, 3, 1, 216, MBASE(4), HMI_ValueStruct.Move_E_scale); + DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 3, 1, 216, MBASE(4), HMI_ValueStruct.Move_E_scale); if (!planner.is_full()) { planner.synchronize(); // Wait for planner moves to finish! planner.buffer_line(current_position, MMM_TO_MMS(FEEDRATE_E), active_extruder); @@ -1290,11 +1290,11 @@ void HMI_Move_Z() { #endif if (HMI_ValueStruct.show_mode == -4) { checkkey = Prepare; - DWIN_Draw_Signed_Float(font8x16, Background_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, MBASE(zoff_line), TERN(HAS_BED_PROBE, BABY_Z_VAR * 100, HMI_ValueStruct.offset_value)); } else { checkkey = Tune; - DWIN_Draw_Signed_Float(font8x16, Background_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, MBASE(zoff_line), TERN(HAS_BED_PROBE, BABY_Z_VAR * 100, HMI_ValueStruct.offset_value)); } DWIN_UpdateLCD(); return; @@ -1336,23 +1336,23 @@ void HMI_Move_Z() { EncoderRate.enabled = false; if (HMI_ValueStruct.show_mode == -1) { // temperature checkkey = TemperatureID; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(temp_line), HMI_ValueStruct.E_Temp); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(temp_line), HMI_ValueStruct.E_Temp); } else 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, White, Background_black, 3, 216, MBASE(temp_line), ui.material_preset[0].hotend_temp); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(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, White, Background_black, 3, 216, MBASE(temp_line), ui.material_preset[1].hotend_temp); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(temp_line), ui.material_preset[1].hotend_temp); return; } else { // tune checkkey = Tune; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(temp_line), HMI_ValueStruct.E_Temp); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(temp_line), HMI_ValueStruct.E_Temp); } thermalManager.setTargetHotend(HMI_ValueStruct.E_Temp, 0); return; @@ -1361,7 +1361,7 @@ void HMI_Move_Z() { NOMORE(HMI_ValueStruct.E_Temp, MAX_E_TEMP); NOLESS(HMI_ValueStruct.E_Temp, MIN_E_TEMP); // E_Temp value - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(temp_line), HMI_ValueStruct.E_Temp); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(temp_line), HMI_ValueStruct.E_Temp); } } @@ -1389,23 +1389,23 @@ void HMI_Move_Z() { EncoderRate.enabled = false; if (HMI_ValueStruct.show_mode == -1) { checkkey = TemperatureID; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(bed_line), HMI_ValueStruct.Bed_Temp); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(bed_line), HMI_ValueStruct.Bed_Temp); } else 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, White, Background_black, 3, 216, MBASE(bed_line), ui.material_preset[0].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); 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, White, Background_black, 3, 216, MBASE(bed_line), ui.material_preset[1].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); return; } else { checkkey = Tune; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(bed_line), HMI_ValueStruct.Bed_Temp); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(bed_line), HMI_ValueStruct.Bed_Temp); } thermalManager.setTargetBed(HMI_ValueStruct.Bed_Temp); return; @@ -1414,7 +1414,7 @@ void HMI_Move_Z() { NOMORE(HMI_ValueStruct.Bed_Temp, BED_MAX_TARGET); NOLESS(HMI_ValueStruct.Bed_Temp, MIN_BED_TEMP); // Bed_Temp value - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(bed_line), HMI_ValueStruct.Bed_Temp); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(bed_line), HMI_ValueStruct.Bed_Temp); } } @@ -1443,23 +1443,23 @@ void HMI_Move_Z() { EncoderRate.enabled = false; if (HMI_ValueStruct.show_mode == -1) { checkkey = TemperatureID; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(fan_line), HMI_ValueStruct.Fan_speed); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(fan_line), HMI_ValueStruct.Fan_speed); } else 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, White, Background_black, 3, 216, MBASE(fan_line), ui.material_preset[0].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); 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, White, Background_black, 3, 216, MBASE(fan_line), ui.material_preset[1].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); return; } else { checkkey = Tune; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(fan_line), HMI_ValueStruct.Fan_speed); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(fan_line), HMI_ValueStruct.Fan_speed); } thermalManager.set_fan_speed(0, HMI_ValueStruct.Fan_speed); return; @@ -1468,7 +1468,7 @@ void HMI_Move_Z() { NOMORE(HMI_ValueStruct.Fan_speed, FANON); NOLESS(HMI_ValueStruct.Fan_speed, FANOFF); // Fan_speed value - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(fan_line), HMI_ValueStruct.Fan_speed); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(fan_line), HMI_ValueStruct.Fan_speed); } } @@ -1487,14 +1487,14 @@ void HMI_PrintSpeed() { checkkey = Tune; EncoderRate.enabled = false; feedrate_percentage = HMI_ValueStruct.print_speed; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(select_tune.now + MROWS - index_tune), 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); return; } // print_speed limit NOMORE(HMI_ValueStruct.print_speed, MAX_PRINT_SPEED); NOLESS(HMI_ValueStruct.print_speed, MIN_PRINT_SPEED); // print_speed value - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(select_tune.now + MROWS - index_tune), HMI_ValueStruct.print_speed); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(select_tune.now + MROWS - index_tune), HMI_ValueStruct.print_speed); } } @@ -1512,7 +1512,7 @@ void HMI_MaxFeedspeedXYZE() { EncoderRate.enabled = false; if (WITHIN(HMI_flag.feedspeed_axis, X_AXIS, E_AXIS)) planner.set_max_feedrate(HMI_flag.feedspeed_axis, HMI_ValueStruct.Max_Feedspeed); - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 4, 210, MBASE(select_speed.now), 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); return; } // MaxFeedspeed limit @@ -1520,7 +1520,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, White, Select_Color, 4, 210, MBASE(select_speed.now), HMI_ValueStruct.Max_Feedspeed); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 4, 210, MBASE(select_speed.now), HMI_ValueStruct.Max_Feedspeed); } } @@ -1538,7 +1538,7 @@ void HMI_MaxAccelerationXYZE() { #if HAS_HOTEND else if (HMI_flag.acc_axis == E_AXIS) planner.set_max_acceleration(E_AXIS, HMI_ValueStruct.Max_Acceleration); #endif - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 4, 210, MBASE(select_acc.now), 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); return; } // MaxAcceleration limit @@ -1546,7 +1546,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, White, Select_Color, 4, 210, MBASE(select_acc.now), HMI_ValueStruct.Max_Acceleration); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 4, 210, MBASE(select_acc.now), HMI_ValueStruct.Max_Acceleration); } } @@ -1564,7 +1564,7 @@ void HMI_MaxAccelerationXYZE() { EncoderRate.enabled = false; if (WITHIN(HMI_flag.step_axis, X_AXIS, E_AXIS)) planner.set_max_jerk(HMI_flag.step_axis, HMI_ValueStruct.Max_Jerk / 10); - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 210, MBASE(select_jerk.now), HMI_ValueStruct.Max_Jerk); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 210, MBASE(select_jerk.now), HMI_ValueStruct.Max_Jerk); return; } // MaxJerk limit @@ -1572,7 +1572,7 @@ void HMI_MaxAccelerationXYZE() { NOMORE(HMI_ValueStruct.Max_Jerk, default_max_jerk[HMI_flag.jerk_axis] * 2 * MINUNITMULT); NOLESS(HMI_ValueStruct.Max_Jerk, (MIN_MAXJERK) * MINUNITMULT); // MaxJerk value - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 210, MBASE(select_jerk.now), HMI_ValueStruct.Max_Jerk); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 1, 210, MBASE(select_jerk.now), HMI_ValueStruct.Max_Jerk); } } @@ -1592,7 +1592,7 @@ void HMI_StepXYZE() { EncoderRate.enabled = false; if (WITHIN(HMI_flag.step_axis, X_AXIS, E_AXIS)) planner.settings.axis_steps_per_mm[HMI_flag.step_axis] = HMI_ValueStruct.Max_Step / 10; - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 210, MBASE(select_step.now), HMI_ValueStruct.Max_Step); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 210, MBASE(select_step.now), HMI_ValueStruct.Max_Step); return; } // Step limit @@ -1600,7 +1600,7 @@ void HMI_StepXYZE() { NOMORE(HMI_ValueStruct.Max_Step, default_axis_steps_per_unit[HMI_flag.step_axis] * 2 * MINUNITMULT); NOLESS(HMI_ValueStruct.Max_Step, MIN_STEP); // Step value - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 210, MBASE(select_step.now), HMI_ValueStruct.Max_Step); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 1, 210, MBASE(select_step.now), HMI_ValueStruct.Max_Step); } } @@ -1619,15 +1619,15 @@ void update_variable() { if (checkkey == Tune) { #if HAS_HOTEND if (last_temp_hotend_target != thermalManager.temp_hotend[0].target) - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(TUNE_CASE_TEMP + MROWS - index_tune), thermalManager.temp_hotend[0].target); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(TUNE_CASE_TEMP + MROWS - index_tune), thermalManager.temp_hotend[0].target); #endif #if HAS_HEATED_BED if (last_temp_bed_target != thermalManager.temp_bed.target) - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(TUNE_CASE_BED + MROWS - index_tune), thermalManager.temp_bed.target); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(TUNE_CASE_BED + MROWS - index_tune), thermalManager.temp_bed.target); #endif #if HAS_FAN if (last_fan_speed != thermalManager.fan_speed[0]) { - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(TUNE_CASE_FAN + MROWS - index_tune), thermalManager.fan_speed[0]); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(TUNE_CASE_FAN + MROWS - index_tune), thermalManager.fan_speed[0]); last_fan_speed = thermalManager.fan_speed[0]; } #endif @@ -1637,15 +1637,15 @@ void update_variable() { if (checkkey == TemperatureID) { #if HAS_HOTEND if (last_temp_hotend_target != thermalManager.temp_hotend[0].target) - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(TEMP_CASE_TEMP), thermalManager.temp_hotend[0].target); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(TEMP_CASE_TEMP), thermalManager.temp_hotend[0].target); #endif #if HAS_HEATED_BED if (last_temp_bed_target != thermalManager.temp_bed.target) - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(TEMP_CASE_BED), thermalManager.temp_bed.target); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(TEMP_CASE_BED), thermalManager.temp_bed.target); #endif #if HAS_FAN if (last_fan_speed != thermalManager.fan_speed[0]) { - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(TEMP_CASE_FAN), thermalManager.fan_speed[0]); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(TEMP_CASE_FAN), thermalManager.fan_speed[0]); last_fan_speed = thermalManager.fan_speed[0]; } #endif @@ -1654,32 +1654,32 @@ void update_variable() { /* Bottom temperature update */ #if HAS_HOTEND if (last_temp_hotend_current != thermalManager.temp_hotend[0].celsius) { - DWIN_Draw_IntValue(true, true, 0, STAT_FONT, White, Background_black, 3, 33, 382, thermalManager.temp_hotend[0].celsius); + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 33, 382, thermalManager.temp_hotend[0].celsius); last_temp_hotend_current = thermalManager.temp_hotend[0].celsius; } if (last_temp_hotend_target != thermalManager.temp_hotend[0].target) { - DWIN_Draw_IntValue(true, true, 0, STAT_FONT, White, Background_black, 3, 33 + 4 * STAT_CHR_W + 6, 382, thermalManager.temp_hotend[0].target); + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 33 + 4 * STAT_CHR_W + 6, 382, thermalManager.temp_hotend[0].target); last_temp_hotend_target = thermalManager.temp_hotend[0].target; } #endif #if HAS_HEATED_BED if (last_temp_bed_current != thermalManager.temp_bed.celsius) { - DWIN_Draw_IntValue(true, true, 0, STAT_FONT, White, Background_black, 3, 178, 382, thermalManager.temp_bed.celsius); + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 178, 382, thermalManager.temp_bed.celsius); last_temp_bed_current = thermalManager.temp_bed.celsius; } if (last_temp_bed_target != thermalManager.temp_bed.target) { - DWIN_Draw_IntValue(true, true, 0, STAT_FONT, White, Background_black, 3, 178 + 4 * STAT_CHR_W + 6, 382, thermalManager.temp_bed.target); + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 178 + 4 * STAT_CHR_W + 6, 382, thermalManager.temp_bed.target); last_temp_bed_target = thermalManager.temp_bed.target; } #endif static uint16_t last_speed = 0; if (last_speed != feedrate_percentage) { - DWIN_Draw_IntValue(true, true, 0, STAT_FONT, White, Background_black, 3, 33 + 2 * STAT_CHR_W, 429, feedrate_percentage); + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 33 + 2 * STAT_CHR_W, 429, feedrate_percentage); last_speed = feedrate_percentage; } #if HAS_ZOFFSET_ITEM if (last_zoffset != BABY_Z_VAR) { - DWIN_Draw_Signed_Float(STAT_FONT, Background_black, 2, 2, 178 + STAT_CHR_W, 429, BABY_Z_VAR * 100); + DWIN_Draw_Signed_Float(DWIN_FONT_STAT, Color_Bg_Black, 2, 2, 178 + STAT_CHR_W, 429, BABY_Z_VAR * 100); last_zoffset = BABY_Z_VAR; } #endif @@ -1869,16 +1869,16 @@ void HMI_StartFrame(const bool with_update) { Goto_MainMenu(); // Clear the bottom area of the screen - DWIN_Draw_Rectangle(1, Background_black, 0, STATUS_Y, DWIN_WIDTH, DWIN_HEIGHT - 1); + DWIN_Draw_Rectangle(1, Color_Bg_Black, 0, STATUS_Y, DWIN_WIDTH, DWIN_HEIGHT - 1); // // Status Area // #if HAS_HOTEND DWIN_ICON_Show(ICON, ICON_HotendTemp, 13, 381); - DWIN_Draw_IntValue(true, true, 0, STAT_FONT, White, Background_black, 3, 33, 382, thermalManager.temp_hotend[0].celsius); - DWIN_Draw_String(false, false, STAT_FONT, White, Background_black, 33 + 3 * STAT_CHR_W + 5, 383, F("/")); - DWIN_Draw_IntValue(true, true, 0, STAT_FONT, White, Background_black, 3, 33 + 4 * STAT_CHR_W + 6, 382, thermalManager.temp_hotend[0].target); + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 33, 382, thermalManager.temp_hotend[0].celsius); + DWIN_Draw_String(false, false, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 33 + 3 * STAT_CHR_W + 5, 383, F("/")); + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 33 + 4 * STAT_CHR_W + 6, 382, thermalManager.temp_hotend[0].target); #endif #if HOTENDS > 1 // DWIN_ICON_Show(ICON,ICON_HotendTemp, 13, 381); @@ -1886,18 +1886,18 @@ void HMI_StartFrame(const bool with_update) { #if HAS_HEATED_BED DWIN_ICON_Show(ICON, ICON_BedTemp, 158, 381); - DWIN_Draw_IntValue(true, true, 0, STAT_FONT, White, Background_black, 3, 178, 382, thermalManager.temp_bed.celsius); - DWIN_Draw_String(false, false, STAT_FONT, White, Background_black, 178 + 3 * STAT_CHR_W + 5, 383, F("/")); - DWIN_Draw_IntValue(true, true, 0, STAT_FONT, White, Background_black, 3, 178 + 4 * STAT_CHR_W + 6, 382, thermalManager.temp_bed.target); + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 178, 382, thermalManager.temp_bed.celsius); + DWIN_Draw_String(false, false, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 178 + 3 * STAT_CHR_W + 5, 383, F("/")); + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 178 + 4 * STAT_CHR_W + 6, 382, thermalManager.temp_bed.target); #endif DWIN_ICON_Show(ICON, ICON_Speed, 13, 429); - DWIN_Draw_IntValue(true, true, 0, STAT_FONT, White, Background_black, 3, 33 + 2 * STAT_CHR_W, 429, feedrate_percentage); - DWIN_Draw_String(false, false, STAT_FONT, White, Background_black, 33 + 5 * STAT_CHR_W + 2, 429, F("%")); + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 33 + 2 * STAT_CHR_W, 429, feedrate_percentage); + DWIN_Draw_String(false, false, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 33 + 5 * STAT_CHR_W + 2, 429, F("%")); #if HAS_ZOFFSET_ITEM DWIN_ICON_Show(ICON, ICON_Zoffset, 158, 428); - DWIN_Draw_Signed_Float(STAT_FONT, Background_black, 2, 2, 178, 429, BABY_Z_VAR * 100); + DWIN_Draw_Signed_Float(DWIN_FONT_STAT, Color_Bg_Black, 2, 2, 178, 429, BABY_Z_VAR * 100); #endif if (with_update) { @@ -1909,8 +1909,8 @@ void HMI_StartFrame(const bool with_update) { inline void Draw_Info_Menu() { Clear_Main_Window(); - DWIN_Draw_String(false, false, font8x16, White, Background_black, (DWIN_WIDTH - strlen(MACHINE_SIZE) * MENU_CHR_W) / 2, 122, (char*)MACHINE_SIZE); - DWIN_Draw_String(false, false, font8x16, White, Background_black, (DWIN_WIDTH - strlen(SHORT_BUILD_VERSION) * MENU_CHR_W) / 2, 195, (char*)SHORT_BUILD_VERSION); + DWIN_Draw_String(false, false, font8x16, Color_White, Color_Bg_Black, (DWIN_WIDTH - strlen(MACHINE_SIZE) * MENU_CHR_W) / 2, 122, (char*)MACHINE_SIZE); + DWIN_Draw_String(false, false, font8x16, Color_White, Color_Bg_Black, (DWIN_WIDTH - strlen(SHORT_BUILD_VERSION) * MENU_CHR_W) / 2, 195, (char*)SHORT_BUILD_VERSION); if (HMI_flag.language_chinese) { DWIN_Frame_TitleCopy(1, 30, 17, 57, 29); // "Info" @@ -1918,7 +1918,7 @@ inline void Draw_Info_Menu() { 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_Draw_String(false, false, font8x16, White, Background_black, (DWIN_WIDTH - strlen(CORP_WEBSITE_C) * MENU_CHR_W) / 2, 268, (char*)CORP_WEBSITE_C); + DWIN_Draw_String(false, false, font8x16, Color_White, Color_Bg_Black, (DWIN_WIDTH - strlen(CORP_WEBSITE_C) * MENU_CHR_W) / 2, 268, (char*)CORP_WEBSITE_C); } else { #ifdef USE_STRING_HEADINGS @@ -1930,7 +1930,7 @@ inline void Draw_Info_Menu() { 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_Draw_String(false, false, font8x16, White, Background_black, (DWIN_WIDTH - strlen(CORP_WEBSITE_E) * MENU_CHR_W) / 2, 268, (char*)CORP_WEBSITE_E); + DWIN_Draw_String(false, false, font8x16, Color_White, Color_Bg_Black, (DWIN_WIDTH - strlen(CORP_WEBSITE_E) * MENU_CHR_W) / 2, 268, (char*)CORP_WEBSITE_E); } Draw_Back_First(); @@ -2393,13 +2393,13 @@ void HMI_Prepare() { select_axis.reset(); Draw_Move_Menu(); - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 216, MBASE(1), current_position.x * MINUNITMULT); - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 216, MBASE(2), current_position.y * MINUNITMULT); - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 216, MBASE(3), current_position.z * MINUNITMULT); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 216, MBASE(1), current_position.x * MINUNITMULT); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 216, MBASE(2), current_position.y * MINUNITMULT); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 216, MBASE(3), current_position.z * MINUNITMULT); #if HAS_HOTEND queue.inject_P(PSTR("G92 E0")); current_position.e = HMI_ValueStruct.Move_E_scale = 0; - DWIN_Draw_Signed_Float(font8x16, Background_black, 3, 1, 216, MBASE(4), 0); + DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 3, 1, 216, MBASE(4), 0); #endif break; case PREPARE_CASE_DISA: // Disable steppers @@ -2479,17 +2479,17 @@ void Draw_Temperature_Menu() { #ifdef USE_STRING_HEADINGS Draw_Title(GET_TEXT_F(MSG_TEMPERATURE)); #if HAS_HOTEND - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(TEMP_CASE_TEMP), GET_TEXT_F(MSG_UBL_SET_TEMP_HOTEND)); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(TEMP_CASE_TEMP), GET_TEXT_F(MSG_UBL_SET_TEMP_HOTEND)); #endif #if HAS_HEATED_BED - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(TEMP_CASE_BED), GET_TEXT_F(MSG_UBL_SET_TEMP_BED)); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(TEMP_CASE_BED), GET_TEXT_F(MSG_UBL_SET_TEMP_BED)); #endif #if HAS_FAN - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(TEMP_CASE_FAN), GET_TEXT_F(MSG_FAN_SPEED)); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(TEMP_CASE_FAN), GET_TEXT_F(MSG_FAN_SPEED)); #endif #if HAS_HOTEND - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(TEMP_CASE_PLA), F("PLA Preheat Settings")); - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(TEMP_CASE_ABS), F("ABS Preheat Settings")); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(TEMP_CASE_PLA), F("PLA Preheat Settings")); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(TEMP_CASE_ABS), F("ABS Preheat Settings")); #endif #else DWIN_Frame_TitleCopy(1, 56, 16, 141, 28); // "Temperature" @@ -2523,15 +2523,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, White, Background_black, 3, 216, MBASE(i), thermalManager.temp_hotend[0].target); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(i), thermalManager.temp_hotend[0].target); #endif #if HAS_HEATED_BED _TMENU_ICON(TEMP_CASE_BED); - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(i), thermalManager.temp_bed.target); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(i), thermalManager.temp_bed.target); #endif #if HAS_FAN _TMENU_ICON(TEMP_CASE_FAN); - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(i), thermalManager.fan_speed[0]); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(i), thermalManager.fan_speed[0]); #endif #if HAS_HOTEND // PLA/ABS items have submenus @@ -2651,10 +2651,10 @@ void HMI_AxisMove() { HMI_flag.ETempTooLow_flag = false; current_position.e = HMI_ValueStruct.Move_E_scale = 0; Draw_Move_Menu(); - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 216, MBASE(1), HMI_ValueStruct.Move_X_scale); - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 216, MBASE(2), HMI_ValueStruct.Move_Y_scale); - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 216, MBASE(3), HMI_ValueStruct.Move_Z_scale); - DWIN_Draw_Signed_Float(font8x16, Background_black, 3, 1, 216, MBASE(4), 0); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 216, MBASE(1), HMI_ValueStruct.Move_X_scale); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 216, MBASE(2), HMI_ValueStruct.Move_Y_scale); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 216, MBASE(3), HMI_ValueStruct.Move_Z_scale); + DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 3, 1, 216, MBASE(4), 0); DWIN_UpdateLCD(); } return; @@ -2679,19 +2679,19 @@ void HMI_AxisMove() { case 1: // X axis move checkkey = Move_X; HMI_ValueStruct.Move_X_scale = current_position.x * MINUNITMULT; - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 216, MBASE(1), HMI_ValueStruct.Move_X_scale); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 1, 216, MBASE(1), HMI_ValueStruct.Move_X_scale); EncoderRate.enabled = true; break; case 2: // Y axis move checkkey = Move_Y; HMI_ValueStruct.Move_Y_scale = current_position.y * MINUNITMULT; - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 216, MBASE(2), HMI_ValueStruct.Move_Y_scale); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 1, 216, MBASE(2), HMI_ValueStruct.Move_Y_scale); EncoderRate.enabled = true; break; case 3: // Z axis move checkkey = Move_Z; HMI_ValueStruct.Move_Z_scale = current_position.z * MINUNITMULT; - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 216, MBASE(3), HMI_ValueStruct.Move_Z_scale); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 1, 216, MBASE(3), HMI_ValueStruct.Move_Z_scale); EncoderRate.enabled = true; break; #if HAS_HOTEND @@ -2740,7 +2740,7 @@ void HMI_Temperature() { case TEMP_CASE_TEMP: // Nozzle temperature checkkey = ETemp; HMI_ValueStruct.E_Temp = thermalManager.temp_hotend[0].target; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(1), thermalManager.temp_hotend[0].target); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(1), thermalManager.temp_hotend[0].target); EncoderRate.enabled = true; break; #endif @@ -2748,7 +2748,7 @@ void HMI_Temperature() { case TEMP_CASE_BED: // Bed temperature checkkey = BedTemp; HMI_ValueStruct.Bed_Temp = thermalManager.temp_bed.target; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(2), thermalManager.temp_bed.target); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(2), thermalManager.temp_bed.target); EncoderRate.enabled = true; break; #endif @@ -2756,7 +2756,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, White, Select_Color, 3, 216, MBASE(3), thermalManager.fan_speed[0]); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(3), thermalManager.fan_speed[0]); EncoderRate.enabled = true; break; #endif @@ -2787,15 +2787,15 @@ void HMI_Temperature() { else { #ifdef USE_STRING_HEADINGS Draw_Title("PLA Settings"); // TODO: GET_TEXT_F - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(PREHEAT_CASE_TEMP), F("Nozzle Temp")); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(PREHEAT_CASE_TEMP), F("Nozzle Temp")); #if HAS_HEATED_BED - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(PREHEAT_CASE_BED), F("Bed Temp")); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(PREHEAT_CASE_BED), F("Bed Temp")); #endif #if HAS_FAN - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(PREHEAT_CASE_FAN), GET_TEXT_F(MSG_FAN_SPEED)); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(PREHEAT_CASE_FAN), GET_TEXT_F(MSG_FAN_SPEED)); #endif #if ENABLED(EEPROM_SETTINGS) - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(PREHEAT_CASE_SAVE), GET_TEXT_F(MSG_STORE_EEPROM)); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(PREHEAT_CASE_SAVE), GET_TEXT_F(MSG_STORE_EEPROM)); #endif #else DWIN_Frame_TitleCopy(1, 56, 16, 141, 28); // "PLA Settings" @@ -2821,14 +2821,14 @@ void HMI_Temperature() { uint8_t i = 0; Draw_Menu_Line(++i, ICON_SetEndTemp); - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(i), ui.material_preset[0].hotend_temp); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(i), ui.material_preset[0].hotend_temp); #if HAS_HEATED_BED Draw_Menu_Line(++i, ICON_SetBedTemp); - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(i), ui.material_preset[0].bed_temp); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(i), ui.material_preset[0].bed_temp); #endif #if HAS_FAN Draw_Menu_Line(++i, ICON_FanSpeed); - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(i), ui.material_preset[0].fan_speed); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(i), ui.material_preset[0].fan_speed); #endif #if ENABLED(EEPROM_SETTINGS) Draw_Menu_Line(++i, ICON_WriteEEPROM); @@ -2863,15 +2863,15 @@ void HMI_Temperature() { else { #ifdef USE_STRING_HEADINGS Draw_Title("ABS Settings"); // TODO: GET_TEXT_F - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(PREHEAT_CASE_TEMP), F("Nozzle Temp")); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(PREHEAT_CASE_TEMP), F("Nozzle Temp")); #if HAS_HEATED_BED - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(PREHEAT_CASE_BED), F("Bed Temp")); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(PREHEAT_CASE_BED), F("Bed Temp")); #endif #if HAS_FAN - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(PREHEAT_CASE_FAN), GET_TEXT_F(MSG_FAN_SPEED)); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(PREHEAT_CASE_FAN), GET_TEXT_F(MSG_FAN_SPEED)); #endif #if ENABLED(EEPROM_SETTINGS) - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(PREHEAT_CASE_SAVE), GET_TEXT_F(MSG_STORE_EEPROM)); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(PREHEAT_CASE_SAVE), GET_TEXT_F(MSG_STORE_EEPROM)); #endif #else DWIN_Frame_TitleCopy(1, 56, 16, 141, 28); // "ABS Settings" @@ -2898,14 +2898,14 @@ void HMI_Temperature() { uint8_t i = 0; Draw_Menu_Line(++i, ICON_SetEndTemp); - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(i), ui.material_preset[1].hotend_temp); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(i), ui.material_preset[1].hotend_temp); #if HAS_HEATED_BED Draw_Menu_Line(++i, ICON_SetBedTemp); - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(i), ui.material_preset[1].bed_temp); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(i), ui.material_preset[1].bed_temp); #endif #if HAS_FAN Draw_Menu_Line(++i, ICON_FanSpeed); - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(i), ui.material_preset[1].fan_speed); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(i), ui.material_preset[1].fan_speed); #endif #if ENABLED(EEPROM_SETTINGS) Draw_Menu_Line(++i, ICON_WriteEEPROM); @@ -2943,11 +2943,11 @@ inline void Draw_Max_Speed_Menu() { else { #ifdef USE_STRING_HEADINGS Draw_Title("Max Speed (mm/s)"); // TODO: GET_TEXT_F - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(1), F("Max Feedrate X")); - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(2), F("Max Feedrate Y")); - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(3), F("Max Feedrate Z")); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(1), F("Max Feedrate X")); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(2), F("Max Feedrate Y")); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(3), F("Max Feedrate Z")); #if HAS_HOTEND - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(4), F("Max Feedrate E")); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(4), F("Max Feedrate E")); #endif #else DWIN_Frame_TitleCopy(1, 144, 16, 189, 26); // "Max Speed (mm/s)" @@ -2973,11 +2973,11 @@ inline void Draw_Max_Speed_Menu() { 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, White, Background_black, 4, 210, MBASE(1), planner.settings.max_feedrate_mm_s[X_AXIS]); - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 4, 210, MBASE(2), planner.settings.max_feedrate_mm_s[Y_AXIS]); - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 4, 210, MBASE(3), planner.settings.max_feedrate_mm_s[Z_AXIS]); + 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]); #if HAS_HOTEND - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 4, 210, MBASE(4), planner.settings.max_feedrate_mm_s[E_AXIS]); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 4, 210, MBASE(4), planner.settings.max_feedrate_mm_s[E_AXIS]); #endif } @@ -3005,11 +3005,11 @@ inline void Draw_Max_Accel_Menu() { else { #ifdef USE_STRING_HEADINGS Draw_Title(GET_TEXT_F(MSG_ACCELERATION)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(1), F("Max Accel X")); - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(2), F("Max Accel Y")); - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(3), F("Max Accel Z")); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(1), F("Max Accel X")); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(2), F("Max Accel Y")); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(3), F("Max Accel Z")); #if HAS_HOTEND - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(4), F("Max Accel E")); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(4), F("Max Accel E")); #endif #else DWIN_Frame_TitleCopy(1, 144, 16, 189, 26); // "Acceleration" @@ -3024,11 +3024,11 @@ inline void Draw_Max_Accel_Menu() { 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, White, Background_black, 4, 210, MBASE(1), planner.settings.max_acceleration_mm_per_s2[X_AXIS]); - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 4, 210, MBASE(2), planner.settings.max_acceleration_mm_per_s2[Y_AXIS]); - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 4, 210, MBASE(3), planner.settings.max_acceleration_mm_per_s2[Z_AXIS]); + 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]); #if HAS_HOTEND - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 4, 210, MBASE(4), planner.settings.max_acceleration_mm_per_s2[E_AXIS]); + 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]); #endif } @@ -3060,11 +3060,11 @@ inline void Draw_Max_Jerk_Menu() { else { #ifdef USE_STRING_HEADINGS Draw_Title(GET_TEXT_F(MSG_JERK)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(1), F("Max Jerk X")); - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(2), F("Max Jerk Y")); - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(3), F("Max Jerk Z")); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(1), F("Max Jerk X")); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(2), F("Max Jerk Y")); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(3), F("Max Jerk Z")); #if HAS_HOTEND - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(4), F("Max Jerk E")); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(4), F("Max Jerk E")); #endif #else DWIN_Frame_TitleCopy(1, 144, 16, 189, 26); // "Jerk" @@ -3094,11 +3094,11 @@ inline void Draw_Max_Jerk_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, White, Background_black, 3, 1, 210, MBASE(1), planner.max_jerk[X_AXIS] * MINUNITMULT); - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 210, MBASE(2), planner.max_jerk[Y_AXIS] * MINUNITMULT); - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 210, MBASE(3), planner.max_jerk[Z_AXIS] * MINUNITMULT); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 210, MBASE(1), planner.max_jerk[X_AXIS] * MINUNITMULT); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 210, MBASE(2), planner.max_jerk[Y_AXIS] * MINUNITMULT); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 210, MBASE(3), planner.max_jerk[Z_AXIS] * MINUNITMULT); #if HAS_HOTEND - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 210, MBASE(4), planner.max_jerk[E_AXIS] * MINUNITMULT); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 210, MBASE(4), planner.max_jerk[E_AXIS] * MINUNITMULT); #endif } @@ -3122,11 +3122,11 @@ inline void Draw_Steps_Menu() { else { #ifdef USE_STRING_HEADINGS Draw_Title(GET_TEXT_F(MSG_STEPS_PER_MM)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(1), F("Steps/mm X")); - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(2), F("Steps/mm Y")); - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(3), F("Steps/mm Z")); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(1), F("Steps/mm X")); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(2), F("Steps/mm Y")); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(3), F("Steps/mm Z")); #if HAS_HOTEND - DWIN_Draw_String(false, true, font8x16, White, Background_black, LBLX, MBASE(4), F("Steps/mm E")); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(4), F("Steps/mm E")); #endif #else DWIN_Frame_TitleCopy(1, 144, 16, 189, 26); // "Steps per mm" @@ -3141,11 +3141,11 @@ inline 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, White, Background_black, 3, 1, 210, MBASE(1), planner.settings.axis_steps_per_mm[X_AXIS] * MINUNITMULT); - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 210, MBASE(2), planner.settings.axis_steps_per_mm[Y_AXIS] * MINUNITMULT); - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 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, 1, 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, 1, 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, 1, 210, MBASE(3), planner.settings.axis_steps_per_mm[Z_AXIS] * MINUNITMULT); #if HAS_HOTEND - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 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, 1, 210, MBASE(4), planner.settings.axis_steps_per_mm[E_AXIS] * MINUNITMULT); #endif } @@ -3253,14 +3253,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, White, Select_Color, 3, 216, MBASE(TUNE_CASE_SPEED + MROWS - index_tune), feedrate_percentage); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(TUNE_CASE_SPEED + MROWS - index_tune), feedrate_percentage); EncoderRate.enabled = true; break; #if HAS_HOTEND case TUNE_CASE_TEMP: // Nozzle temp checkkey = ETemp; HMI_ValueStruct.E_Temp = thermalManager.temp_hotend[0].target; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(TUNE_CASE_TEMP + MROWS - index_tune), thermalManager.temp_hotend[0].target); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(TUNE_CASE_TEMP + MROWS - index_tune), thermalManager.temp_hotend[0].target); EncoderRate.enabled = true; break; #endif @@ -3268,7 +3268,7 @@ void HMI_Tune() { case TUNE_CASE_BED: // Bed temp checkkey = BedTemp; HMI_ValueStruct.Bed_Temp = thermalManager.temp_bed.target; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(TUNE_CASE_BED + MROWS - index_tune), thermalManager.temp_bed.target); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(TUNE_CASE_BED + MROWS - index_tune), thermalManager.temp_bed.target); EncoderRate.enabled = true; break; #endif @@ -3276,7 +3276,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, White, Select_Color, 3, 216, MBASE(TUNE_CASE_FAN + MROWS - index_tune), thermalManager.fan_speed[0]); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(TUNE_CASE_FAN + MROWS - index_tune), thermalManager.fan_speed[0]); EncoderRate.enabled = true; break; #endif @@ -3326,7 +3326,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, White, Select_Color, 3, 216, MBASE(PREHEAT_CASE_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); EncoderRate.enabled = true; break; #endif @@ -3334,7 +3334,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, White, Select_Color, 3, 216, MBASE(PREHEAT_CASE_BED), 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); EncoderRate.enabled = true; break; #endif @@ -3342,7 +3342,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, White, Select_Color, 3, 216, MBASE(PREHEAT_CASE_FAN), 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); EncoderRate.enabled = true; break; #endif @@ -3382,7 +3382,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, White, Select_Color, 3, 216, MBASE(PREHEAT_CASE_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); EncoderRate.enabled = true; break; #endif @@ -3390,7 +3390,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, White, Select_Color, 3, 216, MBASE(PREHEAT_CASE_BED), 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); EncoderRate.enabled = true; break; #endif @@ -3398,7 +3398,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, White, Select_Color, 3, 216, MBASE(PREHEAT_CASE_FAN), 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); EncoderRate.enabled = true; break; #endif @@ -3433,7 +3433,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, White, Select_Color, 4, 210, MBASE(select_speed.now), HMI_ValueStruct.Max_Feedspeed); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 4, 210, MBASE(select_speed.now), HMI_ValueStruct.Max_Feedspeed); EncoderRate.enabled = true; } else { // Back @@ -3462,7 +3462,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, White, Select_Color, 4, 210, MBASE(select_acc.now), HMI_ValueStruct.Max_Acceleration); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 4, 210, MBASE(select_acc.now), HMI_ValueStruct.Max_Acceleration); EncoderRate.enabled = true; } else { // Back @@ -3492,7 +3492,7 @@ void HMI_MaxAcceleration() { checkkey = MaxJerk_value; HMI_flag.jerk_axis = AxisEnum(select_jerk.now - 1); HMI_ValueStruct.Max_Jerk = planner.max_jerk[HMI_flag.jerk_axis] * MINUNITMULT; - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 210, MBASE(select_jerk.now), HMI_ValueStruct.Max_Jerk); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 1, 210, MBASE(select_jerk.now), HMI_ValueStruct.Max_Jerk); EncoderRate.enabled = true; } else { // Back @@ -3522,7 +3522,7 @@ void HMI_Step() { checkkey = Step_value; HMI_flag.step_axis = AxisEnum(select_step.now - 1); HMI_ValueStruct.Max_Step = planner.settings.axis_steps_per_mm[HMI_flag.step_axis] * MINUNITMULT; - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 210, MBASE(select_step.now), HMI_ValueStruct.Max_Step); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 1, 210, MBASE(select_step.now), HMI_ValueStruct.Max_Step); EncoderRate.enabled = true; } else { // Back @@ -3539,7 +3539,7 @@ void HMI_Init() { for (uint16_t t = 0; t <= 100; t += 2) { DWIN_ICON_Show(ICON, ICON_Bar, 15, 260); - DWIN_Draw_Rectangle(1, Background_black, 15 + t * 242 / 100, 260, 257, 280); + DWIN_Draw_Rectangle(1, Color_Bg_Black, 15 + t * 242 / 100, 260, 257, 280); DWIN_UpdateLCD(); delay(20); } @@ -3577,7 +3577,7 @@ void EachMomentUpdate() { Draw_Print_ProgressBar(); // show print done confirm - DWIN_Draw_Rectangle(1, Background_black, 0, 250, DWIN_WIDTH - 1, STATUS_Y); + DWIN_Draw_Rectangle(1, Color_Bg_Black, 0, 250, DWIN_WIDTH - 1, STATUS_Y); DWIN_ICON_Show(ICON, HMI_flag.language_chinese ? ICON_Confirm_C : ICON_Confirm_E, 86, 283); } else if (HMI_flag.pause_flag != printingIsPaused()) { @@ -3654,7 +3654,7 @@ void EachMomentUpdate() { if (!recovery.valid()) return recovery.purge(); auto draw_first_option = [](const bool sel) { - const uint16_t c1 = sel ? Background_window : Select_Color; + const uint16_t c1 = sel ? Color_Bg_Window : Select_Color; DWIN_Draw_Rectangle(0, c1, 25, 306, 126, 345); DWIN_Draw_Rectangle(0, c1, 24, 305, 127, 346); }; @@ -3662,7 +3662,7 @@ void EachMomentUpdate() { auto update_selection = [&](const bool sel) { HMI_flag.select_flag = sel; draw_first_option(sel); - const uint16_t c2 = sel ? Select_Color : Background_window; + const uint16_t c2 = sel ? Select_Color : Color_Bg_Window; DWIN_Draw_Rectangle(0, c2, 145, 306, 246, 345); DWIN_Draw_Rectangle(0, c2, 144, 305, 247, 346); }; @@ -3679,7 +3679,7 @@ void EachMomentUpdate() { draw_first_option(false); char * const name = card.longest_filename(); const int8_t npos = _MAX(0, DWIN_WIDTH - strlen(name) * (MENU_CHR_W)) / 2; - DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, npos, 252, name); + DWIN_Draw_String(false, true, font8x16, Popup_Text_Color, Color_Bg_Window, npos, 252, name); DWIN_UpdateLCD(); break; } diff --git a/Marlin/src/lcd/dwin/e3v2/dwin.h b/Marlin/src/lcd/dwin/e3v2/dwin.h index fedb87afdd81..7b759d9cbfea 100644 --- a/Marlin/src/lcd/dwin/e3v2/dwin.h +++ b/Marlin/src/lcd/dwin/e3v2/dwin.h @@ -214,16 +214,16 @@ enum processID : uint8_t { #define font32x64 0x09 // Color -#define White 0xFFFF -#define Background_window 0x31E8 // Popup background color -#define Background_blue 0x1125 // Dark blue background color -#define Background_black 0x0841 // black background color -#define Font_window 0xD6BA // Popup font background color +#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 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 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; From 4696142a31fe74ad32a57a5939e3af1cbae23e52 Mon Sep 17 00:00:00 2001 From: InsanityAutomation <38436470+InsanityAutomation@users.noreply.github.com> Date: Sat, 19 Sep 2020 10:20:15 -0400 Subject: [PATCH 39/44] Fix compile for Taz Pro (#19424) --- .../ftdi_eve_touch_ui/screens/boot_screen.cpp | 2 +- .../screens/leveling_menu.cpp | 3 -- .../lib/ftdi_eve_touch_ui/screens/screens.h | 4 ++ .../theme/bootscreen_logo_portrait.h | 42 +++++++++++++++++++ 4 files changed, 47 insertions(+), 4 deletions(-) create mode 100644 Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/bootscreen_logo_portrait.h diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/boot_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/boot_screen.cpp index 2c2c0c6a18ec..4ce8f608f123 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/boot_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/boot_screen.cpp @@ -32,7 +32,7 @@ #ifdef SHOW_CUSTOM_BOOTSCREEN #ifdef TOUCH_UI_PORTRAIT - #include "../theme/_bootscreen_portrait.h" + #include "../theme/bootscreen_logo_portrait.h" #else #include "../theme/_bootscreen_landscape.h" #endif diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/leveling_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/leveling_menu.cpp index 2eab27c6086b..74ab332fb4d7 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/leveling_menu.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/leveling_menu.cpp @@ -94,9 +94,6 @@ bool LevelingMenu::onTouchEnd(uint8_t tag) { switch (tag) { case 1: GOTO_PREVIOUS(); break; case 2: - #ifndef BED_LEVELING_COMMANDS - #define BED_LEVELING_COMMANDS "G29" - #endif #if HAS_MESH BedMeshScreen::startMeshProbe(); #else diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h index b425c4fa45fb..2108cff8df2a 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h @@ -27,6 +27,10 @@ #include "../theme/theme.h" #include "string_format.h" +#ifndef BED_LEVELING_COMMANDS + #define BED_LEVELING_COMMANDS "G29" +#endif + extern tiny_timer_t refresh_timer; /********************************* DL CACHE SLOTS ******************************/ diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/bootscreen_logo_portrait.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/bootscreen_logo_portrait.h new file mode 100644 index 000000000000..6ea317dbc3cd --- /dev/null +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/bootscreen_logo_portrait.h @@ -0,0 +1,42 @@ +/**************************************************************************** + * 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: . * + ****************************************************************************/ + +/** + * This file was auto-generated using "svg2cpp.pl" + * + * The encoding consists of x,y pairs with the min and max scaled to + * 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, + y_min = 0.000000, y_max = 480.000000; + +const PROGMEM uint16_t logo_green[] = {0x8048, 0x46D9, 0x27BC, 0x9DBA, 0xD8D3, 0x9DBA}; +const PROGMEM uint16_t logo_mark[] = {0xDB9F, 0xAC0C, 0xDA6F, 0xAC2D, 0xD970, 0xAC91, 0xD8C0, 0xAD23, 0xD885, 0xADCF, 0xD8C0, 0xAE7A, 0xD970, 0xAF0C, 0xDA6F, 0xAF6F, 0xDB9F, 0xAF8F, 0xDCCE, 0xAF6F, 0xDDD0, 0xAF0C, 0xDE7D, 0xAE7B, 0xDEB9, 0xADCF, 0xDE7D, 0xAD22, 0xDDD0, 0xAC91, 0xDCCE, 0xAC2D, 0xFFFF, 0xDB9F, 0xABC3, 0xDCFE, 0xABEA, 0xDE28, 0xAC5E, 0xDEF1, 0xAD06, 0xDF36, 0xADCF, 0xDEF1, 0xAE95, 0xDE28, 0xAF3E, 0xDCFE, 0xAFB1, 0xDB9F, 0xAFD8, 0xDA3F, 0xAFB1, 0xD916, 0xAF3E, 0xD849, 0xAE95, 0xD808, 0xADCF, 0xD849, 0xAD06, 0xD916, 0xAC5E, 0xDA3F, 0xABEA, 0xFFFF, 0xDB7D, 0xACE6, 0xDAE4, 0xACE6, 0xDAE4, 0xADA9, 0xDB7D, 0xADA9, 0xDC3B, 0xAD94, 0xDC71, 0xAD48, 0xDC3B, 0xACFD, 0xFFFF, 0xDB85, 0xAC9E, 0xDCCB, 0xACC8, 0xDD37, 0xAD47, 0xDCF6, 0xADAC, 0xDC3E, 0xADDE, 0xDC85, 0xADFF, 0xDCE8, 0xAE4E, 0xDD92, 0xAEEA, 0xDCBD, 0xAEEA, 0xDC1E, 0xAE58, 0xDBA7, 0xAE03, 0xDB36, 0xADEF, 0xDAE4, 0xADEF, 0xDAE4, 0xAEEA, 0xDA26, 0xAEEA, 0xDA26, 0xAC9E}; +const PROGMEM uint16_t logo_type[] = {0xD8D5, 0xA520, 0xD8A5, 0xA563, 0xD82E, 0xA57F, 0xD348, 0xA57F, 0xD2D1, 0xA598, 0xD2A0, 0xA5D9, 0xD2A0, 0xAF7A, 0xD274, 0xAFBE, 0xD202, 0xAFDA, 0xCD37, 0xAFDA, 0xCCBF, 0xAFBE, 0xCC8F, 0xAF7A, 0xCC8F, 0xA5D9, 0xCC63, 0xA598, 0xCBF1, 0xA57F, 0xC70B, 0xA57F, 0xC694, 0xA563, 0xC664, 0xA520, 0xC664, 0xA28C, 0xC70B, 0xA22C, 0xD82E, 0xA22C, 0xD8A5, 0xA248, 0xD8D5, 0xA28C, 0xFFFF, 0xB138, 0xAC8C, 0xB952, 0xAC8C, 0xB952, 0xA57F, 0xB138, 0xA57F, 0xFFFF, 0xBF27, 0xA421, 0xBF57, 0xA476, 0xBF6D, 0xA4D0, 0xBF6D, 0xAD36, 0xBF57, 0xAD90, 0xBF27, 0xADE6, 0xBBFA, 0xAFB2, 0xBB60, 0xAFCF, 0xBABD, 0xAFDA, 0xAFCE, 0xAFDA, 0xAF30, 0xAFCF, 0xAE9A, 0xAFB2, 0xAB6E, 0xADE6, 0xAB39, 0xAD90, 0xAB28, 0xAD36, 0xAB28, 0xA4D0, 0xAB39, 0xA476, 0xAB6E, 0xA421, 0xAE9A, 0xA255, 0xAF30, 0xA239, 0xAFCE, 0xA22C, 0xBABD, 0xA22C, 0xBB60, 0xA239, 0xBBFA, 0xA255, 0xFFFF, 0x93A4, 0xACDC, 0x9CEA, 0xACDC, 0x9CEA, 0xAA34, 0x93A4, 0xAA34, 0x93A4, 0xACDC, 0xFFFF, 0x93A4, 0xA796, 0x9CEA, 0xA796, 0x9CEA, 0xA525, 0x93A4, 0xA525, 0xFFFF, 0xA227, 0xA421, 0xA258, 0xA478, 0xA26E, 0xA4D5, 0xA26E, 0xA700, 0xA24F, 0xA757, 0xA204, 0xA7A5, 0xA089, 0xA8B8, 0xA061, 0xA903, 0xA092, 0xA949, 0xA1FC, 0xAA43, 0xA24B, 0xAA91, 0xA26E, 0xAAE8, 0xA26E, 0xAD36, 0xA258, 0xAD90, 0xA227, 0xADE6, 0x9EFC, 0xAFB2, 0x9E61, 0xAFCF, 0x9DBE, 0xAFDA, 0x8ED0, 0xAFDA, 0x8E28, 0xAF7A, 0x8E28, 0xA28C, 0x8E59, 0xA248, 0x8ED0, 0xA22C, 0x9DBE, 0xA22C, 0x9E61, 0xA239, 0x9EFC, 0xA255, 0xFFFF, 0x853C, 0xA502, 0x8517, 0xA557, 0x84C9, 0xA5A2, 0x7994, 0xACC8, 0x8494, 0xACC8, 0x850A, 0xACE4, 0x853C, 0xAD27, 0x853C, 0xAF7A, 0x850A, 0xAFBE, 0x8494, 0xAFDA, 0x7371, 0xAFDA, 0x72C9, 0xAF7A, 0x72C9, 0xAD09, 0x72E8, 0xACB2, 0x7333, 0xAC64, 0x7EA5, 0xA53E, 0x73A6, 0xA53E, 0x732F, 0xA522, 0x72FE, 0xA4DF, 0x72FE, 0xA28C, 0x732F, 0xA248, 0x73A6, 0xA22C, 0x8494, 0xA22C, 0x850A, 0xA248, 0x853C, 0xA28C, 0xFFFF, 0x6B68, 0xAC87, 0x6BDB, 0xACA3, 0x6C07, 0xACE6, 0x6C07, 0xAF7A, 0x6BDB, 0xAFBE, 0x6B68, 0xAFDA, 0x5C84, 0xAFDA, 0x5BDC, 0xAF7A, 0x5BDC, 0xA28C, 0x5C84, 0xA22C, 0x6146, 0xA22C, 0x61EE, 0xA28C, 0x61EE, 0xAC2D, 0x621E, 0xAC6E, 0x6295, 0xAC87, 0xFFFF, 0x52C6, 0xA248, 0x52F7, 0xA28C, 0x52F7, 0xAD45, 0x52EE, 0xAD45, 0x52DC, 0xAD9B, 0x52B1, 0xADE6, 0x4F85, 0xAFB2, 0x4EEA, 0xAFCF, 0x4E47, 0xAFDA, 0x4359, 0xAFDA, 0x42BA, 0xAFCF, 0x4224, 0xAFB2, 0x3EF8, 0xADE6, 0x3EC3, 0xAD90, 0x3EB2, 0xAD36, 0x3EB2, 0xA28C, 0x3EE2, 0xA248, 0x3F5A, 0xA22C, 0x441B, 0xA22C, 0x4493, 0xA248, 0x44C3, 0xA28C, 0x44C3, 0xAC2D, 0x44F4, 0xAC71, 0x456B, 0xAC8C, 0x4C3E, 0xAC8C, 0x4CB1, 0xAC71, 0x4CDD, 0xAC2D, 0x4CDD, 0xA28C, 0x4D0D, 0xA248, 0x4D85, 0xA22C, 0x524F, 0xA22C, 0xFFFF, 0x3748, 0xAC87, 0x37BB, 0xACA3, 0x37E7, 0xACE6, 0x37E7, 0xAF7A, 0x37BB, 0xAFBE, 0x3748, 0xAFDA, 0x2864, 0xAFDA, 0x27BC, 0xAF7A, 0x27BC, 0xA28C, 0x2864, 0xA22C, 0x2D26, 0xA22C, 0x2DCD, 0xA28C, 0x2DCD, 0xAC2D, 0x2DFE, 0xAC6E, 0x2E75, 0xAC87}; +const PROGMEM uint16_t logo_black[] = {0x8048, 0x527A, 0x8ADE, 0x5CDE, 0x75B2, 0x5CDE, 0xFFFF, 0x8048, 0x4FF6, 0x71D9, 0x5E20, 0x8EB8, 0x5E20, 0x8048, 0x4FF6, 0xFFFF, 0x4436, 0x8D8E, 0x4ECC, 0x97F2, 0x39A0, 0x97F2, 0xFFFF, 0x4436, 0x8B0A, 0x35C8, 0x9934, 0x52A5, 0x9934, 0xFFFF, 0xBC3D, 0x8D8E, 0xC6D4, 0x97F2, 0xB1A7, 0x97F2, 0xFFFF, 0xBC3D, 0x8B0A, 0xADCE, 0x9934, 0xCAAC, 0x9934, 0xFFFF, 0x8045, 0x6778, 0x7F6D, 0x67A7, 0x7E9D, 0x689F, 0x7D49, 0x69EA, 0x7B41, 0x6A81, 0x7908, 0x6A3A, 0x7726, 0x692C, 0x75EA, 0x685A, 0x7505, 0x684C, 0x744A, 0x6899, 0x73F5, 0x69A8, 0x7345, 0x6B1A, 0x7193, 0x6BF8, 0x6F4D, 0x6C08, 0x6CFA, 0x6B45, 0x6B61, 0x6AA3, 0x6A7D, 0x6AB7, 0x69EB, 0x6B1D, 0x6A1D, 0x6C34, 0x6A22, 0x6DB8, 0x68E5, 0x6ECD, 0x66B9, 0x6F33, 0x6417, 0x6EC5, 0x6239, 0x6E5C, 0x6165, 0x6E91, 0x6108, 0x6F09, 0x61C1, 0x7018, 0x6282, 0x7196, 0x61CF, 0x72D1, 0x5FE5, 0x7384, 0x5D38, 0x7380, 0x5B4B, 0x7365, 0x5A97, 0x73B7, 0x5A74, 0x7438, 0x5B90, 0x7520, 0x5CE8, 0x7671, 0x5CCB, 0x77BB, 0x5B43, 0x78B0, 0x58B6, 0x7914, 0x56D7, 0x7944, 0x564F, 0x79AD, 0x5667, 0x7A2F, 0x57DA, 0x7AE3, 0x59B7, 0x7BF3, 0x5A31, 0x7D37, 0x5927, 0x7E5D, 0x56E0, 0x7F1E, 0x5529, 0x7F93, 0x54D7, 0x800D, 0x5529, 0x8087, 0x56E0, 0x80FD, 0x5926, 0x81BE, 0x5A30, 0x82E5, 0x59B5, 0x8428, 0x57D8, 0x8538, 0x5664, 0x85EB, 0x564C, 0x866D, 0x56D4, 0x86D7, 0x58B2, 0x8708, 0x5B3F, 0x876B, 0x5CC6, 0x8860, 0x5CE3, 0x89AA, 0x5B8B, 0x8AFC, 0x5A6D, 0x8BE3, 0x5A91, 0x8C65, 0x5B44, 0x8CB7, 0x5D32, 0x8C9C, 0x5FDE, 0x8C98, 0x61C7, 0x8D4B, 0x627A, 0x8E87, 0x61B9, 0x9005, 0x60FF, 0x9114, 0x615C, 0x918B, 0x622F, 0x91C0, 0x640E, 0x9158, 0x66B0, 0x90EA, 0x68DC, 0x9150, 0x6A18, 0x9266, 0x6A12, 0x93E9, 0x69E0, 0x9501, 0x6A72, 0x9567, 0x6B56, 0x957B, 0x6CEE, 0x94D9, 0x6F43, 0x9417, 0x7188, 0x9428, 0x7339, 0x9506, 0x73E9, 0x9678, 0x743E, 0x9787, 0x74F8, 0x97D4, 0x75DD, 0x97C6, 0x771A, 0x96F4, 0x78FB, 0x95E6, 0x7B35, 0x95A1, 0x7D3D, 0x9637, 0x7E91, 0x9782, 0x7F60, 0x987A, 0x8038, 0x98AA, 0x810F, 0x987B, 0x81DF, 0x9782, 0x8333, 0x9638, 0x853B, 0x95A1, 0x8775, 0x95E7, 0x8956, 0x96F5, 0x8A92, 0x97C8, 0x8B78, 0x97D6, 0x8C32, 0x9789, 0x8C88, 0x967A, 0x8D37, 0x9508, 0x8EE9, 0x942A, 0x912F, 0x941A, 0x9383, 0x94DD, 0x951B, 0x957F, 0x95FF, 0x956B, 0x9690, 0x9505, 0x9660, 0x93ED, 0x9659, 0x926A, 0x9797, 0x9154, 0x99C3, 0x90EF, 0x9C65, 0x915D, 0x9E43, 0x91C6, 0x9F17, 0x9191, 0x9F74, 0x9119, 0x9EBB, 0x900A, 0x9DFA, 0x8E8C, 0x9EAE, 0x8D51, 0xA098, 0x8C9E, 0xA345, 0x8CA2, 0xA531, 0x8CBE, 0xA5E5, 0x8C6B, 0xA609, 0x8BEA, 0xA4EC, 0x8B02, 0xA394, 0x89B1, 0xA3B2, 0x8867, 0xA53A, 0x8772, 0xA7C6, 0x870E, 0xA9A5, 0x86DE, 0xAA2D, 0x8675, 0xAA14, 0x85F2, 0xA8A2, 0x853F, 0xA6C5, 0x842E, 0xA64B, 0x82EB, 0xA755, 0x81C5, 0xA99C, 0x8104, 0xAB52, 0x808F, 0xABA6, 0x8015, 0xAB52, 0x7F9B, 0xA99C, 0x7F25, 0xA755, 0x7E64, 0xA64C, 0x7D3E, 0xA6C7, 0x7BFA, 0xA8A5, 0x7AEA, 0xAA18, 0x7A37, 0xAA31, 0x79B5, 0xA9A9, 0x794B, 0xA7CA, 0x791B, 0xA53C, 0x78B7, 0xA3B6, 0x77C1, 0xA39A, 0x7677, 0xA4F1, 0x7526, 0xA60E, 0x743F, 0xA5EB, 0x73BD, 0xA538, 0x736B, 0xA34B, 0x7387, 0xA09E, 0x738A, 0x9EB4, 0x72D6, 0x9E02, 0x719B, 0x9EC4, 0x701D, 0x9F7E, 0x6F0E, 0x9F20, 0x6E96, 0x9E4E, 0x6E61, 0x9C6E, 0x6ECA, 0x99CB, 0x6F37, 0x97A0, 0x6ED2, 0x9664, 0x6DBC, 0x966B, 0x6C38, 0x969B, 0x6B21, 0x960B, 0x6ABB, 0x9526, 0x6AA6, 0x938E, 0x6B48, 0x913B, 0x6C0B, 0x8EF4, 0x6BFA, 0x8D43, 0x6B1D, 0x8C94, 0x69AA, 0x8C3F, 0x689B, 0x8B85, 0x684D, 0x8A9E, 0x685C, 0x8962, 0x692E, 0x8781, 0x6A3C, 0x8546, 0x6A82, 0x833F, 0x69EA, 0x81EC, 0x68A0, 0x811C, 0x67A8, 0x8045, 0x6778, 0x8045, 0x6778, 0xFFFF, 0x8047, 0x6AA0, 0x81C8, 0x6AFA, 0x8268, 0x6BD5, 0x81C8, 0x6CAF, 0x8047, 0x6D09, 0x7EC6, 0x6CAF, 0x7E27, 0x6BD5, 0x7EC6, 0x6AFA, 0x8047, 0x6AA0, 0x8047, 0x6AA0, 0xFFFF, 0x803E, 0x6E19, 0x867C, 0x6E71, 0x8C65, 0x6F75, 0x91D7, 0x711B, 0x96AD, 0x735B, 0x9ABC, 0x762C, 0x9DA2, 0x794C, 0x9F5F, 0x7CA2, 0x9FF3, 0x8011, 0x9F5E, 0x8380, 0x9DA1, 0x86D5, 0x9ABA, 0x89F6, 0x96AB, 0x8CC7, 0x91D6, 0x8F08, 0x8C65, 0x90AD, 0x867C, 0x91B1, 0x803D, 0x9209, 0x7A00, 0x91B1, 0x7416, 0x90AD, 0x6EA6, 0x8F08, 0x69D0, 0x8CC7, 0x65D6, 0x8A0A, 0x62EE, 0x86F4, 0x6125, 0x839B, 0x6089, 0x8011, 0x6124, 0x7C88, 0x62ED, 0x792E, 0x65D6, 0x7619, 0x69CF, 0x735B, 0x6EA5, 0x711B, 0x7416, 0x6F75, 0x7A00, 0x6E71, 0x803E, 0x6E19, 0x803E, 0x6E19, 0xFFFF, 0x803E, 0x6EB2, 0x7A5A, 0x6F04, 0x74B2, 0x6FF8, 0x6F4B, 0x7194, 0x6A8F, 0x73C7, 0x66A2, 0x7681, 0x63D5, 0x7986, 0x6226, 0x7CBF, 0x6197, 0x8011, 0x6226, 0x8363, 0x63D5, 0x869C, 0x66A2, 0x89A2, 0x6A8F, 0x8C5B, 0x6F4B, 0x8E8E, 0x74B2, 0x902B, 0x7A5A, 0x911E, 0x803D, 0x9170, 0x803E, 0x9170, 0x8621, 0x911E, 0x8BCA, 0x902B, 0x9130, 0x8E8E, 0x95ED, 0x8C5B, 0x99CF, 0x89AB, 0x9CA7, 0x869C, 0x9E55, 0x8367, 0x9EE5, 0x8011, 0x9E55, 0x7CBB, 0x9CA7, 0x7986, 0x99CF, 0x7677, 0x95ED, 0x73C7, 0x9130, 0x7194, 0x8BCA, 0x6FF8, 0x8621, 0x6F04, 0x803E, 0x6EB2, 0x803E, 0x6EB2, 0xFFFF, 0x80BC, 0x6FD7, 0x80AF, 0x71D8, 0x7FC8, 0x71D9, 0x7FB7, 0x6FD8, 0x80BC, 0x6FD7, 0x80BC, 0x6FD7, 0xFFFF, 0x83CB, 0x6FF6, 0x84CD, 0x700B, 0x843E, 0x7206, 0x835B, 0x71F4, 0xFFFF, 0x7CA9, 0x6FF8, 0x7D1A, 0x71F5, 0x7C37, 0x7207, 0x7BA7, 0x700D, 0x7CA9, 0x6FF8, 0x7CA9, 0x6FF8, 0xFFFF, 0x87CD, 0x7068, 0x88C7, 0x7092, 0x87BA, 0x727C, 0x86DF, 0x7258, 0xFFFF, 0x78A8, 0x706B, 0x7997, 0x725A, 0x78BA, 0x727E, 0x77AD, 0x7095, 0x78A8, 0x706B, 0x78A8, 0x706B, 0xFFFF, 0x6700, 0x708A, 0x6880, 0x70E5, 0x6920, 0x71BF, 0x6880, 0x7299, 0x66FF, 0x72F4, 0x657F, 0x7299, 0x64E0, 0x71BF, 0x657F, 0x70E4, 0x6700, 0x708A, 0x6700, 0x708A, 0xFFFF, 0x998D, 0x708C, 0x9B0E, 0x70E6, 0x9BAE, 0x71C0, 0x9B0E, 0x729B, 0x998D, 0x72F6, 0x980D, 0x729B, 0x976E, 0x71C1, 0x980D, 0x70E7, 0x998D, 0x708C, 0x998D, 0x708C, 0xFFFF, 0x8BA7, 0x712C, 0x8C95, 0x716A, 0x8B10, 0x7339, 0x8A3F, 0x7303, 0x8BA7, 0x712C, 0xFFFF, 0x74CE, 0x712F, 0x7635, 0x7307, 0x7564, 0x733C, 0x73DE, 0x716D, 0x74CE, 0x712F, 0x74CE, 0x712F, 0xFFFF, 0x8F47, 0x723F, 0x9023, 0x728E, 0x8E2D, 0x743A, 0x8D6B, 0x73F4, 0x8F47, 0x723F, 0xFFFF, 0x712D, 0x7242, 0x7308, 0x73F7, 0x7248, 0x743D, 0x7050, 0x7292, 0x712D, 0x7242, 0x712D, 0x7242, 0xFFFF, 0x803E, 0x72F6, 0x891B, 0x73F4, 0x909A, 0x76CC, 0x959F, 0x7B0B, 0x975E, 0x8011, 0x959F, 0x8517, 0x909A, 0x8957, 0x891B, 0x8C2E, 0x803E, 0x8D2B, 0x7761, 0x8C2E, 0x6FE2, 0x8957, 0x6ADD, 0x8517, 0x691E, 0x8011, 0x6ADD, 0x7B0B, 0x6FE2, 0x76CC, 0x7761, 0x73F4, 0x803E, 0x72F6, 0x803E, 0x72F6, 0xFFFF, 0x803E, 0x738F, 0x77C8, 0x7481, 0x70A0, 0x7738, 0x6BD7, 0x7B46, 0x6A2C, 0x8011, 0x6BD7, 0x84DC, 0x70A1, 0x88EA, 0x77C9, 0x8BA1, 0x803E, 0x8C93, 0x88B4, 0x8BA1, 0x8FDB, 0x88EA, 0x94A5, 0x84DD, 0x9650, 0x8011, 0x94A5, 0x7B46, 0x8FDB, 0x7738, 0x88B4, 0x7481, 0x803E, 0x738F, 0x803E, 0x738F, 0xFFFF, 0x929B, 0x739A, 0x935C, 0x73FA, 0x9100, 0x7578, 0x905A, 0x7527, 0x9175, 0x745E, 0xFFFF, 0x6DDC, 0x739D, 0x7022, 0x7527, 0x6F74, 0x757C, 0x6D16, 0x73FF, 0x6DDC, 0x739D, 0x6DDC, 0x739D, 0xFFFF, 0x9589, 0x7533, 0x9634, 0x75A4, 0x937E, 0x76ED, 0x92E8, 0x768B, 0xFFFF, 0x6AEB, 0x7539, 0x6D8D, 0x7690, 0x6CFB, 0x76F0, 0x6CEC, 0x76FA, 0x6BED, 0x7674, 0x6A40, 0x75A9, 0x6A45, 0x75A7, 0x6AEB, 0x7539, 0x6AEB, 0x7539, 0xFFFF, 0x980B, 0x7707, 0x989A, 0x7784, 0x9597, 0x7892, 0x951A, 0x7825, 0xFFFF, 0x686A, 0x770C, 0x6B5B, 0x782A, 0x6ADF, 0x7897, 0x67DD, 0x7788, 0x686A, 0x770C, 0x686A, 0x770C, 0xFFFF, 0x9A12, 0x790A, 0x9A7E, 0x7991, 0x9740, 0x7A5E, 0x96E1, 0x79E8, 0x9A12, 0x790A, 0xFFFF, 0x6664, 0x790F, 0x6996, 0x79ED, 0x6937, 0x7A63, 0x65F9, 0x7996, 0x6664, 0x790F, 0x6664, 0x790F, 0xFFFF, 0x9B91, 0x7B32, 0x9BDB, 0x7BC1, 0x9870, 0x7C48, 0x9831, 0x7BCB, 0xFFFF, 0x64E6, 0x7B37, 0x6847, 0x7BD0, 0x6807, 0x7C4C, 0x649D, 0x7BC5, 0x64E6, 0x7B37, 0x64E6, 0x7B37, 0xFFFF, 0x9C82, 0x7D72, 0x9CA7, 0x7E06, 0x9925, 0x7E46, 0x9903, 0x7DC5, 0xFFFF, 0x63F7, 0x7D78, 0x6776, 0x7DC9, 0x6756, 0x7E49, 0x63D3, 0x7E0A, 0x63F7, 0x7D78, 0x63F7, 0x7D78, 0xFFFF, 0x5C87, 0x7EDB, 0x5E08, 0x7F35, 0x5EA8, 0x800F, 0x5E08, 0x80E9, 0x5C87, 0x8144, 0x5C85, 0x8144, 0x5B06, 0x80E9, 0x5A67, 0x800F, 0x5B06, 0x7F35, 0x5C87, 0x7EDB, 0x5C87, 0x7EDB, 0xFFFF, 0xA402, 0x7EDE, 0xA583, 0x7F38, 0xA623, 0x8011, 0xA623, 0x8013, 0xA583, 0x80EC, 0xA402, 0x8147, 0xA281, 0x80ED, 0xA1E2, 0x8013, 0xA281, 0x7F38, 0xA402, 0x7EDE, 0xA402, 0x7EDE, 0xFFFF, 0x9CE0, 0x7FC0, 0x9CE0, 0x8055, 0x9957, 0x804D, 0x9957, 0x7FCB, 0xFFFF, 0x639D, 0x7FC5, 0x6726, 0x7FCE, 0x6726, 0x8051, 0x639D, 0x805A, 0x639D, 0x7FC5, 0x639D, 0x7FC5, 0xFFFF, 0x9927, 0x81D1, 0x9CAA, 0x8210, 0x9C87, 0x82A2, 0x9907, 0x8252, 0x9927, 0x81D1, 0x9927, 0x81D1, 0xFFFF, 0x6757, 0x81D5, 0x6777, 0x8255, 0x63F9, 0x82A7, 0x63D4, 0x8214, 0xFFFF, 0x9877, 0x83CF, 0x9BE2, 0x8455, 0x9B99, 0x84E3, 0x9838, 0x844C, 0x9877, 0x83CF, 0x9877, 0x83CF, 0xFFFF, 0x6808, 0x83D3, 0x6848, 0x8450, 0x64E7, 0x84E8, 0x649E, 0x845A, 0xFFFF, 0x9749, 0x85B9, 0x9A88, 0x8684, 0x9A1D, 0x870C, 0x96EB, 0x862E, 0x9749, 0x85B9, 0x9749, 0x85B9, 0xFFFF, 0x6938, 0x85BD, 0x6997, 0x8634, 0x6665, 0x8710, 0x65F9, 0x8689, 0xFFFF, 0x95A2, 0x8785, 0x98A5, 0x8892, 0x9818, 0x890F, 0x9527, 0x87F2, 0x95A2, 0x8785, 0x95A2, 0x8785, 0xFFFF, 0x6ADF, 0x878A, 0x6B5B, 0x87F8, 0x686A, 0x8914, 0x67DC, 0x8897, 0x6ADF, 0x878A, 0xFFFF, 0x6CF7, 0x892F, 0x6D8D, 0x8991, 0x6AEB, 0x8AE9, 0x6A40, 0x8A79, 0xFFFF, 0x9380, 0x8932, 0x9645, 0x8A72, 0x963E, 0x8A77, 0x9599, 0x8AE3, 0x92F5, 0x898D, 0x9380, 0x8932, 0x9380, 0x8932, 0xFFFF, 0x9110, 0x8AA1, 0x936F, 0x8C1F, 0x92AA, 0x8C80, 0x9064, 0x8AF7, 0x9110, 0x8AA1, 0x9110, 0x8AA1, 0xFFFF, 0x6F73, 0x8AA5, 0x7021, 0x8AFB, 0x7035, 0x8B04, 0x6DED, 0x8C8B, 0x6DE1, 0x8C87, 0x6D17, 0x8C23, 0xFFFF, 0x8E3E, 0x8BE1, 0x9037, 0x8D8B, 0x8F59, 0x8DDC, 0x8D7C, 0x8C27, 0x8E3E, 0x8BE1, 0x8E3E, 0x8BE1, 0xFFFF, 0x7259, 0x8BEB, 0x731B, 0x8C31, 0x7140, 0x8DE7, 0x7064, 0x8D97, 0xFFFF, 0x8B21, 0x8CE3, 0x8CA9, 0x8EB2, 0x8BBA, 0x8EEF, 0x8A51, 0x8D18, 0x8B21, 0x8CE3, 0x8B21, 0x8CE3, 0xFFFF, 0x7576, 0x8CEB, 0x7648, 0x8D20, 0x74E0, 0x8EF8, 0x73F2, 0x8EBB, 0xFFFF, 0x66F3, 0x8D2F, 0x6874, 0x8D8A, 0x687D, 0x8D8F, 0x6886, 0x8D94, 0x6926, 0x8E6E, 0x6887, 0x8F48, 0x6705, 0x8FA2, 0x6584, 0x8F49, 0x657F, 0x8F45, 0x6570, 0x8F3E, 0x6573, 0x8F3E, 0x64D3, 0x8E63, 0x6573, 0x8D89, 0x66F3, 0x8D2F, 0x66F3, 0x8D2F, 0xFFFF, 0x9993, 0x8D31, 0x9B13, 0x8D8C, 0x9BB4, 0x8E66, 0x9B16, 0x8F40, 0x9993, 0x8F9A, 0x9814, 0x8F40, 0x9774, 0x8E66, 0x9812, 0x8D8C, 0x9993, 0x8D31, 0x9993, 0x8D31, 0xFFFF, 0x87CD, 0x8DA1, 0x88DC, 0x8F8B, 0x87E0, 0x8FB5, 0x86F0, 0x8DC6, 0x87CD, 0x8DA1, 0x87CD, 0x8DA1, 0xFFFF, 0x78CD, 0x8DA8, 0x79A8, 0x8DCB, 0x78BC, 0x8FBB, 0x77C1, 0x8F92, 0xFFFF, 0x8450, 0x8E19, 0x84E2, 0x9014, 0x83E0, 0x9029, 0x836C, 0x8E2C, 0x8450, 0x8E19, 0x8450, 0x8E19, 0xFFFF, 0x7C48, 0x8E1C, 0x7D2B, 0x8E2E, 0x7CBD, 0x902C, 0x7BBB, 0x9017, 0x7C48, 0x8E1C, 0xFFFF, 0x80BF, 0x8E49, 0x80D2, 0x904A, 0x7FCC, 0x904A, 0x7FD9, 0x8E49, 0x80BF, 0x8E49, 0x80BF, 0x8E49, 0xFFFF, 0x804F, 0x9321, 0x81D0, 0x937A, 0x8271, 0x9455, 0x81D1, 0x952F, 0x8051, 0x958A, 0x7ECF, 0x9530, 0x7E2F, 0x9456, 0x7ECE, 0x937B, 0x804F, 0x9321, 0x804F, 0x9321, 0xFFFF, 0x8048, 0x46D9, 0x27BC, 0x9DBA, 0xD8D3, 0x9DBA, 0xFFFF, 0x8048, 0x4BC9, 0x952E, 0x604A, 0x6B62, 0x604A, 0xFFFF, 0x68D2, 0x62CE, 0x97BF, 0x62CE, 0xB9BA, 0x8427, 0xA239, 0x9B36, 0x5E16, 0x9B36, 0x46B6, 0x8446, 0x68D2, 0x62CE, 0xFFFF, 0xBC3E, 0x869F, 0xD13B, 0x9B36, 0xA742, 0x9B36, 0xFFFF, 0x4431, 0x86BE, 0x590E, 0x9B36, 0x2F54, 0x9B36, 0x4431, 0x86BE}; +const PROGMEM uint16_t logo_white[] = {0x80BC, 0x6FD7, 0x80AF, 0x71D8, 0x7FC8, 0x71D9, 0x7FB7, 0x6FD8, 0x80BC, 0x6FD7, 0xFFFF, 0x83CB, 0x6FF6, 0x84CD, 0x700B, 0x843E, 0x7206, 0x835B, 0x71F4, 0xFFFF, 0x7CA9, 0x6FF8, 0x7D1A, 0x71F5, 0x7C37, 0x7207, 0x7BA7, 0x700D, 0x7CA9, 0x6FF8, 0x7CA9, 0x6FF8, 0xFFFF, 0x87CD, 0x7068, 0x88C7, 0x7092, 0x87BA, 0x727C, 0x86DF, 0x7258, 0xFFFF, 0x78A8, 0x706B, 0x7997, 0x725A, 0x78BA, 0x727E, 0x77AD, 0x7095, 0x78A8, 0x706B, 0x78A8, 0x706B, 0xFFFF, 0x8BA7, 0x712C, 0x8C95, 0x716A, 0x8B10, 0x7339, 0x8A3F, 0x7303, 0xFFFF, 0x74CE, 0x712F, 0x7635, 0x7307, 0x7564, 0x733C, 0x73DE, 0x716D, 0x74CE, 0x712F, 0x74CE, 0x712F, 0xFFFF, 0x8F47, 0x723F, 0x9023, 0x728E, 0x8E2D, 0x743A, 0x8D6B, 0x73F4, 0xFFFF, 0x712D, 0x7242, 0x7309, 0x73F7, 0x7248, 0x743D, 0x7050, 0x7292, 0x712D, 0x7242, 0x712D, 0x7242, 0xFFFF, 0x929B, 0x739A, 0x935C, 0x73FA, 0x9100, 0x7578, 0x905A, 0x7527, 0xFFFF, 0x6DDC, 0x739D, 0x7022, 0x7527, 0x6F74, 0x757C, 0x6D16, 0x73FF, 0x6DDC, 0x739D, 0x6DDC, 0x739D, 0xFFFF, 0x9589, 0x7533, 0x9634, 0x75A4, 0x937E, 0x76ED, 0x92E8, 0x768B, 0xFFFF, 0x6AEB, 0x7539, 0x6D8D, 0x7690, 0x6CFB, 0x76F0, 0x6A40, 0x75A9, 0x6AEB, 0x7539, 0xFFFF, 0x980B, 0x7707, 0x989A, 0x7784, 0x9597, 0x7892, 0x951A, 0x7825, 0xFFFF, 0x686A, 0x770C, 0x6B5B, 0x782A, 0x6ADF, 0x7897, 0x67DD, 0x7788, 0x686A, 0x770C, 0x686A, 0x770C, 0xFFFF, 0x9A12, 0x790A, 0x9A7E, 0x7991, 0x9740, 0x7A5E, 0x96E1, 0x79E8, 0xFFFF, 0x6664, 0x790F, 0x6996, 0x79ED, 0x6937, 0x7A63, 0x65F9, 0x7996, 0x6664, 0x790F, 0x6664, 0x790F, 0xFFFF, 0x9B91, 0x7B32, 0x9BDB, 0x7BC1, 0x9870, 0x7C48, 0x9831, 0x7BCC, 0xFFFF, 0x64E6, 0x7B37, 0x6847, 0x7BD0, 0x6807, 0x7C4C, 0x649D, 0x7BC5, 0x64E6, 0x7B37, 0x64E6, 0x7B37, 0xFFFF, 0x9C82, 0x7D72, 0x9CA7, 0x7E06, 0x9925, 0x7E46, 0x9903, 0x7DC5, 0xFFFF, 0x63F7, 0x7D78, 0x6776, 0x7DC9, 0x6756, 0x7E49, 0x63D3, 0x7E0A, 0x63F7, 0x7D78, 0x63F7, 0x7D78, 0xFFFF, 0x9CE0, 0x7FC0, 0x9CE0, 0x8055, 0x9957, 0x804D, 0x9957, 0x7FCB, 0xFFFF, 0x639D, 0x7FC5, 0x6726, 0x7FCE, 0x6726, 0x8051, 0x639D, 0x805A, 0x639D, 0x7FC5, 0xFFFF, 0x9927, 0x81D1, 0x9CAA, 0x8210, 0x9C87, 0x82A2, 0x9907, 0x8252, 0x9927, 0x81D1, 0x9927, 0x81D1, 0xFFFF, 0x6757, 0x81D5, 0x6777, 0x8256, 0x63F9, 0x82A7, 0x63D4, 0x8214, 0xFFFF, 0x9877, 0x83CF, 0x9BE2, 0x8455, 0x9B99, 0x84E3, 0x9838, 0x844C, 0x9877, 0x83CF, 0xFFFF, 0x6808, 0x83D3, 0x6848, 0x8450, 0x64E7, 0x84E8, 0x649E, 0x845A, 0xFFFF, 0x9749, 0x85B9, 0x9A88, 0x8684, 0x9A1D, 0x870C, 0x96EB, 0x862E, 0x9749, 0x85B9, 0x9749, 0x85B9, 0xFFFF, 0x6938, 0x85BD, 0x6997, 0x8634, 0x6665, 0x8710, 0x65F9, 0x8689, 0xFFFF, 0x95A2, 0x8785, 0x98A5, 0x8892, 0x9818, 0x890F, 0x9527, 0x87F2, 0x95A2, 0x8785, 0x95A2, 0x8785, 0xFFFF, 0x6ADF, 0x878A, 0x6B5B, 0x87F8, 0x686A, 0x8915, 0x67DC, 0x8897, 0xFFFF, 0x6CF7, 0x8930, 0x6D8D, 0x8991, 0x6AEB, 0x8AE9, 0x6A40, 0x8A79, 0xFFFF, 0x9380, 0x8932, 0x9645, 0x8A72, 0x9599, 0x8AE3, 0x92F5, 0x898D, 0x9380, 0x8932, 0xFFFF, 0x9110, 0x8AA1, 0x936F, 0x8C1F, 0x92AA, 0x8C80, 0x9064, 0x8AF7, 0x9110, 0x8AA1, 0x9110, 0x8AA1, 0xFFFF, 0x6F73, 0x8AA5, 0x7021, 0x8AFB, 0x6DED, 0x8C8C, 0x6D17, 0x8C23, 0xFFFF, 0x8E3E, 0x8BE1, 0x9037, 0x8D8B, 0x8F59, 0x8DDC, 0x8D7C, 0x8C27, 0x8E3E, 0x8BE1, 0x8E3E, 0x8BE1, 0xFFFF, 0x7259, 0x8BEB, 0x731B, 0x8C31, 0x7140, 0x8DE7, 0x7064, 0x8D97, 0xFFFF, 0x8B21, 0x8CE3, 0x8CA9, 0x8EB2, 0x8BBA, 0x8EEF, 0x8A51, 0x8D18, 0x8B21, 0x8CE3, 0x8B21, 0x8CE3, 0xFFFF, 0x7576, 0x8CEB, 0x7648, 0x8D20, 0x74E0, 0x8EF8, 0x73F2, 0x8EBB, 0xFFFF, 0x87CD, 0x8DA1, 0x88DC, 0x8F8B, 0x87E0, 0x8FB5, 0x86F0, 0x8DC6, 0x87CD, 0x8DA1, 0x87CD, 0x8DA1, 0xFFFF, 0x78CC, 0x8DA8, 0x79A8, 0x8DCB, 0x78BC, 0x8FBB, 0x77C0, 0x8F92, 0xFFFF, 0x8450, 0x8E19, 0x84E2, 0x9014, 0x83E0, 0x9029, 0x836C, 0x8E2C, 0x8450, 0x8E19, 0x8450, 0x8E19, 0xFFFF, 0x7C48, 0x8E1C, 0x7D2B, 0x8E2E, 0x7CBD, 0x902C, 0x7BBB, 0x9017, 0xFFFF, 0x80BE, 0x8E49, 0x80D1, 0x904A, 0x7FCC, 0x904A, 0x7FD9, 0x8E49, 0x80BE, 0x8E49, 0xFFFF, 0x8276, 0x75D6, 0x83AF, 0x75FE, 0x8436, 0x7628, 0x84AE, 0x7661, 0x8542, 0x7706, 0x8512, 0x77BA, 0x8457, 0x7845, 0x8335, 0x788B, 0x8318, 0x7882, 0x82D8, 0x7860, 0x831E, 0x7830, 0x8353, 0x7823, 0x83E6, 0x77F9, 0x8464, 0x7790, 0x847A, 0x771A, 0x8415, 0x76B7, 0x83B6, 0x7691, 0x8351, 0x7676, 0x827F, 0x7662, 0x81BB, 0x7687, 0x8161, 0x76AF, 0x8123, 0x76DA, 0x80E5, 0x771A, 0x80C5, 0x774D, 0x80B8, 0x77C1, 0x80D1, 0x77EE, 0x8107, 0x7814, 0x81CC, 0x786B, 0x837F, 0x7918, 0x8464, 0x7983, 0x84C0, 0x79B2, 0x852D, 0x79FD, 0x859D, 0x7ABC, 0x858E, 0x7B79, 0x8545, 0x7C25, 0x84D9, 0x7CC5, 0x8469, 0x7D4D, 0x843B, 0x7DCD, 0x8555, 0x7DA8, 0x85D3, 0x7D67, 0x870D, 0x7CA0, 0x87E0, 0x7BC0, 0x880D, 0x7B5B, 0x886D, 0x7A46, 0x88B3, 0x799B, 0x88CC, 0x7970, 0x893A, 0x78EA, 0x8995, 0x78A8, 0x8A01, 0x786F, 0x8AF8, 0x781F, 0x8BA6, 0x77FD, 0x8C0C, 0x77EF, 0x8C96, 0x77FB, 0x8D1D, 0x7815, 0x8D59, 0x7826, 0x8E40, 0x7889, 0x8EDB, 0x7925, 0x8EFC, 0x797B, 0x8EFF, 0x79D4, 0x8E71, 0x7A7B, 0x8D58, 0x7AD2, 0x8C23, 0x7ADE, 0x8AFF, 0x7A97, 0x8AF5, 0x7A81, 0x8AEF, 0x7A4E, 0x8B68, 0x7A52, 0x8B96, 0x7A5F, 0x8C39, 0x7A87, 0x8D33, 0x7A7F, 0x8E07, 0x7A3F, 0x8E66, 0x79CB, 0x8E63, 0x7985, 0x8E43, 0x793F, 0x8DC6, 0x78C6, 0x8CFA, 0x7876, 0x8C7E, 0x785F, 0x8C18, 0x7857, 0x8B84, 0x7874, 0x8B22, 0x788F, 0x8A7D, 0x78CA, 0x8A2E, 0x78F9, 0x89F0, 0x7930, 0x89A3, 0x79A5, 0x8979, 0x7AC0, 0x897C, 0x7B9C, 0x8972, 0x7BF2, 0x88CC, 0x7D32, 0x87B7, 0x7E4C, 0x8665, 0x7F52, 0x8660, 0x7F5A, 0x878F, 0x7F01, 0x88AE, 0x7EC2, 0x89FD, 0x7E9E, 0x8B8D, 0x7EC6, 0x8C40, 0x7F0E, 0x8CB6, 0x7F68, 0x8D1D, 0x7FD7, 0x8DFA, 0x80BD, 0x8EA8, 0x816E, 0x8F34, 0x81D4, 0x8F8A, 0x81F9, 0x8FDA, 0x820A, 0x90AB, 0x820F, 0x9120, 0x81FF, 0x91A5, 0x81DC, 0x91F4, 0x81B8, 0x922C, 0x8198, 0x9288, 0x812B, 0x927D, 0x80AB, 0x9252, 0x8068, 0x921C, 0x8033, 0x9174, 0x7FEB, 0x9099, 0x7FEB, 0x8FCF, 0x8029, 0x8F5D, 0x808D, 0x8F47, 0x80A4, 0x8ED4, 0x80A4, 0x8EC5, 0x8070, 0x8F65, 0x7FE6, 0x906D, 0x7F92, 0x91A4, 0x7F90, 0x92A8, 0x7FF7, 0x92FC, 0x8043, 0x9331, 0x8090, 0x9349, 0x813D, 0x92D1, 0x81E3, 0x9264, 0x8227, 0x91E5, 0x825B, 0x915D, 0x8280, 0x90D3, 0x8296, 0x8FA0, 0x829A, 0x8F2C, 0x8286, 0x8EE7, 0x8273, 0x8E78, 0x824A, 0x8DA9, 0x81D4, 0x8CB9, 0x8127, 0x8B68, 0x802C, 0x8B22, 0x8001, 0x8AC3, 0x7FE7, 0x8A50, 0x7FF4, 0x88FD, 0x8068, 0x87A4, 0x811D, 0x879E, 0x812D, 0x8904, 0x81F1, 0x89D4, 0x8285, 0x8A7C, 0x8343, 0x8A94, 0x8431, 0x8A4E, 0x84A1, 0x89E8, 0x850E, 0x892F, 0x85E5, 0x88B0, 0x86E5, 0x88C0, 0x8757, 0x88F2, 0x878D, 0x8927, 0x87AD, 0x8ABF, 0x8821, 0x8B0E, 0x881E, 0x8B70, 0x8811, 0x8C1B, 0x87D6, 0x8C9B, 0x8776, 0x8CC4, 0x873D, 0x8CD3, 0x8705, 0x8CA2, 0x86A3, 0x8C06, 0x8662, 0x8B39, 0x864F, 0x8A77, 0x8662, 0x89F9, 0x864D, 0x8A10, 0x8606, 0x8A66, 0x85F7, 0x8B35, 0x85DC, 0x8C50, 0x85FD, 0x8D3C, 0x8663, 0x8D94, 0x870A, 0x8D7D, 0x875F, 0x8D3A, 0x87B8, 0x8CB1, 0x882D, 0x8BC1, 0x888C, 0x8B30, 0x88A7, 0x8A8D, 0x88AE, 0x89EE, 0x8898, 0x896E, 0x887E, 0x8869, 0x882D, 0x87EE, 0x87EA, 0x87A4, 0x87A8, 0x878E, 0x8785, 0x874D, 0x86E3, 0x875D, 0x8637, 0x87FD, 0x8466, 0x8705, 0x835A, 0x86B8, 0x8359, 0x84A4, 0x8358, 0x7F20, 0x851B, 0x7F13, 0x864D, 0x8016, 0x86F9, 0x818E, 0x87D8, 0x823B, 0x8869, 0x8272, 0x88C9, 0x8276, 0x8915, 0x8266, 0x893D, 0x81FB, 0x89D8, 0x8197, 0x8A21, 0x8119, 0x8A62, 0x80A7, 0x8A8A, 0x8016, 0x8AAA, 0x7EDC, 0x8AAE, 0x7DC5, 0x8A63, 0x7D55, 0x8A29, 0x7CFA, 0x89E5, 0x7CAD, 0x8939, 0x7D1B, 0x8895, 0x7E00, 0x8825, 0x7F27, 0x8800, 0x7F66, 0x880F, 0x7F69, 0x8850, 0x7E49, 0x8873, 0x7D9A, 0x88C9, 0x7D4F, 0x893E, 0x7D8B, 0x89B2, 0x7DD8, 0x89E6, 0x7E36, 0x8A10, 0x7F02, 0x8A40, 0x7FDB, 0x8A34, 0x8046, 0x8A16, 0x8091, 0x89F5, 0x80A5, 0x89EB, 0x80FE, 0x89AB, 0x8126, 0x8981, 0x8159, 0x8918, 0x814F, 0x88E6, 0x8128, 0x88B8, 0x8094, 0x8856, 0x7EFC, 0x8796, 0x7D74, 0x86E7, 0x7D3D, 0x86C5, 0x7CD8, 0x8674, 0x7C98, 0x8605, 0x7CA0, 0x8536, 0x7D7C, 0x83E6, 0x7E07, 0x8357, 0x7DED, 0x835B, 0x79CC, 0x843E, 0x7962, 0x8448, 0x77CB, 0x8450, 0x76F3, 0x8438, 0x763E, 0x841E, 0x7502, 0x83FE, 0x746C, 0x83FD, 0x73E4, 0x840A, 0x72CE, 0x8444, 0x729B, 0x8457, 0x71E6, 0x84B7, 0x71B5, 0x84EB, 0x719B, 0x853B, 0x719B, 0x8558, 0x71D4, 0x85E0, 0x72B0, 0x8642, 0x73D4, 0x8661, 0x74B3, 0x8616, 0x74AD, 0x84D7, 0x74B2, 0x84B3, 0x74B5, 0x849B, 0x751E, 0x8496, 0x753B, 0x84B8, 0x75C5, 0x856E, 0x756D, 0x865A, 0x74D0, 0x86B8, 0x73FA, 0x86EA, 0x7250, 0x86CF, 0x70E7, 0x863F, 0x707E, 0x85C8, 0x705F, 0x8549, 0x7075, 0x84CC, 0x70AC, 0x8475, 0x70CD, 0x8452, 0x71FF, 0x839C, 0x7287, 0x8376, 0x736A, 0x833A, 0x7443, 0x8319, 0x751E, 0x8311, 0x76AC, 0x8327, 0x77C4, 0x8341, 0x7810, 0x8340, 0x799F, 0x8313, 0x7A2A, 0x82EA, 0x7B24, 0x8281, 0x7BE4, 0x820C, 0x7BEC, 0x81B1, 0x7A5E, 0x81C8, 0x7809, 0x81ED, 0x7751, 0x81F8, 0x7664, 0x81EF, 0x7571, 0x81B4, 0x74BB, 0x8141, 0x7483, 0x80F9, 0x7408, 0x802F, 0x73D9, 0x7FEB, 0x7359, 0x7F50, 0x72A0, 0x7EC4, 0x719E, 0x7E89, 0x7074, 0x7EA8, 0x7015, 0x7ECC, 0x6FD0, 0x7EF8, 0x6FA3, 0x7F19, 0x6F6B, 0x7FBB, 0x6F93, 0x8017, 0x6FA7, 0x8032, 0x6FD7, 0x805A, 0x70DF, 0x8092, 0x7205, 0x805A, 0x729E, 0x7FCB, 0x72B3, 0x7FBC, 0x7309, 0x7FA6, 0x733B, 0x7FDE, 0x72F9, 0x804B, 0x726D, 0x80A7, 0x70E6, 0x80FB, 0x700D, 0x80EC, 0x6F48, 0x80A8, 0x6EFC, 0x8073, 0x6EC1, 0x8026, 0x6E93, 0x7FCC, 0x6ED4, 0x7ED8, 0x6F54, 0x7E72, 0x6FCB, 0x7E3A, 0x700B, 0x7E25, 0x71AB, 0x7DED, 0x7356, 0x7E3E, 0x7472, 0x7EF4, 0x7536, 0x7FBD, 0x75DA, 0x8075, 0x7628, 0x80B6, 0x767B, 0x80D8, 0x76D9, 0x80EF, 0x7755, 0x80FC, 0x7881, 0x80D5, 0x7931, 0x8093, 0x7A00, 0x801E, 0x799B, 0x7D9B, 0x789A, 0x7CD8, 0x77C0, 0x7BE5, 0x7783, 0x7B55, 0x7787, 0x7AB9, 0x77AE, 0x7A67, 0x77E6, 0x7A1D, 0x781E, 0x79CD, 0x785E, 0x7909, 0x7853, 0x78C0, 0x7823, 0x788B, 0x7808, 0x7875, 0x7649, 0x77E8, 0x74B6, 0x7869, 0x7488, 0x78B3, 0x7472, 0x7901, 0x74D2, 0x796F, 0x75D8, 0x799A, 0x76EE, 0x7971, 0x774A, 0x797A, 0x7751, 0x79B4, 0x76A0, 0x79F0, 0x75E4, 0x7A0A, 0x7454, 0x79E1, 0x73AF, 0x7986, 0x7369, 0x7909, 0x7374, 0x7891, 0x739D, 0x783C, 0x73B6, 0x781E, 0x74B7, 0x7768, 0x765D, 0x772C, 0x77ED, 0x7769, 0x7932, 0x77FC, 0x7979, 0x7836, 0x79B8, 0x787B, 0x79DF, 0x7912, 0x7998, 0x7A14, 0x7967, 0x7AB4, 0x796A, 0x7AD8, 0x79C5, 0x7B60, 0x7A9D, 0x7BE9, 0x7B72, 0x7C47, 0x7EBA, 0x7BD6, 0x8206, 0x7CA8, 0x82FA, 0x7C2E, 0x8391, 0x7BB4, 0x83F6, 0x7B40, 0x8413, 0x7AD0, 0x83DD, 0x7A71, 0x838A, 0x7A39, 0x8296, 0x79B7, 0x80F3, 0x78FA, 0x8016, 0x788A, 0x7FB4, 0x7833, 0x7F8D, 0x77DF, 0x7F92, 0x77A9, 0x7FB3, 0x7718, 0x7FF6, 0x76C2, 0x8036, 0x768A, 0x8097, 0x764A, 0x80DF, 0x762A, 0x813C, 0x7605, 0x8275, 0x75D5}; + +#define LOGO_BACKGROUND 0xDEEA5C + +#define LOGO_PAINT_PATHS \ + LOGO_PAINT_PATH(0xC1D82F, logo_green) \ + LOGO_PAINT_PATH(0x000000, logo_black) \ + LOGO_PAINT_PATH(0x000000, logo_type) \ + LOGO_PAINT_PATH(0x000000, logo_mark) \ + LOGO_PAINT_PATH(0xFFFFFF, logo_white) From 9fd06fa7678efd6838fbe7c47e2b65a892be4b2c Mon Sep 17 00:00:00 2001 From: Marcio T Date: Sat, 19 Sep 2020 08:23:56 -0600 Subject: [PATCH 40/44] Fix case light brightness save/load (#19436) --- 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 2c679068b936..3cb88da4eee1 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -138,7 +138,7 @@ void M710_report(const bool forReplay); #endif -#if ENABLED(CASE_LIGHT_MENU) && DISABLED(CASE_LIGHT_NO_BRIGHTNESS) +#if ENABLED(CASE_LIGHT_ENABLE) && DISABLED(CASE_LIGHT_NO_BRIGHTNESS) #include "../feature/caselight.h" #define HAS_CASE_LIGHT_BRIGHTNESS 1 #endif From af8f9f790a34f3a14b3478cd5ae98d219a8cf9e4 Mon Sep 17 00:00:00 2001 From: qwewer0 <57561110+qwewer0@users.noreply.github.com> Date: Sat, 19 Sep 2020 17:17:24 +0200 Subject: [PATCH 41/44] Optional Host Start menu item (#19443) --- Marlin/Configuration_adv.h | 1 + Marlin/src/lcd/menu/menu_main.cpp | 4 ++-- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 35b1dcc563ef..a010856d1871 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -3232,6 +3232,7 @@ //#define HOST_ACTION_COMMANDS #if ENABLED(HOST_ACTION_COMMANDS) //#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/lcd/menu/menu_main.cpp b/Marlin/src/lcd/menu/menu_main.cpp index 334d998d5c6f..5b983825599e 100644 --- a/Marlin/src/lcd/menu/menu_main.cpp +++ b/Marlin/src/lcd/menu/menu_main.cpp @@ -54,7 +54,7 @@ #include "../../feature/password/password.h" #endif -#ifdef ACTION_ON_START +#if ENABLED(HOST_START_MENU_ITEM) && defined(ACTION_ON_START) #include "../../feature/host_actions.h" #endif @@ -162,7 +162,7 @@ void menu_main() { if (TERN0(MACHINE_CAN_PAUSE, printingIsPaused())) ACTION_ITEM(MSG_RESUME_PRINT, ui.resume_print); - #ifdef ACTION_ON_START + #if ENABLED(HOST_START_MENU_ITEM) && defined(ACTION_ON_START) ACTION_ITEM(MSG_HOST_START_PRINT, host_action_start); #endif From 98bcb25fd4494875e6c76a5bacef8b7c2fd452f0 Mon Sep 17 00:00:00 2001 From: ellensp Date: Sun, 20 Sep 2020 03:18:42 +1200 Subject: [PATCH 42/44] Ultratronics Pro SPI pins (#19444) --- Marlin/src/pins/sam/pins_ULTRATRONICS_PRO.h | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/Marlin/src/pins/sam/pins_ULTRATRONICS_PRO.h b/Marlin/src/pins/sam/pins_ULTRATRONICS_PRO.h index 671307bc00cf..75b29629e90d 100644 --- a/Marlin/src/pins/sam/pins_ULTRATRONICS_PRO.h +++ b/Marlin/src/pins/sam/pins_ULTRATRONICS_PRO.h @@ -23,6 +23,7 @@ /** * ReprapWorld ULTRATRONICS v1.0 + * https://reprapworld.com/documentation/datasheet_ultratronics10_05.pdf */ #ifndef ARDUINO_ARCH_SAM @@ -146,6 +147,10 @@ #define SPI_EEPROM2_CS -1 #define SPI_FLASH_CS -1 +#define SCK_PIN 76 +#define MISO_PIN 74 +#define MOSI_PIN 75 + // SPI for Max6675 or Max31855 Thermocouple #define MAX6675_SS_PIN 65 #define MAX31855_SS0 65 From b5e4511de8c4b147d791e90bb102299e77ee4fb0 Mon Sep 17 00:00:00 2001 From: enigmaquip Date: Sat, 19 Sep 2020 09:19:45 -0600 Subject: [PATCH 43/44] Fix Creality DWIN Control menu icons (#19441) --- Marlin/src/lcd/dwin/e3v2/dwin.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/dwin/e3v2/dwin.cpp b/Marlin/src/lcd/dwin/e3v2/dwin.cpp index ca3a5cccffc6..131c96bef1e1 100644 --- a/Marlin/src/lcd/dwin/e3v2/dwin.cpp +++ b/Marlin/src/lcd/dwin/e3v2/dwin.cpp @@ -744,7 +744,7 @@ inline void Draw_Control_Menu() { // Draw icons and lines uint8_t i = 0; - #define _TEMP_ICON(N) do{ ++i; if (CVISI(i)) Draw_Menu_Line(CSCROL(i), ICON_SetEndTemp + (N) - 1); }while(0) + #define _TEMP_ICON(N) do{ ++i; if (CVISI(i)) Draw_Menu_Line(CSCROL(i), ICON_Temperature + (N) - 1); }while(0) _TEMP_ICON(CONTROL_CASE_TEMP); if (CVISI(i)) Draw_More_Icon(CSCROL(i)); From 0c7035d8a3725d799cb286516a1bba40c578d202 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 20 Sep 2020 00:13:46 +0000 Subject: [PATCH 44/44] [cron] Bump distribution date (2020-09-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 0faa1f8b28e4..b33163f5f3c5 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-09-19" + #define STRING_DISTRIBUTION_DATE "2020-09-20" #endif /**