From 0ea26d538bfb883bed57c005a6c0c3a365c31acc Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 31 Mar 2020 00:03:22 +0000 Subject: [PATCH 01/37] [cron] Bump distribution date (2020-03-31) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 7f5c59aeef8e..33b9bbfbea6d 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-03-30" + #define STRING_DISTRIBUTION_DATE "2020-03-31" #endif /** From 96ab16a9dd7167840d9c9a871c43c60bdc7c6b15 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 31 Mar 2020 12:36:59 -0500 Subject: [PATCH 02/37] Pulldown for all FastIO headers Co-Authored-By: borsegbr --- Marlin/src/HAL/AVR/fastio.h | 4 ++-- Marlin/src/HAL/DUE/fastio.h | 2 +- Marlin/src/HAL/ESP32/fastio.h | 2 +- Marlin/src/HAL/LPC1768/fastio.h | 2 +- Marlin/src/HAL/SAMD51/fastio.h | 4 ++-- Marlin/src/HAL/TEENSY31_32/fastio.h | 3 ++- Marlin/src/HAL/TEENSY35_36/fastio.h | 3 ++- .../ftdi_eve_touch_ui/ftdi_eve_lib/compat.h | 21 ++++++++++--------- 8 files changed, 22 insertions(+), 19 deletions(-) diff --git a/Marlin/src/HAL/AVR/fastio.h b/Marlin/src/HAL/AVR/fastio.h index 2246a0f9d09f..a45e0f2bebb7 100644 --- a/Marlin/src/HAL/AVR/fastio.h +++ b/Marlin/src/HAL/AVR/fastio.h @@ -98,9 +98,9 @@ #define SET_INPUT(IO) _SET_INPUT(IO) #define SET_INPUT_PULLUP(IO) do{ _SET_INPUT(IO); _WRITE(IO, HIGH); }while(0) +#define SET_INPUT_PULLDOWN SET_INPUT #define SET_OUTPUT(IO) _SET_OUTPUT(IO) - -#define SET_PWM(IO) SET_OUTPUT(IO) +#define SET_PWM SET_OUTPUT #define IS_INPUT(IO) _IS_INPUT(IO) #define IS_OUTPUT(IO) _IS_OUTPUT(IO) diff --git a/Marlin/src/HAL/DUE/fastio.h b/Marlin/src/HAL/DUE/fastio.h index 6f1f8d8bf2a8..01abd8204946 100644 --- a/Marlin/src/HAL/DUE/fastio.h +++ b/Marlin/src/HAL/DUE/fastio.h @@ -166,7 +166,7 @@ // Set pin as output (wrapper) - reads the pin and sets the output to that value #define SET_OUTPUT(IO) _SET_OUTPUT(IO) // Set pin as PWM -#define SET_PWM(IO) SET_OUTPUT(IO) +#define SET_PWM SET_OUTPUT // Check if pin is an input #define IS_INPUT(IO) ((digitalPinToPort(IO)->PIO_OSR & digitalPinToBitMask(IO)) == 0) diff --git a/Marlin/src/HAL/ESP32/fastio.h b/Marlin/src/HAL/ESP32/fastio.h index 9c4efaee9de3..09930194d616 100644 --- a/Marlin/src/HAL/ESP32/fastio.h +++ b/Marlin/src/HAL/ESP32/fastio.h @@ -56,7 +56,7 @@ #define SET_OUTPUT(IO) do{ _SET_OUTPUT(IO); }while(0) // Set pin as PWM -#define SET_PWM(IO) SET_OUTPUT(IO) +#define SET_PWM SET_OUTPUT // Set pin as output and init #define OUT_WRITE(IO,V) do{ _SET_OUTPUT(IO); WRITE(IO,V); }while(0) diff --git a/Marlin/src/HAL/LPC1768/fastio.h b/Marlin/src/HAL/LPC1768/fastio.h index 48de5b8fa079..8e8e66db7225 100644 --- a/Marlin/src/HAL/LPC1768/fastio.h +++ b/Marlin/src/HAL/LPC1768/fastio.h @@ -104,7 +104,7 @@ /// set pin as output wrapper - reads the pin and sets the output to that value #define SET_OUTPUT(IO) do{ _WRITE(IO, _READ(IO)); _SET_OUTPUT(IO); }while(0) // set pin as PWM -#define SET_PWM(IO) SET_OUTPUT(IO) +#define SET_PWM SET_OUTPUT /// check if pin is an input wrapper #define IS_INPUT(IO) _IS_INPUT(IO) diff --git a/Marlin/src/HAL/SAMD51/fastio.h b/Marlin/src/HAL/SAMD51/fastio.h index f6a2675de055..d3b3dc1f63c5 100644 --- a/Marlin/src/HAL/SAMD51/fastio.h +++ b/Marlin/src/HAL/SAMD51/fastio.h @@ -100,9 +100,9 @@ PORT->Group[port].DIRCLR.reg = MASK(pin); \ }while(0) // Set pin as PWM (push pull) -#define SET_PWM(IO) SET_OUTPUT(IO) +#define SET_PWM SET_OUTPUT // Set pin as PWM (open drain) -#define SET_PWM_OD(IO) SET_OUTPUT_OD(IO) +#define SET_PWM_OD SET_OUTPUT_OD // check if pin is an output #define IS_OUTPUT(IO) ((PORT->Group[(EPortType)GET_SAMD_PORT(IO)].DIR.reg & MASK(GET_SAMD_PIN(IO))) \ diff --git a/Marlin/src/HAL/TEENSY31_32/fastio.h b/Marlin/src/HAL/TEENSY31_32/fastio.h index 8547fe2b7a81..e74920d49334 100644 --- a/Marlin/src/HAL/TEENSY31_32/fastio.h +++ b/Marlin/src/HAL/TEENSY31_32/fastio.h @@ -76,8 +76,9 @@ #define SET_INPUT(IO) _SET_INPUT(IO) #define SET_INPUT_PULLUP(IO) _SET_INPUT_PULLUP(IO) +#define SET_INPUT_PULLDOWN SET_INPUT #define SET_OUTPUT(IO) _SET_OUTPUT(IO) -#define SET_PWM(IO) SET_OUTPUT(IO) +#define SET_PWM SET_OUTPUT #define IS_INPUT(IO) _IS_INPUT(IO) #define IS_OUTPUT(IO) _IS_OUTPUT(IO) diff --git a/Marlin/src/HAL/TEENSY35_36/fastio.h b/Marlin/src/HAL/TEENSY35_36/fastio.h index 8547fe2b7a81..e74920d49334 100644 --- a/Marlin/src/HAL/TEENSY35_36/fastio.h +++ b/Marlin/src/HAL/TEENSY35_36/fastio.h @@ -76,8 +76,9 @@ #define SET_INPUT(IO) _SET_INPUT(IO) #define SET_INPUT_PULLUP(IO) _SET_INPUT_PULLUP(IO) +#define SET_INPUT_PULLDOWN SET_INPUT #define SET_OUTPUT(IO) _SET_OUTPUT(IO) -#define SET_PWM(IO) SET_OUTPUT(IO) +#define SET_PWM SET_OUTPUT #define IS_INPUT(IO) _IS_INPUT(IO) #define IS_OUTPUT(IO) _IS_OUTPUT(IO) diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h index ef2b23a3a2b0..3023a1c6bc9a 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h @@ -176,11 +176,12 @@ #undef MAKE_ARDUINO_PINS } // namespace fast_io - #define SET_INPUT(pin) fast_io::pin::set_input() - #define SET_INPUT_PULLUP(pin) fast_io::pin::set_input(); fast_io::pin::set_high() - #define SET_OUTPUT(pin) fast_io::pin::set_output() - #define READ(pin) fast_io::pin::read() - #define WRITE(pin, value) fast_io::pin::write(value) + #define SET_INPUT(pin) fast_io::pin::set_input() + #define SET_INPUT_PULLUP(pin) do{ fast_io::pin::set_input(); fast_io::pin::set_high(); }while(0) + #define SET_INPUT_PULLDOWN SET_INPUT + #define SET_OUTPUT(pin) fast_io::pin::set_output() + #define READ(pin) fast_io::pin::read() + #define WRITE(pin, value) fast_io::pin::write(value) #ifndef pgm_read_word_far #define pgm_read_word_far pgm_read_word @@ -195,11 +196,11 @@ #endif #define SERIAL_ECHO_START() - #define SERIAL_ECHOLNPGM(str) Serial.println(F(str)) - #define SERIAL_ECHOPGM(str) Serial.print(F(str)) - #define SERIAL_ECHO_MSG(str) Serial.println(str) - #define SERIAL_ECHOLNPAIR(str, val) {Serial.print(F(str)); Serial.println(val);} - #define SERIAL_ECHOPAIR(str, val) {Serial.print(F(str)); Serial.print(val);} + #define SERIAL_ECHOLNPGM(str) Serial.println(F(str)) + #define SERIAL_ECHOPGM(str) Serial.print(F(str)) + #define SERIAL_ECHO_MSG(str) Serial.println(str) + #define SERIAL_ECHOLNPAIR(str, val) do{ Serial.print(F(str)); Serial.println(val); }while(0) + #define SERIAL_ECHOPAIR(str, val) do{ Serial.print(F(str)); Serial.print(val); }while(0) #define safe_delay delay From 528907cb1604ae2f5c8807e7512e2ea1a98289bf Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 31 Mar 2020 12:50:30 -0500 Subject: [PATCH 03/37] Additional TERN macros --- Marlin/src/core/macros.h | 3 +++ 1 file changed, 3 insertions(+) diff --git a/Marlin/src/core/macros.h b/Marlin/src/core/macros.h index bcee642368dc..899baf73592e 100644 --- a/Marlin/src/core/macros.h +++ b/Marlin/src/core/macros.h @@ -194,6 +194,9 @@ #define DISABLED(V...) DO(DIS,&&,V) #define TERN(O,A,B) _TERN(_ENA_1(O),B,A) // OPTION converted to '0' or '1' +#define TERN0(O,A) _TERN(_ENA_1(O),0,A) // OPTION converted to A or '0' +#define TERN1(O,A) _TERN(_ENA_1(O),1,A) // OPTION converted to A or '1' +#define TERN_(O,A) _TERN(_ENA_1(O),,A) // OPTION converted to A or '' #define _TERN(E,V...) __TERN(_CAT(T_,E),V) // Prepend 'T_' to get 'T_0' or 'T_1' #define __TERN(T,V...) ___TERN(_CAT(_NO,T),V) // Prepend '_NO' to get '_NOT_0' or '_NOT_1' #define ___TERN(P,V...) THIRD(P,V) // If first argument has a comma, A. Else B. From e0e87ca19a57dc42e9eb5e22d044b8f3c1116544 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 31 Mar 2020 12:49:36 -0500 Subject: [PATCH 04/37] Fix last arc segment Co-Authored-By: ellensp --- Marlin/src/gcode/motion/G2_G3.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/gcode/motion/G2_G3.cpp b/Marlin/src/gcode/motion/G2_G3.cpp index b11b1136b6e1..b0fb299ab26c 100644 --- a/Marlin/src/gcode/motion/G2_G3.cpp +++ b/Marlin/src/gcode/motion/G2_G3.cpp @@ -236,7 +236,7 @@ void plan_arc( planner.apply_leveling(raw); #endif - planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, seg_length + planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, 0 #if ENABLED(SCARA_FEEDRATE_SCALING) , inv_duration #endif From ac0a7f2281a5c0df22a3df3fe83d4f112739bbe0 Mon Sep 17 00:00:00 2001 From: Eric Ptak Date: Tue, 31 Mar 2020 20:59:08 +0200 Subject: [PATCH 05/37] Fix Fysetc stm32flash usage (#17331) --- buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py b/buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py index 1aeaa4d700d2..67a75f5b47fe 100644 --- a/buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py +++ b/buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py @@ -30,7 +30,7 @@ env.Replace( UPLOADER=UPLOAD_TOOL, - UPLOADCMD=expandvars(UPLOAD_TOOL + " -v -i rts,-dtr,dtr $UPLOAD_PORT -R -w \"" + join("$BUILD_DIR","${PROGNAME}.hex")+"\"") + UPLOADCMD=expandvars(UPLOAD_TOOL + " -v -i rts,-dtr,dtr -R -b 115200 -g 0x8000000 -w \"" + join("$BUILD_DIR","${PROGNAME}.hex")+"\"" + " $UPLOAD_PORT") ) # Python callback From c759729478b7b41a4f6d276380249dd482e24bb8 Mon Sep 17 00:00:00 2001 From: Tanguy Pruvot Date: Tue, 31 Mar 2020 21:13:20 +0200 Subject: [PATCH 06/37] STM32F1: Restore M43 build support (#17336) --- Marlin/src/gcode/config/M43.cpp | 12 ++++++++++-- 1 file changed, 10 insertions(+), 2 deletions(-) diff --git a/Marlin/src/gcode/config/M43.cpp b/Marlin/src/gcode/config/M43.cpp index 2c28da62fb21..baf5efb137f6 100644 --- a/Marlin/src/gcode/config/M43.cpp +++ b/Marlin/src/gcode/config/M43.cpp @@ -67,7 +67,11 @@ inline void toggle_pins() { else { watchdog_refresh(); report_pin_state_extended(pin, ignore_protection, true, PSTR("Pulsing ")); - const bool prior_mode = GET_PINMODE(pin); + #ifdef __STM32F1__ + const auto prior_mode = _GET_MODE(i); + #else + const bool prior_mode = GET_PINMODE(pin); + #endif #if AVR_AT90USB1286_FAMILY // Teensy IDEs don't know about these pins so must use FASTIO if (pin == TEENSY_E2) { SET_OUTPUT(TEENSY_E2); @@ -96,7 +100,11 @@ inline void toggle_pins() { watchdog_refresh(); } } - pinMode(pin, prior_mode); + #ifdef __STM32F1__ + _SET_MODE(i, prior_mode); + #else + pinMode(pin, prior_mode); + #endif } SERIAL_EOL(); } From d83ad6f321af6511d35e0396776f557195fcba9f Mon Sep 17 00:00:00 2001 From: Marcio T Date: Tue, 31 Mar 2020 13:22:04 -0600 Subject: [PATCH 07/37] Improve / fix FTDI EVE Touch UI (#17338) - Fix timeout and debugging string - Fix check for whether `LCD_TIMEOUT_TO_STATUS` is valid - Fix incorrect debugging message - Make capitalization of callbacks consistent. - Allow Touch UI to use hardware SPI on Einsy boards - Move print stats to About Printer page. - More generic about screen with GPL license. - Add missing handler for power loss event - Less code duplication on status screen and main/advanced menu; more legible - Reorganize advanced and main menu to add more features - Hide home Z button when using Z_SAFE_HOMING - Fix compilation errors when certain features enabled - Fix missing labels in UI - Improve color scheme - Add new preheat menus - Fix incorrect rendering of Marlin logo on boot - Add Level X Axis and Auto calibrate buttons --- Marlin/src/gcode/feature/powerloss/M1000.cpp | 2 +- Marlin/src/gcode/temp/M303.cpp | 2 +- .../ftdi_eve_lib/basic/spi.cpp | 11 + .../ftdi_eve_lib/extended/event_loop.cpp | 2 +- .../ftdi_eve_touch_ui/language/language_en.h | 14 +- .../lib/ftdi_eve_touch_ui/marlin_events.cpp | 8 +- .../lib/ftdi_eve_touch_ui/pin_mappings.h | 15 +- .../screens/about_screen.cpp | 78 +++--- .../screens/advanced_settings_menu.cpp | 154 ++++++------ .../base_numeric_adjustment_screen.cpp | 12 +- .../ftdi_eve_touch_ui/screens/base_screen.cpp | 8 +- .../screens/bio_advanced_settings.cpp | 2 +- .../screens/bio_confirm_home_e.cpp | 12 +- .../screens/bio_confirm_home_xyz.cpp | 10 +- .../screens/bio_main_menu.cpp | 4 +- .../ftdi_eve_touch_ui/screens/boot_screen.cpp | 14 +- .../screens/change_filament_screen.cpp | 3 +- .../screens/interface_settings_screen.cpp | 10 +- .../screens/interface_sounds_screen.cpp | 2 +- .../ftdi_eve_touch_ui/screens/main_menu.cpp | 165 +++++++------ .../screens/preheat_menu.cpp | 83 +++++++ .../screens/preheat_timer_screen.cpp | 3 - .../lib/ftdi_eve_touch_ui/screens/screens.cpp | 1 + .../lib/ftdi_eve_touch_ui/screens/screens.h | 9 +- .../screens/status_screen.cpp | 226 ++++++++--------- .../lib/ftdi_eve_touch_ui/theme/colors.h | 228 ++++++++++-------- .../theme/marlin_bootscreen_landscape.h | 4 +- .../theme/marlin_bootscreen_portrait.h | 4 +- Marlin/src/lcd/extui/ui_api.h | 4 +- Marlin/src/lcd/extui_dgus_lcd.cpp | 6 +- Marlin/src/lcd/extui_example.cpp | 4 +- Marlin/src/lcd/extui_malyan_lcd.cpp | 2 +- Marlin/src/lcd/language/language_en.h | 3 + Marlin/src/module/temperature.cpp | 10 +- 34 files changed, 641 insertions(+), 474 deletions(-) create mode 100644 Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/preheat_menu.cpp diff --git a/Marlin/src/gcode/feature/powerloss/M1000.cpp b/Marlin/src/gcode/feature/powerloss/M1000.cpp index ea2c6e3dab1b..8d8cdc755717 100644 --- a/Marlin/src/gcode/feature/powerloss/M1000.cpp +++ b/Marlin/src/gcode/feature/powerloss/M1000.cpp @@ -63,7 +63,7 @@ void GcodeSuite::M1000() { #if HAS_LCD_MENU ui.goto_screen(menu_job_recovery); #elif ENABLED(EXTENSIBLE_UI) - ExtUI::OnPowerLossResume(); + ExtUI::onPowerLossResume(); #else SERIAL_ECHO_MSG("Resume requires LCD."); #endif diff --git a/Marlin/src/gcode/temp/M303.cpp b/Marlin/src/gcode/temp/M303.cpp index 657dd867ee9f..358a1436b171 100644 --- a/Marlin/src/gcode/temp/M303.cpp +++ b/Marlin/src/gcode/temp/M303.cpp @@ -73,7 +73,7 @@ void GcodeSuite::M303() { if (!WITHIN(e, SI, EI)) { SERIAL_ECHOLNPGM(STR_PID_BAD_EXTRUDER_NUM); #if ENABLED(EXTENSIBLE_UI) - ExtUI::OnPidTuning(ExtUI::result_t::PID_BAD_EXTRUDER_NUM); + ExtUI::onPidTuning(ExtUI::result_t::PID_BAD_EXTRUDER_NUM); #endif return; } diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.cpp index 7f666be45b56..6621ea3cbf19 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.cpp @@ -38,6 +38,11 @@ namespace FTDI { SET_OUTPUT(CLCD_SPI_CS); WRITE(CLCD_SPI_CS, 1); + #ifdef CLCD_SPI_EXTRA_CS + SET_OUTPUT(CLCD_SPI_EXTRA_CS); + WRITE(CLCD_SPI_EXTRA_CS, 1); + #endif + #ifdef SPI_FLASH_SS SET_OUTPUT(SPI_FLASH_SS); WRITE(SPI_FLASH_SS, 1); @@ -111,12 +116,18 @@ namespace FTDI { ::SPI.beginTransaction(spi_settings); #endif WRITE(CLCD_SPI_CS, 0); + #ifdef CLCD_SPI_EXTRA_CS + WRITE(CLCD_SPI_EXTRA_CS, 0); + #endif delayMicroseconds(1); } // CLCD SPI - Chip Deselect void SPI::spi_ftdi_deselect() { WRITE(CLCD_SPI_CS, 1); + #ifdef CLCD_SPI_EXTRA_CS + WRITE(CLCD_SPI_EXTRA_CS, 1); + #endif #ifndef CLCD_USE_SOFT_SPI ::SPI.endTransaction(); #endif diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.cpp index f0f693bfd887..b338758ed157 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.cpp @@ -191,7 +191,7 @@ namespace FTDI { #if ENABLED(TOUCH_UI_DEBUG) SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR("Touch end: ", tag); + SERIAL_ECHOLNPAIR("Touch end: ", pressed_tag); #endif const uint8_t saved_pressed_tag = pressed_tag; 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 e59e1d9468cc..ebd60aed31d5 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 @@ -70,13 +70,15 @@ namespace Language_en { PROGMEM Language_Str MSG_PRINT_FINISHED = u8"Print finished"; PROGMEM Language_Str MSG_PRINT_ERROR = u8"Print error"; PROGMEM Language_Str MSG_ABOUT_TOUCH_PANEL_1 = u8"Color Touch Panel"; - PROGMEM Language_Str MSG_ABOUT_TOUCH_PANEL_2 = u8"Portions " COPYRIGHT_SIGN " 2019 Aleph Objects, Inc.\n" - "Portions " COPYRIGHT_SIGN " 2019 Cocoa Press"; - PROGMEM Language_Str MSG_FIRMWARE_FOR_TOOLHEAD = u8"Firmware for toolhead:\n%s\n\n"; + PROGMEM Language_Str MSG_ABOUT_TOUCH_PANEL_2 = WEBSITE_URL; + PROGMEM Language_Str MSG_LICENSE = u8"This program is free software: you can redistribute it and/or modify it under the terms of " + "the GNU General Public License as published by the Free Software Foundation, either version 3 " + "of the License, or (at your option) any later version.\n\nTo view a copy of the GNU General " + "Public License, go to the following location: http://www.gnu.org/licenses."; PROGMEM Language_Str MSG_RUNOUT_1 = u8"Runout 1"; PROGMEM Language_Str MSG_RUNOUT_2 = u8"Runout 2"; PROGMEM Language_Str MSG_DISPLAY_MENU = u8"Display"; - PROGMEM Language_Str MSG_INTERFACE_SETTINGS = u8"Interface Settings"; + PROGMEM Language_Str MSG_INTERFACE = u8"Interface"; PROGMEM Language_Str MSG_MEASURE_AUTOMATICALLY = u8"Measure automatically"; PROGMEM Language_Str MSG_H_OFFSET = u8"H Offset"; PROGMEM Language_Str MSG_V_OFFSET = u8"V Offset"; @@ -129,7 +131,7 @@ namespace Language_en { PROGMEM Language_Str MSG_SOUND_VOLUME = u8"Sound volume"; PROGMEM Language_Str MSG_SCREEN_LOCK = u8"Screen lock"; PROGMEM Language_Str MSG_BOOT_SCREEN = u8"Boot screen"; - PROGMEM Language_Str MSG_INTERFACE_SOUNDS = u8"Interface Sounds"; + PROGMEM Language_Str MSG_SOUNDS = u8"Sounds"; PROGMEM Language_Str MSG_CLICK_SOUNDS = u8"Click sounds"; PROGMEM Language_Str MSG_EEPROM_RESTORED = u8"Settings restored from backup"; PROGMEM Language_Str MSG_EEPROM_RESET = u8"Settings restored to default"; @@ -144,12 +146,12 @@ namespace Language_en { PROGMEM Language_Str MSG_TOUCH_CALIBRATION_START = u8"Release to begin screen calibration"; PROGMEM Language_Str MSG_TOUCH_CALIBRATION_PROMPT = u8"Touch the dots to calibrate"; + PROGMEM Language_Str MSG_AUTOLEVEL_X_AXIS = u8"Level X Axis"; #ifdef TOUCH_UI_LULZBOT_BIO PROGMEM Language_Str MSG_MOVE_TO_HOME = u8"Move to Home"; PROGMEM Language_Str MSG_RAISE_PLUNGER = u8"Raise Plunger"; PROGMEM Language_Str MSG_RELEASE_XY_AXIS = u8"Release X and Y Axis"; - PROGMEM Language_Str MSG_AUTOLEVEL_X_AXIS = u8"Auto-level X Axis"; PROGMEM Language_Str MSG_BED_TEMPERATURE = u8"Bed Temperature"; PROGMEM Language_Str MSG_HOME_XYZ_WARNING = u8"About to move to home position. Ensure the top and the bed of the printer are clear.\n\nContinue?"; PROGMEM Language_Str MSG_HOME_E_WARNING = u8"About to re-home plunger and auto-level. Remove syringe prior to proceeding.\n\nContinue?"; 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 96845d40658e..bed32cc6064d 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 @@ -131,8 +131,14 @@ namespace ExtUI { } #endif + #if ENABLED(POWER_LOSS_RECOVERY) + void onPowerLossResume() { + // Called on resume from power-loss + } + #endif + #if HAS_PID_HEATING - void OnPidTuning(const result_t rst) { + void onPidTuning(const result_t rst) { // Called for temperature PID tuning result SERIAL_ECHOLNPAIR("OnPidTuning:", rst); switch (rst) { diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h index 548c6c7439d4..b5b0f22e11dc 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h @@ -129,12 +129,13 @@ * 9 GND GND GND --> GND * 10 5V 5V 5V --> KILL [3] * - * [1] This configuration is not compatible with the - * EinsyRetro 1.1a because there is a level shifter - * on MISO enabled by SD/USB chip select. + * [1] This configuration allows daisy-chaining of the + * display and SD/USB on EXP2, except for [2] * - * [2] This configuration allows daisy-chaining of the - * display and SD/USB on EXP2. + * [2] The Ultimachine Einsy boards have a level shifter + * on MISO enabled by SD_CSEL chip select, hence it + * is not possible to run both the display and the + * SD/USB on EXP2. * * [3] Archim Rambo provides 5V on this pin. On any other * board, divert this wire from the ribbon cable and @@ -148,4 +149,8 @@ #define CLCD_SPI_CS BTN_EN1 #define CLCD_MOD_RESET BTN_EN2 + + #if MB(EINSY_RAMBO, EINSY_RETRO) && DISABLED(SDSUPPORT) + #define CLCD_SPI_EXTRA_CS SDSS + #endif #endif diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/about_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/about_screen.cpp index afd4402fc109..70acc09071e9 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/about_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/about_screen.cpp @@ -27,7 +27,7 @@ #include "screens.h" #define GRID_COLS 4 -#define GRID_ROWS 9 +#define GRID_ROWS 7 using namespace FTDI; using namespace Theme; @@ -45,50 +45,62 @@ void AboutScreen::onRedraw(draw_mode_t) { .cmd(COLOR_RGB(bg_text_enabled)) .tag(0); - draw_text_box(cmd, BTN_POS(1,2), BTN_SIZE(4,1), - #ifdef CUSTOM_MACHINE_NAME - F(CUSTOM_MACHINE_NAME) - #else - GET_TEXT_F(MSG_ABOUT_TOUCH_PANEL_1) - #endif - , OPT_CENTER, font_xlarge - ); + #define HEADING_POS BTN_POS(1,2), BTN_SIZE(4,1) + #define FW_VERS_POS BTN_POS(1,3), BTN_SIZE(4,1) + #define FW_INFO_POS BTN_POS(1,4), BTN_SIZE(4,1) + #define LICENSE_POS BTN_POS(1,5), BTN_SIZE(4,2) + #define STATS_POS BTN_POS(1,7), BTN_SIZE(2,1) + #define BACK_POS BTN_POS(3,7), BTN_SIZE(2,1) - #ifdef TOOLHEAD_NAME - char about_str[ - strlen_P(GET_TEXT(FIRMWARE_FOR_TOOLHEAD)) + - strlen_P(TOOLHEAD_NAME) + - strlen_P(GET_TEXT(MSG_ABOUT_TOUCH_PANEL_2)) + 1 - ]; + #define _INSET_POS(x,y,w,h) x + w/10, y, w - w/5, h + #define INSET_POS(pos) _INSET_POS(pos) - sprintf_P(about_str, GET_TEXT(MSG_FIRMWARE_FOR_TOOLHEAD), TOOLHEAD_NAME); - strcat_P (about_str, GET_TEXT(MSG_ABOUT_TOUCH_PANEL_2)); + char about_str[ + strlen_P(GET_TEXT(MSG_ABOUT_TOUCH_PANEL_2)) + + strlen_P(TOOLHEAD_NAME) + 1 + ]; + #ifdef TOOLHEAD_NAME + // If MSG_ABOUT_TOUCH_PANEL_2 has %s, substitute in the toolhead name. + // But this is optional, so squelch the compiler warning here. + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wformat-extra-args" + sprintf_P(about_str, GET_TEXT(MSG_ABOUT_TOUCH_PANEL_2), TOOLHEAD_NAME); + #pragma GCC diagnostic pop + #else + strcpy_P(about_str, GET_TEXT(MSG_ABOUT_TOUCH_PANEL_2)); #endif - cmd.tag(2); - draw_text_box(cmd, BTN_POS(1,3), BTN_SIZE(4,3), - #ifdef TOOLHEAD_NAME - about_str + draw_text_box(cmd, HEADING_POS, + #ifdef CUSTOM_MACHINE_NAME + F(CUSTOM_MACHINE_NAME) #else - GET_TEXT_F(MSG_ABOUT_TOUCH_PANEL_2) + GET_TEXT_F(MSG_ABOUT_TOUCH_PANEL_1) #endif - , OPT_CENTER, font_medium + , OPT_CENTER, font_xlarge ); - - cmd.tag(0); - draw_text_box(cmd, BTN_POS(1,6), BTN_SIZE(4,2), progmem_str(getFirmwareName_str()), OPT_CENTER, font_medium); - - cmd.font(font_medium).colors(action_btn).tag(1).button(BTN_POS(2,8), BTN_SIZE(2,1), GET_TEXT_F(MSG_BUTTON_OKAY)); + draw_text_box(cmd, FW_VERS_POS, progmem_str(getFirmwareName_str()), OPT_CENTER, font_medium); + draw_text_box(cmd, FW_INFO_POS, about_str, OPT_CENTER, font_medium); + draw_text_box(cmd, INSET_POS(LICENSE_POS), GET_TEXT_F(MSG_LICENSE), OPT_CENTER, font_tiny); + + cmd.font(font_medium) + .colors(normal_btn) + .tag(2).button(STATS_POS, GET_TEXT_F(MSG_INFO_STATS_MENU)) + .colors(action_btn) + .tag(1).button(BACK_POS, GET_TEXT_F(MSG_BACK)); } bool AboutScreen::onTouchEnd(uint8_t tag) { switch (tag) { - case 1: GOTO_PREVIOUS(); return true; -#if ENABLED(TOUCH_UI_DEVELOPER_MENU) - case 2: GOTO_SCREEN(DeveloperMenu); return true; -#endif - default: return false; + case 1: GOTO_PREVIOUS(); break; + #if ENABLED(PRINTCOUNTER) + case 2: GOTO_SCREEN(StatisticsScreen); break; + #endif + #if ENABLED(TOUCH_UI_DEVELOPER_MENU) + case 3: GOTO_SCREEN(DeveloperMenu); break; + #endif + default: return false; } + return true; } #endif // TOUCH_UI_FTDI_EVE 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 6029382838e6..57137c5d4aa5 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 @@ -37,127 +37,116 @@ void AdvancedSettingsMenu::onRedraw(draw_mode_t what) { .cmd(CLEAR(true,true,true)); } + #ifdef TOUCH_UI_PORTRAIT + #if HAS_CASE_LIGHT || ENABLED(SENSORLESS_HOMING) + #define GRID_ROWS 9 + #else + #define GRID_ROWS 8 + #endif + #define GRID_COLS 2 + #define RESTORE_DEFAULTS_POS BTN_POS(1,1), BTN_SIZE(2,1) + #define DISPLAY_POS BTN_POS(1,2), BTN_SIZE(1,1) + #define INTERFACE_POS BTN_POS(2,2), BTN_SIZE(1,1) + #define ZPROBE_ZOFFSET_POS BTN_POS(1,3), BTN_SIZE(1,1) + #define STEPS_PER_MM_POS BTN_POS(2,3), BTN_SIZE(1,1) + #define FILAMENT_POS BTN_POS(1,4), BTN_SIZE(1,1) + #define VELOCITY_POS BTN_POS(2,4), BTN_SIZE(1,1) + #define TMC_CURRENT_POS BTN_POS(1,5), BTN_SIZE(1,1) + #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 BACKLASH_POS BTN_POS(2,7), BTN_SIZE(1,1) + #define CASE_LIGHT_POS BTN_POS(1,8), BTN_SIZE(1,1) + #define TMC_HOMING_THRS_POS BTN_POS(2,8), BTN_SIZE(1,1) + #if HAS_CASE_LIGHT || ENABLED(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) + #endif + #else + #define GRID_ROWS 6 + #define GRID_COLS 3 + #define ZPROBE_ZOFFSET_POS BTN_POS(1,1), BTN_SIZE(1,1) + #define CASE_LIGHT_POS BTN_POS(1,4), BTN_SIZE(1,1) + #define STEPS_PER_MM_POS BTN_POS(2,1), BTN_SIZE(1,1) + #define TMC_CURRENT_POS BTN_POS(3,1), BTN_SIZE(1,1) + #define TMC_HOMING_THRS_POS BTN_POS(3,2), BTN_SIZE(1,1) + #define BACKLASH_POS BTN_POS(3,3), BTN_SIZE(1,1) + #define FILAMENT_POS BTN_POS(1,3), BTN_SIZE(1,1) + #define ENDSTOPS_POS BTN_POS(3,4), BTN_SIZE(1,1) + #define DISPLAY_POS BTN_POS(3,5), BTN_SIZE(1,1) + #define INTERFACE_POS BTN_POS(1,5), BTN_SIZE(2,1) + #define RESTORE_DEFAULTS_POS BTN_POS(1,6), BTN_SIZE(2,1) + #define VELOCITY_POS BTN_POS(2,2), BTN_SIZE(1,1) + #define ACCELERATION_POS BTN_POS(2,3), BTN_SIZE(1,1) + #define JERK_POS BTN_POS(2,4), BTN_SIZE(1,1) + #define OFFSETS_POS BTN_POS(1,2), BTN_SIZE(1,1) + #define BACK_POS BTN_POS(3,6), BTN_SIZE(1,1) + #endif + if (what & FOREGROUND) { CommandProcessor cmd; cmd.colors(normal_btn) .font(Theme::font_medium) - #ifdef TOUCH_UI_PORTRAIT - #define GRID_ROWS 10 - #define GRID_COLS 2 .enabled( #if HAS_BED_PROBE 1 #endif ) - .tag(2) .button( BTN_POS(1,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_ZPROBE_ZOFFSET)) + .tag(2) .button( ZPROBE_ZOFFSET_POS, GET_TEXT_F(MSG_ZPROBE_ZOFFSET)) .enabled( #if HAS_CASE_LIGHT 1 #endif ) - .tag(16).button( BTN_POS(1,6), BTN_SIZE(1,1), GET_TEXT_F(MSG_CASE_LIGHT)) - .tag(3) .button( BTN_POS(2,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_STEPS_PER_MM)) + .tag(16).button( CASE_LIGHT_POS, GET_TEXT_F(MSG_CASE_LIGHT)) + .tag(3) .button( STEPS_PER_MM_POS, GET_TEXT_F(MSG_STEPS_PER_MM)) .enabled( #if HAS_TRINAMIC_CONFIG 1 #endif ) - .tag(13).button( BTN_POS(1,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_TMC_CURRENT)) + .tag(13).button( TMC_CURRENT_POS, GET_TEXT_F(MSG_TMC_CURRENT)) .enabled( - #if HAS_TRINAMIC_CONFIG + #if ENABLED(SENSORLESS_HOMING) 1 #endif ) - .tag(14).button( BTN_POS(1,7), BTN_SIZE(2,1), GET_TEXT_F(MSG_TMC_HOMING_THRS)) + .tag(14).button( TMC_HOMING_THRS_POS, GET_TEXT_F(MSG_TMC_HOMING_THRS)) .enabled( #if HOTENDS > 1 1 #endif ) - .tag(4) .button( BTN_POS(1,2), BTN_SIZE(1,1), GET_TEXT_F(MSG_OFFSETS_MENU)) + .tag(4) .button( OFFSETS_POS, GET_TEXT_F(MSG_OFFSETS_MENU)) .enabled( #if EITHER(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR) 1 #endif ) - .tag(11).button( BTN_POS(1,3), BTN_SIZE(1,1), GET_TEXT_F(MSG_FILAMENT)) - .tag(12).button( BTN_POS(1,5), BTN_SIZE(1,1), GET_TEXT_F(MSG_LCD_ENDSTOPS)) - .tag(15).button( BTN_POS(2,6), BTN_SIZE(1,1), GET_TEXT_F(MSG_DISPLAY_MENU)) - .tag(9) .button( BTN_POS(1,8), BTN_SIZE(2,1), GET_TEXT_F(MSG_INTERFACE_SETTINGS)) - .tag(10).button( BTN_POS(1,9), BTN_SIZE(2,1), GET_TEXT_F(MSG_RESTORE_DEFAULTS)) - .tag(5) .button( BTN_POS(2,2), BTN_SIZE(1,1), GET_TEXT_F(MSG_VELOCITY)) - .tag(6) .button( BTN_POS(2,3), BTN_SIZE(1,1), GET_TEXT_F(MSG_ACCELERATION)) - #if DISABLED(CLASSIC_JERK) - .tag(7) .button( BTN_POS(2,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_JUNCTION_DEVIATION)) - #else - .tag(7) .button( BTN_POS(2,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_JERK)) - #endif - .enabled( - #if ENABLED(BACKLASH_GCODE) - 1 - #endif - ) - .tag(8).button( BTN_POS(2,5), BTN_SIZE(1,1), GET_TEXT_F(MSG_BACKLASH)) - .colors(action_btn) - .tag(1) .button( BTN_POS(1,10), BTN_SIZE(2,1), GET_TEXT_F(MSG_BACK)); - #undef GRID_COLS - #undef GRID_ROWS - #else - #define GRID_ROWS 6 - #define GRID_COLS 3 - .enabled( - #if HAS_BED_PROBE - 1 - #endif - ) - .tag(2) .button( BTN_POS(1,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_ZPROBE_ZOFFSET)) - .enabled( - #if HAS_CASE_LIGHT - 1 - #endif - ) - .tag(16).button( BTN_POS(1,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_CASE_LIGHT)) - .enabled(1) - .tag(3) .button( BTN_POS(2,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_STEPS_PER_MM)) - .enabled( - #if HAS_TRINAMIC_CONFIG - 1 - #endif - ) - .tag(13).button( BTN_POS(3,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_TMC_CURRENT)) - .enabled( - #if HAS_TRINAMIC_CONFIG - 1 + .tag(11).button( FILAMENT_POS, GET_TEXT_F(MSG_FILAMENT)) + .tag(12).button( ENDSTOPS_POS, GET_TEXT_F(MSG_LCD_ENDSTOPS)) + .tag(15).button( DISPLAY_POS, GET_TEXT_F(MSG_DISPLAY_MENU)) + .tag(9) .button( INTERFACE_POS, GET_TEXT_F(MSG_INTERFACE)) + .tag(10).button( RESTORE_DEFAULTS_POS, GET_TEXT_F(MSG_RESTORE_DEFAULTS)) + .tag(5) .button( VELOCITY_POS, GET_TEXT_F(MSG_VELOCITY)) + .tag(6) .button( ACCELERATION_POS, GET_TEXT_F(MSG_ACCELERATION)) + .tag(7) .button( JERK_POS, GET_TEXT_F( + #if DISABLED(CLASSIC_JERK) + MSG_JUNCTION_DEVIATION + #else + JERK_POS #endif - ) - .tag(14).button( BTN_POS(3,2), BTN_SIZE(1,1), GET_TEXT_F(MSG_TMC_HOMING_THRS)) + )) .enabled( #if ENABLED(BACKLASH_GCODE) 1 #endif ) - .tag(8).button( BTN_POS(3,3), BTN_SIZE(1,1), GET_TEXT_F(MSG_BACKLASH)) - .enabled( - #if HOTENDS > 1 - 1 - #endif - ) - .tag(4) .button( BTN_POS(1,2), BTN_SIZE(1,1), GET_TEXT_F(MSG_OFFSETS_MENU)) - .tag(12).button( BTN_POS(3,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_LCD_ENDSTOPS)) - .tag(5) .button( BTN_POS(2,2), BTN_SIZE(1,1), GET_TEXT_F(MSG_VELOCITY)) - .tag(6) .button( BTN_POS(2,3), BTN_SIZE(1,1), GET_TEXT_F(MSG_ACCELERATION)) - #if DISABLED(CLASSIC_JERK) - .tag(7) .button( BTN_POS(2,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_JUNCTION_DEVIATION)) - #else - .tag(7) .button( BTN_POS(2,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_JERK)) - #endif - .tag(11).button( BTN_POS(1,3), BTN_SIZE(1,1), GET_TEXT_F(MSG_FILAMENT)) - .tag(15).button( BTN_POS(3,5), BTN_SIZE(1,1), GET_TEXT_F(MSG_DISPLAY_MENU)) - .tag(9) .button( BTN_POS(1,5), BTN_SIZE(2,1), GET_TEXT_F(MSG_INTERFACE_SETTINGS)) - .tag(10).button( BTN_POS(1,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_RESTORE_DEFAULTS)) + .tag(8).button( BACKLASH_POS, GET_TEXT_F(MSG_BACKLASH)) .colors(action_btn) - .tag(1) .button( BTN_POS(3,6), BTN_SIZE(1,1), GET_TEXT_F(MSG_BACK)); - #endif + .tag(1).button( BACK_POS, GET_TEXT_F(MSG_BACK)); } } @@ -191,6 +180,8 @@ bool AdvancedSettingsMenu::onTouchEnd(uint8_t tag) { case 12: GOTO_SCREEN(EndstopStatesScreen); break; #if HAS_TRINAMIC_CONFIG case 13: GOTO_SCREEN(StepperCurrentScreen); break; + #endif + #if ENABLED(SENSORLESS_HOMING) case 14: GOTO_SCREEN(StepperBumpSensitivityScreen); break; #endif case 15: GOTO_SCREEN(DisplayTuningScreen); break; @@ -201,5 +192,4 @@ bool AdvancedSettingsMenu::onTouchEnd(uint8_t tag) { } return true; } - #endif // TOUCH_UI_FTDI_EVE diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_numeric_adjustment_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_numeric_adjustment_screen.cpp index 97e399a4030b..3e3f1d48a205 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_numeric_adjustment_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_numeric_adjustment_screen.cpp @@ -345,10 +345,14 @@ void BaseNumericAdjustmentScreen::widgets_t::home_buttons(uint8_t tag) { } cmd.font(LAYOUT_FONT); - _button(cmd, tag+0, BTN_POS(5,_line), BTN_SIZE(2,1), GET_TEXT_F(MSG_AXIS_X)); - _button(cmd, tag+1, BTN_POS(7,_line), BTN_SIZE(2,1), GET_TEXT_F(MSG_AXIS_Y)); - _button(cmd, tag+2, BTN_POS(9,_line), BTN_SIZE(2,1), GET_TEXT_F(MSG_AXIS_Z)); - _button(cmd, tag+3, BTN_POS(11,_line), BTN_SIZE(3,1), GET_TEXT_F(MSG_AXIS_ALL)); + _button(cmd, tag+0, BTN_POS(5,_line), BTN_SIZE(2,1), GET_TEXT_F(MSG_AXIS_X)); + _button(cmd, tag+1, BTN_POS(7,_line), BTN_SIZE(2,1), GET_TEXT_F(MSG_AXIS_Y)); + #if DISABLED(Z_SAFE_HOMING) + _button(cmd, tag+2, BTN_POS(9,_line), BTN_SIZE(2,1), GET_TEXT_F(MSG_AXIS_Z)); + _button(cmd, tag+3, BTN_POS(11,_line), BTN_SIZE(3,1), GET_TEXT_F(MSG_AXIS_ALL)); + #else + _button(cmd, tag+3, BTN_POS(9,_line), BTN_SIZE(3,1), GET_TEXT_F(MSG_AXIS_ALL)); + #endif _line++; } diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_screen.cpp index 77cadabcd778..7e88b7883af8 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_screen.cpp @@ -46,7 +46,7 @@ bool BaseScreen::buttonStyleCallback(CommandProcessor &cmd, uint8_t tag, uint8_t return false; } - #ifdef LCD_TIMEOUT_TO_STATUS + #if LCD_TIMEOUT_TO_STATUS if (EventLoop::get_pressed_tag() != 0) { reset_menu_timeout(); } @@ -66,7 +66,7 @@ bool BaseScreen::buttonStyleCallback(CommandProcessor &cmd, uint8_t tag, uint8_t } void BaseScreen::onIdle() { - #ifdef LCD_TIMEOUT_TO_STATUS + #if LCD_TIMEOUT_TO_STATUS if ((millis() - last_interaction) > LCD_TIMEOUT_TO_STATUS) { reset_menu_timeout(); #if ENABLED(TOUCH_UI_DEBUG) @@ -78,12 +78,12 @@ void BaseScreen::onIdle() { } void BaseScreen::reset_menu_timeout() { - #ifdef LCD_TIMEOUT_TO_STATUS + #if LCD_TIMEOUT_TO_STATUS last_interaction = millis(); #endif } -#ifdef LCD_TIMEOUT_TO_STATUS +#if LCD_TIMEOUT_TO_STATUS uint32_t BaseScreen::last_interaction; #endif diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_advanced_settings.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_advanced_settings.cpp index 6c9f74f93f09..ed8bcee55736 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_advanced_settings.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_advanced_settings.cpp @@ -85,7 +85,7 @@ void AdvancedSettingsMenu::onRedraw(draw_mode_t what) { #endif ) .tag(12) .button( BTN_POS(1,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_LINEAR_ADVANCE)) - .tag(13) .button( BTN_POS(1,7), BTN_SIZE(2,1), GET_TEXT_F(MSG_INTERFACE_SETTINGS)) + .tag(13) .button( BTN_POS(1,7), BTN_SIZE(2,1), GET_TEXT_F(MSG_INTERFACE)) .tag(14) .button( BTN_POS(1,8), BTN_SIZE(2,1), GET_TEXT_F(MSG_RESTORE_DEFAULTS)) .colors(action_btn) .tag(1). button( BTN_POS(1,9), BTN_SIZE(2,1), GET_TEXT_F(MSG_BACK)); diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_e.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_e.cpp index a3254bae9ae4..79a6112e4fc9 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_e.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_e.cpp @@ -36,11 +36,13 @@ void BioConfirmHomeE::onRedraw(draw_mode_t) { bool BioConfirmHomeE::onTouchEnd(uint8_t tag) { switch (tag) { case 1: - SpinnerDialogBox::enqueueAndWait_P(F( - "G28 E\n" - AXIS_LEVELING_COMMANDS "\n" - PARK_AND_RELEASE_COMMANDS - )); + #if defined(AXIS_LEVELING_COMMANDS) && defined(PARK_AND_RELEASE_COMMANDS) + SpinnerDialogBox::enqueueAndWait_P(F( + "G28 E\n" + AXIS_LEVELING_COMMANDS "\n" + PARK_AND_RELEASE_COMMANDS + )); + #endif current_screen.forget(); break; case 2: diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_xyz.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_xyz.cpp index 883a446b3ea9..3ae2d680ce63 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_xyz.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_xyz.cpp @@ -36,10 +36,12 @@ void BioConfirmHomeXYZ::onRedraw(draw_mode_t) { bool BioConfirmHomeXYZ::onTouchEnd(uint8_t tag) { switch (tag) { case 1: - SpinnerDialogBox::enqueueAndWait_P(F( - "G28\n" - PARK_AND_RELEASE_COMMANDS - )); + #ifdef PARK_AND_RELEASE_COMMANDS + SpinnerDialogBox::enqueueAndWait_P(F( + "G28\n" + PARK_AND_RELEASE_COMMANDS + )); + #endif current_screen.forget(); break; case 2: diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_main_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_main_menu.cpp index 40ed8479ee64..1f6aa45c1746 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_main_menu.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_main_menu.cpp @@ -51,7 +51,7 @@ void MainMenu::onRedraw(draw_mode_t what) { .tag(4).button( BTN_POS(1,4), BTN_SIZE(2,1), GET_TEXT_F(MSG_RELEASE_XY_AXIS)) .tag(5).button( BTN_POS(1,5), BTN_SIZE(2,1), GET_TEXT_F(MSG_AUTOLEVEL_X_AXIS)) .tag(6).button( BTN_POS(1,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_BED_TEMPERATURE)) - .tag(7).button( BTN_POS(1,7), BTN_SIZE(2,1), GET_TEXT_F(MSG_INTERFACE_SETTINGS)) + .tag(7).button( BTN_POS(1,7), BTN_SIZE(2,1), GET_TEXT_F(MSG_INTERFACE)) .tag(8).button( BTN_POS(1,8), BTN_SIZE(2,1), GET_TEXT_F(MSG_ADVANCED_SETTINGS)) .tag(9).button( BTN_POS(1,9), BTN_SIZE(2,1), GET_TEXT_F(MSG_INFO_MENU)) .colors(action_btn) @@ -72,7 +72,9 @@ bool MainMenu::onTouchEnd(uint8_t tag) { case 2: GOTO_SCREEN(BioConfirmHomeXYZ); break; case 3: SpinnerDialogBox::enqueueAndWait_P(e_homed ? F("G0 E0 F120") : F("G112")); break; case 4: StatusScreen::unlockMotors(); break; + #ifdef AXIS_LEVELING_COMMANDS case 5: SpinnerDialogBox::enqueueAndWait_P(F(AXIS_LEVELING_COMMANDS)); break; + #endif case 6: GOTO_SCREEN(TemperatureScreen); break; case 7: GOTO_SCREEN(InterfaceSettingsScreen); break; case 8: GOTO_SCREEN(AdvancedSettingsMenu); break; 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 996c12cf23fd..5e022b58e73d 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 @@ -80,12 +80,14 @@ void BootScreen::onIdle() { SpinnerDialogBox::hide(); } - if (UIData::animations_enabled()) { - // If there is a startup video in the flash SPI, play - // that, otherwise show a static splash screen. - if (!MediaPlayerScreen::playBootMedia()) - showSplashScreen(); - } + #if DISABLED(TOUCH_UI_NO_BOOTSCREEN) + if (UIData::animations_enabled()) { + // If there is a startup video in the flash SPI, play + // that, otherwise show a static splash screen. + if (!MediaPlayerScreen::playBootMedia()) + showSplashScreen(); + } + #endif StatusScreen::loadBitmaps(); diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/change_filament_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/change_filament_screen.cpp index 2d1e0d66272f..2b5963fdf6f1 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/change_filament_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/change_filament_screen.cpp @@ -111,6 +111,7 @@ void ChangeFilamentScreen::onRedraw(draw_mode_t what) { if (what & BACKGROUND) { cmd.cmd(CLEAR_COLOR_RGB(bg_color)) .cmd(CLEAR(true,true,true)) + .cmd(COLOR_RGB(bg_text_enabled)) .tag(0) #ifdef TOUCH_UI_PORTRAIT .font(font_large) @@ -119,7 +120,7 @@ void ChangeFilamentScreen::onRedraw(draw_mode_t what) { #endif .text(BTN_POS(1,1), BTN_SIZE(2,1), GET_TEXT_F(MSG_EXTRUDER_SELECTION)) #ifdef TOUCH_UI_PORTRAIT - .text(BTN_POS(1,7), BTN_SIZE(1,1), F("")) + .text(BTN_POS(1,7), BTN_SIZE(1,1), GET_TEXT_F(MSG_CURRENT_TEMPERATURE)) #else .text(BTN_POS(3,1), BTN_SIZE(2,1), GET_TEXT_F(MSG_CURRENT_TEMPERATURE)) .font(font_small) diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp index 3de03579e4b0..4e165aa4484a 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp @@ -69,7 +69,7 @@ void InterfaceSettingsScreen::onRedraw(draw_mode_t what) { .cmd(COLOR_RGB(bg_text_enabled)) .tag(0) .font(font_medium) - .text(BTN_POS(1,1), BTN_SIZE(4,1), GET_TEXT_F(MSG_INTERFACE_SETTINGS)) + .text(BTN_POS(1,1), BTN_SIZE(4,1), GET_TEXT_F(MSG_INTERFACE)) #undef EDGE_R #define EDGE_R 30 .font(font_small) @@ -77,7 +77,9 @@ void InterfaceSettingsScreen::onRedraw(draw_mode_t what) { .text(BTN_POS(1,2), BTN_SIZE(2,1), GET_TEXT_F(MSG_LCD_BRIGHTNESS), OPT_RIGHTX | OPT_CENTERY) .text(BTN_POS(1,3), BTN_SIZE(2,1), GET_TEXT_F(MSG_SOUND_VOLUME), OPT_RIGHTX | OPT_CENTERY) .text(BTN_POS(1,4), BTN_SIZE(2,1), GET_TEXT_F(MSG_SCREEN_LOCK), OPT_RIGHTX | OPT_CENTERY); + #if DISABLED(TOUCH_UI_NO_BOOTSCREEN) cmd.text(BTN_POS(1,5), BTN_SIZE(2,1), GET_TEXT_F(MSG_BOOT_SCREEN), OPT_RIGHTX | OPT_CENTERY); + #endif #undef EDGE_R } @@ -95,16 +97,18 @@ void InterfaceSettingsScreen::onRedraw(draw_mode_t what) { .tag(3).slider(BTN_POS(3,3), BTN_SIZE(2,1), screen_data.InterfaceSettingsScreen.volume, 0xFF) .colors(ui_toggle) .tag(4).toggle2(BTN_POS(3,4), BTN_SIZE(w,1), GET_TEXT_F(MSG_NO), GET_TEXT_F(MSG_YES), LockScreen::is_enabled()) + #if DISABLED(TOUCH_UI_NO_BOOTSCREEN) .tag(5).toggle2(BTN_POS(3,5), BTN_SIZE(w,1), GET_TEXT_F(MSG_NO), GET_TEXT_F(MSG_YES), UIData::animations_enabled()) + #endif #undef EDGE_R #define EDGE_R 0 #ifdef TOUCH_UI_PORTRAIT .colors(normal_btn) - .tag(6).button (BTN_POS(1,6), BTN_SIZE(4,1), GET_TEXT_F(MSG_INTERFACE_SOUNDS)) + .tag(6).button (BTN_POS(1,6), BTN_SIZE(4,1), GET_TEXT_F(MSG_SOUNDS)) .colors(action_btn) .tag(1).button (BTN_POS(1,7), BTN_SIZE(4,1), GET_TEXT_F(MSG_BACK)); #else - .tag(6).button (BTN_POS(1,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_INTERFACE_SOUNDS)) + .tag(6).button (BTN_POS(1,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_SOUNDS)) .colors(action_btn) .tag(1).button (BTN_POS(3,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_BACK)); #endif diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_sounds_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_sounds_screen.cpp index 57f520e8abd1..48fae863a706 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_sounds_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_sounds_screen.cpp @@ -71,7 +71,7 @@ void InterfaceSoundsScreen::onRedraw(draw_mode_t what) { #define GRID_ROWS 9 .font(font_medium) - .text(BTN_POS(1,1), BTN_SIZE(4,1), GET_TEXT_F(MSG_INTERFACE_SOUNDS)) + .text(BTN_POS(1,1), BTN_SIZE(4,1), GET_TEXT_F(MSG_SOUNDS)) #undef EDGE_R #define EDGE_R 30 .font(font_small) 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 016996e26579..5d165edef0fa 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 @@ -37,81 +37,89 @@ void MainMenu::onRedraw(draw_mode_t what) { .cmd(CLEAR(true,true,true)); } + #ifdef TOUCH_UI_PORTRAIT + #define GRID_ROWS 8 + #define GRID_COLS 2 + #define ABOUT_PRINTER_POS BTN_POS(1,1), BTN_SIZE(2,1) + #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 BACK_POS BTN_POS(1,8), BTN_SIZE(2,1) + #else + #define GRID_ROWS 6 + #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) + #define AUTO_HOME_POS BTN_POS(1,2), BTN_SIZE(1,1) + #define CLEAN_NOZZLE_POS BTN_POS(2,2), BTN_SIZE(1,1) + #define MOVE_AXIS_POS BTN_POS(1,3), BTN_SIZE(1,1) + #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) + #endif + if (what & FOREGROUND) { CommandProcessor cmd; cmd.colors(normal_btn) .font(Theme::font_medium) - #ifdef TOUCH_UI_PORTRAIT - #define GRID_ROWS 8 - #define GRID_COLS 2 - .tag(2).button( BTN_POS(1,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_AUTO_HOME)) - .enabled( - #if ENABLED(NOZZLE_CLEAN_FEATURE) - 1 - #endif - ) - .tag(3).button( BTN_POS(2,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_CLEAN_NOZZLE)) - .tag(4).button( BTN_POS(1,2), BTN_SIZE(1,1), GET_TEXT_F(MSG_MOVE_AXIS)) - .tag(5).button( BTN_POS(2,2), BTN_SIZE(1,1), GET_TEXT_F(MSG_DISABLE_STEPPERS)) - .tag(6).button( BTN_POS(1,3), BTN_SIZE(2,1), GET_TEXT_F(MSG_TEMPERATURE)) - .enabled( - #if NONE(TOUCH_UI_LULZBOT_BIO, TOUCH_UI_COCOA_PRESS) - 1 - #endif + .tag(2).button( AUTO_HOME_POS, GET_TEXT_F(MSG_AUTO_HOME)) + .enabled( + #if ANY(NOZZLE_CLEAN_FEATURE, TOUCH_UI_COCOA_PRESS) + 1 + #endif + ) + .tag(3).button( CLEAN_NOZZLE_POS, GET_TEXT_F( + #if ENABLED(TOUCH_UI_COCOA_PRESS) + MSG_PREHEAT_1 + #else + MSG_CLEAN_NOZZLE + #endif + )) + .tag(4).button( MOVE_AXIS_POS, GET_TEXT_F(MSG_MOVE_AXIS)) + .tag(5).button( DISABLE_STEPPERS_POS, GET_TEXT_F(MSG_DISABLE_STEPPERS)) + .tag(6).button( TEMPERATURE_POS, GET_TEXT_F(MSG_TEMPERATURE)) + .enabled( + #if DISABLED(TOUCH_UI_LULZBOT_BIO) + 1 + #endif + ) + .tag(7).button( FILAMENTCHANGE_POS, GET_TEXT_F( + #if ENABLED(TOUCH_UI_COCOA_PRESS) + MSG_CASE_LIGHT + #else + MSG_FILAMENTCHANGE + #endif + )) + .tag(8).button( ADVANCED_SETTINGS_POS, GET_TEXT_F(MSG_ADVANCED_SETTINGS)) + .enabled( + #ifdef PRINTCOUNTER + 1 + #endif ) - .tag(7).button( BTN_POS(1,4), BTN_SIZE(2,1), GET_TEXT_F(MSG_FILAMENTCHANGE)) - .tag(8).button( BTN_POS(1,5), BTN_SIZE(2,1), GET_TEXT_F(MSG_ADVANCED_SETTINGS)) - .enabled( - #ifdef PRINTCOUNTER - 1 - #endif + .enabled( + #ifdef AXIS_LEVELING_COMMANDS + 1 + #endif ) - .tag(9).button( BTN_POS(1,7), BTN_SIZE(2,1), GET_TEXT_F(MSG_INFO_STATS_MENU)) - .tag(10).button( BTN_POS(1,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_INFO_MENU)) - .colors(action_btn) - .tag(1).button( BTN_POS(1,8), BTN_SIZE(2,1), GET_TEXT_F(MSG_BACK)); - #undef GRID_COLS - #undef GRID_ROWS - #else - #define GRID_ROWS 5 - #define GRID_COLS 2 - .tag(2).button( BTN_POS(1,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_AUTO_HOME)) - #if ENABLED(TOUCH_UI_COCOA_PRESS) - .tag(3).button( BTN_POS(2,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_PREHEAT_1)) - #else - .enabled( - #if ENABLED(NOZZLE_CLEAN_FEATURE) - 1 - #endif - ) - .tag(3).button( BTN_POS(2,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_CLEAN_NOZZLE)) - #endif - .tag(4).button( BTN_POS(1,2), BTN_SIZE(1,1), GET_TEXT_F(MSG_MOVE_AXIS)) - .tag(5).button( BTN_POS(2,2), BTN_SIZE(1,1), GET_TEXT_F(MSG_DISABLE_STEPPERS)) - .tag(6).button( BTN_POS(1,3), BTN_SIZE(1,1), GET_TEXT_F(MSG_TEMPERATURE)) - #if ENABLED(TOUCH_UI_COCOA_PRESS) - .tag(7).button( BTN_POS(2,3), BTN_SIZE(1,1), GET_TEXT_F(MSG_CASE_LIGHT)) - #else - .enabled( - #if DISABLED(TOUCH_UI_LULZBOT_BIO) - 1 - #endif - ) - .tag(7).button( BTN_POS(2,3), BTN_SIZE(1,1), GET_TEXT_F(MSG_FILAMENTCHANGE)) - #endif - .tag(8).button( BTN_POS(1,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_ADVANCED_SETTINGS)) - .enabled( - #ifdef PRINTCOUNTER - 1 - #endif + .tag(9).button( LEVEL_AXIS_POS, GET_TEXT_F(MSG_AUTOLEVEL_X_AXIS)) + .enabled( + #ifdef HAS_LEVELING + 1 + #endif ) - .tag(9).button( BTN_POS(2,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_INFO_STATS_MENU)) - .tag(10).button( BTN_POS(1,5), BTN_SIZE(1,1), GET_TEXT_F(MSG_INFO_MENU)) - .colors(action_btn) - .tag(1).button( BTN_POS(2,5), BTN_SIZE(1,1), GET_TEXT_F(MSG_BACK)); - #undef GRID_COLS - #undef GRID_ROWS - #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)) + .colors(action_btn) + .tag(1).button( BACK_POS, GET_TEXT_F(MSG_BACK)); } } @@ -122,23 +130,32 @@ bool MainMenu::onTouchEnd(uint8_t tag) { case 1: SaveSettingsDialogBox::promptToSaveSettings(); break; case 2: SpinnerDialogBox::enqueueAndWait_P(F("G28")); break; #if ENABLED(TOUCH_UI_COCOA_PRESS) - case 3: GOTO_SCREEN(PreheatTimerScreen); break; + case 3: GOTO_SCREEN(PreheatMenu); break; #elif ENABLED(NOZZLE_CLEAN_FEATURE) case 3: injectCommands_P(PSTR("G12")); GOTO_SCREEN(StatusScreen); break; #endif case 4: GOTO_SCREEN(MoveAxisScreen); break; case 5: injectCommands_P(PSTR("M84")); break; case 6: GOTO_SCREEN(TemperatureScreen); break; - #if ENABLED(TOUCH_UI_COCOA_PRESS) + #if ENABLED(TOUCH_UI_COCOA_PRESS) && HAS_CASE_LIGHT case 7: GOTO_SCREEN(CaseLightScreen); break; #else case 7: GOTO_SCREEN(ChangeFilamentScreen); break; #endif case 8: GOTO_SCREEN(AdvancedSettingsMenu); break; -#if ENABLED(PRINTCOUNTER) - case 9: GOTO_SCREEN(StatisticsScreen); break; -#endif - case 10: GOTO_SCREEN(AboutScreen); break; + #ifdef AXIS_LEVELING_COMMANDS + case 9: SpinnerDialogBox::enqueueAndWait_P(F(AXIS_LEVELING_COMMANDS)); break; + #endif + #ifdef HAS_LEVELING + case 10: SpinnerDialogBox::enqueueAndWait_P(F( + #ifdef BED_LEVELING_COMMANDS + BED_LEVELING_COMMANDS + #else + "G29" + #endif + )); break; + #endif + case 11: GOTO_SCREEN(AboutScreen); break; default: return false; } diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/preheat_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/preheat_menu.cpp new file mode 100644 index 000000000000..f0b5dd887b8f --- /dev/null +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/preheat_menu.cpp @@ -0,0 +1,83 @@ +/******************** + * preheat_menu.cpp * + ********************/ + +/**************************************************************************** + * Written By Marcio Teixeira 2020 - Cocoa Press * + * * + * This program is free software: you can redistribute it and/or modify * + * it under the terms of the GNU General Public License as published by * + * the Free Software Foundation, either version 3 of the License, or * + * (at your option) any later version. * + * * + * This program is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * + * GNU General Public License for more details. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +#include "../config.h" + +#if ENABLED(TOUCH_UI_FTDI_EVE) && defined(TOUCH_UI_COCOA_PRESS) + +#include "screens.h" + +using namespace FTDI; +using namespace ExtUI; +using namespace Theme; + +void PreheatMenu::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); + } + + #define GRID_ROWS 3 + #define GRID_COLS 2 + + if (what & FOREGROUND) { + CommandProcessor cmd; + cmd.cmd(COLOR_RGB(bg_text_enabled)) + .font(Theme::font_medium) + .text ( BTN_POS(1,1), BTN_SIZE(2,1), GET_TEXT_F(MSG_PREHEAT_1)) + .colors(normal_btn) + .tag(2).button( BTN_POS(1,2), BTN_SIZE(1,1), F("Dark Chocolate")) + .tag(3).button( BTN_POS(2,2), BTN_SIZE(1,1), F("Milk Chocolate")) + .tag(4).button( BTN_POS(1,3), BTN_SIZE(1,1), F("White Chocolate")) + .colors(action_btn) + .tag(1) .button( BTN_POS(2,3), BTN_SIZE(1,1), GET_TEXT_F(MSG_BACK)); + } +} + +bool PreheatMenu::onTouchEnd(uint8_t tag) { + switch (tag) { + case 1: GOTO_PREVIOUS(); break; + case 2: + #ifdef COCOA_PRESS_PREHEAT_DARK_CHOCOLATE_SCRIPT + injectCommands_P(PSTR(COCOA_PRESS_PREHEAT_DARK_CHOCOLATE_SCRIPT)); + #endif + GOTO_SCREEN(PreheatTimerScreen); + break; + case 3: + #ifdef COCOA_PRESS_PREHEAT_MILK_CHOCOLATE_SCRIPT + injectCommands_P(PSTR(COCOA_PRESS_PREHEAT_MILK_CHOCOLATE_SCRIPT)); + #endif + GOTO_SCREEN(PreheatTimerScreen); + break; + case 4: + #ifdef COCOA_PRESS_PREHEAT_WHITE_CHOCOLATE_SCRIPT + injectCommands_P(PSTR(COCOA_PRESS_PREHEAT_WHITE_CHOCOLATE_SCRIPT)); + #endif + GOTO_SCREEN(PreheatTimerScreen); + break; + default: return false; + } + return true; +} + +#endif // TOUCH_UI_FTDI_EVE diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/preheat_timer_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/preheat_timer_screen.cpp index 0a24c3008204..7d68ae2d671a 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/preheat_timer_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/preheat_timer_screen.cpp @@ -77,9 +77,6 @@ void PreheatTimerScreen::draw_interaction_buttons(draw_mode_t what) { void PreheatTimerScreen::onEntry() { screen_data.PreheatTimerScreen.start_ms = millis(); - #ifdef COCOA_PRESS_PREHEAT_SCRIPT - injectCommands_P(PSTR(COCOA_PRESS_PREHEAT_SCRIPT)); - #endif } void PreheatTimerScreen::onRedraw(draw_mode_t what) { 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 69c1cf1420b7..ce7546204021 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 @@ -105,6 +105,7 @@ SCREEN_TABLE { DECL_SCREEN(BioConfirmHomeE), #endif #if ENABLED(TOUCH_UI_COCOA_PRESS) + DECL_SCREEN(PreheatMenu), DECL_SCREEN(PreheatTimerScreen), #endif #if ENABLED(TOUCH_UI_DEVELOPER_MENU) 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 02c5b148310d..346d122a0f25 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 @@ -76,6 +76,7 @@ enum { PRINTING_SCREEN_CACHE, #endif #if ENABLED(TOUCH_UI_COCOA_PRESS) + PREHEAT_MENU_CACHE, PREHEAT_TIMER_SCREEN_CACHE, #endif CHANGE_FILAMENT_SCREEN_CACHE, @@ -99,7 +100,7 @@ enum { class BaseScreen : public UIScreen { protected: - #ifdef LCD_TIMEOUT_TO_STATUS + #if LCD_TIMEOUT_TO_STATUS static uint32_t last_interaction; #endif @@ -314,6 +315,12 @@ class StatusScreen : public BaseScreen, public CachedScreen { + public: + static void onRedraw(draw_mode_t); + static bool onTouchEnd(uint8_t tag); + }; + class PreheatTimerScreen : public BaseScreen, public CachedScreen { private: static uint16_t secondsRemaining(); 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 e71f200a359c..98d0bba75941 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 @@ -33,9 +33,9 @@ using namespace FTDI; using namespace Theme; #ifdef TOUCH_UI_PORTRAIT - #define GRID_ROWS 8 + #define GRID_ROWS 8 #else - #define GRID_ROWS 8 + #define GRID_ROWS 8 #endif void StatusScreen::draw_axis_position(draw_mode_t what) { @@ -43,41 +43,41 @@ void StatusScreen::draw_axis_position(draw_mode_t what) { #define GRID_COLS 3 + #ifdef TOUCH_UI_PORTRAIT + #define X_LBL_POS BTN_POS(1,5), BTN_SIZE(1,1) + #define Y_LBL_POS BTN_POS(1,6), BTN_SIZE(1,1) + #define Z_LBL_POS BTN_POS(1,7), BTN_SIZE(1,1) + #define X_VAL_POS BTN_POS(2,5), BTN_SIZE(2,1) + #define Y_VAL_POS BTN_POS(2,6), BTN_SIZE(2,1) + #define Z_VAL_POS BTN_POS(2,7), BTN_SIZE(2,1) + #else + #define X_LBL_POS BTN_POS(1,5), BTN_SIZE(1,1) + #define Y_LBL_POS BTN_POS(2,5), BTN_SIZE(1,1) + #define Z_LBL_POS BTN_POS(3,5), BTN_SIZE(1,1) + #define X_VAL_POS BTN_POS(1,6), BTN_SIZE(1,1) + #define Y_VAL_POS BTN_POS(2,6), BTN_SIZE(1,1) + #define Z_VAL_POS BTN_POS(3,6), BTN_SIZE(1,1) + #endif + + #define _UNION_POS(x1,y1,w1,h1,x2,y2,w2,h2) x1,y1,max(x1+w1,x2+w2)-x1,max(y1+h1,y2+h2)-y1 + #define UNION_POS(p1, p2) _UNION_POS(p1, p2) + if (what & BACKGROUND) { cmd.tag(6) - #ifdef TOUCH_UI_PORTRAIT - .fgcolor(Theme::axis_label) - .font(Theme::font_large) - .button( BTN_POS(1,5), BTN_SIZE(2,1), F(""), OPT_FLAT) - .button( BTN_POS(1,6), BTN_SIZE(2,1), F(""), OPT_FLAT) - .button( BTN_POS(1,7), BTN_SIZE(2,1), F(""), OPT_FLAT) - - .font(Theme::font_small) - .text ( BTN_POS(1,5), BTN_SIZE(1,1), GET_TEXT_F(MSG_AXIS_X)) - .text ( BTN_POS(1,6), BTN_SIZE(1,1), GET_TEXT_F(MSG_AXIS_Y)) - .text ( BTN_POS(1,7), BTN_SIZE(1,1), GET_TEXT_F(MSG_AXIS_Z)) - - .font(Theme::font_medium) - .fgcolor(Theme::x_axis) .button( BTN_POS(2,5), BTN_SIZE(2,1), F(""), OPT_FLAT) - .fgcolor(Theme::y_axis) .button( BTN_POS(2,6), BTN_SIZE(2,1), F(""), OPT_FLAT) - .fgcolor(Theme::z_axis) .button( BTN_POS(2,7), BTN_SIZE(2,1), F(""), OPT_FLAT); - #else - .fgcolor(Theme::axis_label) - .font(Theme::font_large) - .button( BTN_POS(1,5), BTN_SIZE(1,2), F(""), OPT_FLAT) - .button( BTN_POS(2,5), BTN_SIZE(1,2), F(""), OPT_FLAT) - .button( BTN_POS(3,5), BTN_SIZE(1,2), F(""), OPT_FLAT) - - .font(Theme::font_small) - .text ( BTN_POS(1,5), BTN_SIZE(1,1), GET_TEXT_F(MSG_AXIS_X)) - .text ( BTN_POS(2,5), BTN_SIZE(1,1), GET_TEXT_F(MSG_AXIS_Y)) - .text ( BTN_POS(3,5), BTN_SIZE(1,1), GET_TEXT_F(MSG_AXIS_Z)) - .font(Theme::font_medium) - - .fgcolor(Theme::x_axis) .button( BTN_POS(1,6), BTN_SIZE(1,1), F(""), OPT_FLAT) - .fgcolor(Theme::y_axis) .button( BTN_POS(2,6), BTN_SIZE(1,1), F(""), OPT_FLAT) - .fgcolor(Theme::z_axis) .button( BTN_POS(3,6), BTN_SIZE(1,1), F(""), OPT_FLAT); - #endif + .fgcolor(Theme::axis_label) + .font(Theme::font_large) + .button( UNION_POS(X_LBL_POS, X_VAL_POS), F(""), OPT_FLAT) + .button( UNION_POS(Y_LBL_POS, Y_VAL_POS), F(""), OPT_FLAT) + .button( UNION_POS(Z_LBL_POS, Z_VAL_POS), F(""), OPT_FLAT) + .font(Theme::font_medium) + .fgcolor(Theme::x_axis) .button( X_VAL_POS, F(""), OPT_FLAT) + .fgcolor(Theme::y_axis) .button( Y_VAL_POS, F(""), OPT_FLAT) + .fgcolor(Theme::z_axis) .button( Z_VAL_POS, F(""), OPT_FLAT) + .font(Theme::font_small) + .text ( X_LBL_POS, GET_TEXT_F(MSG_AXIS_X)) + .text ( Y_LBL_POS, GET_TEXT_F(MSG_AXIS_Y)) + .text ( Z_LBL_POS, GET_TEXT_F(MSG_AXIS_Z)) + .colors(normal_btn); } if (what & FOREGROUND) { @@ -101,16 +101,11 @@ void StatusScreen::draw_axis_position(draw_mode_t what) { else strcpy_P(z_str, PSTR("?")); - cmd.tag(6).font(Theme::font_medium) - #ifdef TOUCH_UI_PORTRAIT - .text ( BTN_POS(2,5), BTN_SIZE(2,1), x_str) - .text ( BTN_POS(2,6), BTN_SIZE(2,1), y_str) - .text ( BTN_POS(2,7), BTN_SIZE(2,1), z_str); - #else - .text ( BTN_POS(1,6), BTN_SIZE(1,1), x_str) - .text ( BTN_POS(2,6), BTN_SIZE(1,1), y_str) - .text ( BTN_POS(3,6), BTN_SIZE(1,1), z_str); - #endif + cmd.tag(6) + .font(Theme::font_medium) + .text ( X_VAL_POS, x_str) + .text ( Y_VAL_POS, y_str) + .text ( Z_VAL_POS, z_str); } #undef GRID_COLS @@ -125,49 +120,49 @@ void StatusScreen::draw_axis_position(draw_mode_t what) { void StatusScreen::draw_temperature(draw_mode_t what) { using namespace Theme; + #define TEMP_RECT_1 BTN_POS(1,1), BTN_SIZE(4,2) + #define TEMP_RECT_2 BTN_POS(1,1), BTN_SIZE(8,1) + #define NOZ_1_POS BTN_POS(1,1), BTN_SIZE(4,1) + #define NOZ_2_POS BTN_POS(5,1), BTN_SIZE(4,1) + #define BED_POS BTN_POS(1,2), BTN_SIZE(4,1) + #define FAN_POS BTN_POS(5,2), BTN_SIZE(4,1) + + #define _ICON_POS(x,y,w,h) x, y, w/4, h + #define _TEXT_POS(x,y,w,h) x + w/4, y, w - w/4, h + #define ICON_POS(pos) _ICON_POS(pos) + #define TEXT_POS(pos) _TEXT_POS(pos) + CommandProcessor cmd; if (what & BACKGROUND) { cmd.font(Theme::font_small) - #ifdef TOUCH_UI_PORTRAIT - .tag(5) - .fgcolor(temp) .button( BTN_POS(1,1), BTN_SIZE(4,2), F(""), OPT_FLAT) - .button( BTN_POS(1,1), BTN_SIZE(8,1), F(""), OPT_FLAT) - .fgcolor(fan_speed) .button( BTN_POS(5,2), BTN_SIZE(4,1), F(""), OPT_FLAT) - .tag(0) - .fgcolor(progress) .button( BTN_POS(1,3), BTN_SIZE(4,1), F(""), OPT_FLAT) - .button( BTN_POS(5,3), BTN_SIZE(4,1), F(""), OPT_FLAT); - #else .tag(5) - .fgcolor(temp) .button( BTN_POS(1,1), BTN_SIZE(4,2), F(""), OPT_FLAT) - .button( BTN_POS(1,1), BTN_SIZE(8,1), F(""), OPT_FLAT) - .fgcolor(fan_speed) .button( BTN_POS(5,2), BTN_SIZE(4,1), F(""), OPT_FLAT) - .tag(0) - .fgcolor(progress) .button( BTN_POS(9,1), BTN_SIZE(4,1), F(""), OPT_FLAT) - .button( BTN_POS(9,2), BTN_SIZE(4,1), F(""), OPT_FLAT); - #endif + .fgcolor(temp) .button( TEMP_RECT_1, F(""), OPT_FLAT) + .button( TEMP_RECT_2, F(""), OPT_FLAT) + .fgcolor(fan_speed).button( FAN_POS, F(""), OPT_FLAT) + .tag(0); // Draw Extruder Bitmap on Extruder Temperature Button cmd.tag(5) - .cmd(BITMAP_SOURCE(Extruder_Icon_Info)) - .cmd(BITMAP_LAYOUT(Extruder_Icon_Info)) - .cmd(BITMAP_SIZE (Extruder_Icon_Info)) - .icon (BTN_POS(1,1), BTN_SIZE(1,1), Extruder_Icon_Info, icon_scale) - .icon (BTN_POS(5,1), BTN_SIZE(1,1), Extruder_Icon_Info, icon_scale); + .cmd (BITMAP_SOURCE(Extruder_Icon_Info)) + .cmd (BITMAP_LAYOUT(Extruder_Icon_Info)) + .cmd (BITMAP_SIZE (Extruder_Icon_Info)) + .icon(ICON_POS(NOZ_1_POS), Extruder_Icon_Info, icon_scale) + .icon(ICON_POS(NOZ_2_POS), Extruder_Icon_Info, icon_scale); // Draw Bed Heat Bitmap on Bed Heat Button - cmd.cmd(BITMAP_SOURCE(Bed_Heat_Icon_Info)) - .cmd(BITMAP_LAYOUT(Bed_Heat_Icon_Info)) - .cmd(BITMAP_SIZE (Bed_Heat_Icon_Info)) - .icon (BTN_POS(1,2), BTN_SIZE(1,1), Bed_Heat_Icon_Info, icon_scale); + cmd.cmd (BITMAP_SOURCE(Bed_Heat_Icon_Info)) + .cmd (BITMAP_LAYOUT(Bed_Heat_Icon_Info)) + .cmd (BITMAP_SIZE (Bed_Heat_Icon_Info)) + .icon(ICON_POS(BED_POS), Bed_Heat_Icon_Info, icon_scale); // Draw Fan Percent Bitmap on Bed Heat Button - cmd.cmd(BITMAP_SOURCE(Fan_Icon_Info)) - .cmd(BITMAP_LAYOUT(Fan_Icon_Info)) - .cmd(BITMAP_SIZE (Fan_Icon_Info)) - .icon (BTN_POS(5,2), BTN_SIZE(1,1), Fan_Icon_Info, icon_scale); + cmd.cmd (BITMAP_SOURCE(Fan_Icon_Info)) + .cmd (BITMAP_LAYOUT(Fan_Icon_Info)) + .cmd (BITMAP_SIZE (Fan_Icon_Info)) + .icon(ICON_POS(FAN_POS), Fan_Icon_Info, icon_scale); #ifdef TOUCH_UI_USE_UTF8 load_utf8_bitmaps(cmd); // Restore font bitmap handles @@ -212,10 +207,10 @@ void StatusScreen::draw_temperature(draw_mode_t what) { cmd.tag(5) .font(font_medium) - .text(BTN_POS(2,1), BTN_SIZE(3,1), e0_str) - .text(BTN_POS(6,1), BTN_SIZE(3,1), e1_str) - .text(BTN_POS(2,2), BTN_SIZE(3,1), bed_str) - .text(BTN_POS(6,2), BTN_SIZE(3,1), fan_str); + .text(TEXT_POS(NOZ_1_POS), e0_str) + .text(TEXT_POS(NOZ_2_POS), e1_str) + .text(TEXT_POS(BED_POS), bed_str) + .text(TEXT_POS(FAN_POS), fan_str); } } @@ -225,15 +220,18 @@ void StatusScreen::draw_progress(draw_mode_t what) { CommandProcessor cmd; + #if ENABLED(TOUCH_UI_PORTRAIT) + #define TIME_POS BTN_POS(1,3), BTN_SIZE(4,1) + #define PROGRESS_POS BTN_POS(5,3), BTN_SIZE(4,1) + #else + #define TIME_POS BTN_POS(9,1), BTN_SIZE(4,1) + #define PROGRESS_POS BTN_POS(9,2), BTN_SIZE(4,1) + #endif + if (what & BACKGROUND) { cmd.tag(0).font(font_medium) - #ifdef TOUCH_UI_PORTRAIT - .fgcolor(progress) .button(BTN_POS(1,3), BTN_SIZE(4,1), F(""), OPT_FLAT) - .button(BTN_POS(5,3), BTN_SIZE(4,1), F(""), OPT_FLAT); - #else - .fgcolor(progress) .button(BTN_POS(9,1), BTN_SIZE(4,1), F(""), OPT_FLAT) - .button(BTN_POS(9,2), BTN_SIZE(4,1), F(""), OPT_FLAT); - #endif + .fgcolor(progress).button(TIME_POS, F(""), OPT_FLAT) + .button(PROGRESS_POS, F(""), OPT_FLAT); } if (what & FOREGROUND) { @@ -248,13 +246,8 @@ void StatusScreen::draw_progress(draw_mode_t what) { sprintf_P(progress_str, PSTR("%-3d %%"), getProgress_percent() ); cmd.font(font_medium) - #ifdef TOUCH_UI_PORTRAIT - .tag(0).text(BTN_POS(1,3), BTN_SIZE(4,1), time_str) - .text(BTN_POS(5,3), BTN_SIZE(4,1), progress_str); - #else - .tag(0).text(BTN_POS(9,1), BTN_SIZE(4,1), time_str) - .text(BTN_POS(9,2), BTN_SIZE(4,1), progress_str); - #endif + .tag(0).text(TIME_POS, time_str) + .text(PROGRESS_POS, progress_str); } } @@ -266,6 +259,14 @@ void StatusScreen::draw_interaction_buttons(draw_mode_t what) { if (what & FOREGROUND) { using namespace ExtUI; + #if ENABLED(TOUCH_UI_PORTRAIT) + #define MEDIA_BTN_POS BTN_POS(1,8), BTN_SIZE(2,1) + #define MENU_BTN_POS BTN_POS(3,8), BTN_SIZE(2,1) + #else + #define MEDIA_BTN_POS BTN_POS(1,7), BTN_SIZE(2,2) + #define MENU_BTN_POS BTN_POS(3,7), BTN_SIZE(2,2) + #endif + const bool has_media = isMediaInserted() && !isPrintingFromMedia(); CommandProcessor cmd; @@ -273,42 +274,29 @@ void StatusScreen::draw_interaction_buttons(draw_mode_t what) { .font(Theme::font_medium) .enabled(has_media) .colors(has_media ? action_btn : normal_btn) - .tag(3).button( - #ifdef TOUCH_UI_PORTRAIT - BTN_POS(1,8), BTN_SIZE(2,1), - #else - BTN_POS(1,7), BTN_SIZE(2,2), - #endif - isPrintingFromMedia() ? GET_TEXT_F(MSG_PRINTING) : GET_TEXT_F(MSG_BUTTON_MEDIA) - ).colors(!has_media ? action_btn : normal_btn) - #ifdef TOUCH_UI_PORTRAIT - .tag(4).button( BTN_POS(3,8), BTN_SIZE(2,1), GET_TEXT_F(MSG_BUTTON_MENU)); - #else - .tag(4).button( BTN_POS(3,7), BTN_SIZE(2,2), GET_TEXT_F(MSG_BUTTON_MENU)); - #endif + .tag(3).button(MEDIA_BTN_POS, isPrintingFromMedia() ? GET_TEXT_F(MSG_PRINTING) : GET_TEXT_F(MSG_BUTTON_MEDIA)) + .colors(!has_media ? action_btn : normal_btn) + .tag(4).button( MENU_BTN_POS, GET_TEXT_F(MSG_BUTTON_MENU)); } #undef GRID_COLS } void StatusScreen::draw_status_message(draw_mode_t what, const char* message) { #define GRID_COLS 1 + + #if ENABLED(TOUCH_UI_PORTRAIT) + #define STATUS_POS BTN_POS(1,4), BTN_SIZE(1,1) + #else + #define STATUS_POS BTN_POS(1,3), BTN_SIZE(1,2) + #endif + if (what & BACKGROUND) { CommandProcessor cmd; cmd.fgcolor(Theme::status_msg) .tag(0) - #ifdef TOUCH_UI_PORTRAIT - .button( BTN_POS(1,4), BTN_SIZE(1,1), F(""), OPT_FLAT); - #else - .button( BTN_POS(1,3), BTN_SIZE(1,2), F(""), OPT_FLAT); - #endif + .button( STATUS_POS, F(""), OPT_FLAT); - draw_text_box(cmd, - #ifdef TOUCH_UI_PORTRAIT - BTN_POS(1,4), BTN_SIZE(1,1), - #else - BTN_POS(1,3), BTN_SIZE(1,2), - #endif - message, OPT_CENTER, font_large); + draw_text_box(cmd, STATUS_POS, message, OPT_CENTER, font_large); } #undef GRID_COLS } @@ -326,10 +314,10 @@ void StatusScreen::setStatusMessage(const char* message) { .cmd(CLEAR(true,true,true)); draw_temperature(BACKGROUND); - draw_progress(BACKGROUND); - draw_axis_position(BACKGROUND); draw_status_message(BACKGROUND, message); draw_interaction_buttons(BACKGROUND); + draw_progress(BACKGROUND); + draw_axis_position(BACKGROUND); storeBackground(); 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 933e91db80fd..e2770d8116d3 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 @@ -24,121 +24,149 @@ #pragma once namespace Theme { - #ifdef TOUCH_UI_LULZBOT_BIO - // The Lulzbot Bio uses the color PANTONE 2175C on the case silkscreen. - // This translates to HSL(208°, 100%, 39%) as an accent color on the GUI. - - constexpr int accent_hue = 208; - constexpr float accent_sat = 0.5; - - constexpr uint32_t logo_bg_rgb = 0xffffff; - constexpr uint32_t logo_fill_rgb = 0xffffff; - constexpr uint32_t logo_stroke_rgb = hsl_to_rgb(accent_hue, 1.0, 0.39); + #if ENABLED(TOUCH_UI_COCOA_THEME) + constexpr int accent_hue = 23; + + // Browns and Oranges + constexpr uint32_t accent_color_1 = hsl_to_rgb(12.8,0.597,0.263); // Darkest + constexpr uint32_t accent_color_2 = hsl_to_rgb(12.8,0.597,0.263); + constexpr uint32_t accent_color_3 = hsl_to_rgb( 9.6,0.664,0.443); + constexpr uint32_t accent_color_4 = hsl_to_rgb(16.3,0.873,0.537); + constexpr uint32_t accent_color_5 = hsl_to_rgb(23.0,0.889,0.539); + constexpr uint32_t accent_color_6 = hsl_to_rgb(23.0,0.889,0.539); // Lightest #else - // The Lulzbot logo uses the color PANTONE 382c. - // This translates to HSL(68°, 68%, 52%) as an accent color on the GUI. - - constexpr int accent_hue = 68; - constexpr float accent_sat = 0.68; - - constexpr uint32_t logo_bg_rgb = hsl_to_rgb(accent_hue, 0.77, 0.64); - constexpr uint32_t logo_fill_rgb = hsl_to_rgb(accent_hue, 0.68, 0.52); // Lulzbot Green - constexpr uint32_t logo_stroke_rgb = 0x000000; + // Use linear accent colors + + #if ANY(TOUCH_UI_ROYAL_THEME, TOUCH_UI_FROZEN_THEME) + // Dark blue accent colors + constexpr int accent_hue = 216; + constexpr float accent_sat = 0.7; + #else + // Green accent colors + constexpr int accent_hue = 68; + constexpr float accent_sat = 0.68; + #endif + + // Shades of accent color + constexpr uint32_t accent_color_0 = hsl_to_rgb(accent_hue, accent_sat, 0.15); // Darkest + constexpr uint32_t accent_color_1 = hsl_to_rgb(accent_hue, accent_sat, 0.26); + constexpr uint32_t accent_color_2 = hsl_to_rgb(accent_hue, accent_sat, 0.39); + constexpr uint32_t accent_color_3 = hsl_to_rgb(accent_hue, accent_sat, 0.52); + constexpr uint32_t accent_color_4 = hsl_to_rgb(accent_hue, accent_sat, 0.65); + constexpr uint32_t accent_color_5 = hsl_to_rgb(accent_hue, accent_sat, 0.78); + constexpr uint32_t accent_color_6 = hsl_to_rgb(accent_hue, accent_sat, 0.91); // Lightest #endif - // Shades of accent color + // Shades of gray - #ifdef TOUCH_UI_COCOA_PRESS - constexpr uint32_t accent_color_1 = hsl_to_rgb(12.8,0.597,0.263); // Darkest - constexpr uint32_t accent_color_2 = hsl_to_rgb(12.8,0.597,0.263); - constexpr uint32_t accent_color_3 = hsl_to_rgb( 9.6,0.664,0.443); - constexpr uint32_t accent_color_4 = hsl_to_rgb(16.3,0.873,0.537); - constexpr uint32_t accent_color_5 = hsl_to_rgb(23.0,0.889,0.539); - constexpr uint32_t accent_color_6 = hsl_to_rgb(23.0,0.889,0.539); // Lightest + constexpr float gray_sat = 0.14; + constexpr uint32_t gray_color_0 = hsl_to_rgb(accent_hue, gray_sat, 0.15); // Darkest + constexpr uint32_t gray_color_1 = hsl_to_rgb(accent_hue, gray_sat, 0.26); + constexpr uint32_t gray_color_2 = hsl_to_rgb(accent_hue, gray_sat, 0.39); + constexpr uint32_t gray_color_3 = hsl_to_rgb(accent_hue, gray_sat, 0.52); + constexpr uint32_t gray_color_4 = hsl_to_rgb(accent_hue, gray_sat, 0.65); + constexpr uint32_t gray_color_5 = hsl_to_rgb(accent_hue, gray_sat, 0.78); + constexpr uint32_t gray_color_6 = hsl_to_rgb(accent_hue, gray_sat, 0.91); // Lightest + + #if ENABLED(TOUCH_UI_ROYAL_THEME) + constexpr uint32_t theme_darkest = accent_color_1; + constexpr uint32_t theme_dark = accent_color_4; + + constexpr uint32_t bg_color = gray_color_0; + constexpr uint32_t axis_label = gray_color_1; + + constexpr uint32_t bg_text_enabled = accent_color_6; + constexpr uint32_t bg_text_disabled = gray_color_0; + constexpr uint32_t bg_normal = accent_color_4; + constexpr uint32_t fg_disabled = gray_color_0; + constexpr uint32_t fg_normal = accent_color_0; + constexpr uint32_t fg_action = accent_color_1; + + constexpr uint32_t logo_bg_rgb = accent_color_1; + constexpr uint32_t logo_fill_rgb = accent_color_0; + constexpr uint32_t logo_stroke_rgb = accent_color_4; + #elif ANY(TOUCH_UI_COCOA_THEME, TOUCH_UI_FROZEN_THEME) + constexpr uint32_t theme_darkest = accent_color_1; + constexpr uint32_t theme_dark = accent_color_4; + + constexpr uint32_t bg_color = 0xFFFFFF; + constexpr uint32_t axis_label = gray_color_5; + + constexpr uint32_t bg_text_enabled = accent_color_1; + constexpr uint32_t bg_text_disabled = gray_color_1; + constexpr uint32_t bg_normal = accent_color_4; + constexpr uint32_t fg_disabled = gray_color_6; + constexpr uint32_t fg_normal = accent_color_1; + constexpr uint32_t fg_action = accent_color_4; + + constexpr uint32_t logo_bg_rgb = accent_color_5; + constexpr uint32_t logo_fill_rgb = accent_color_6; + constexpr uint32_t logo_stroke_rgb = accent_color_2; #else - constexpr uint32_t accent_color_1 = hsl_to_rgb(accent_hue, accent_sat, 0.26); // Darkest - constexpr uint32_t accent_color_2 = hsl_to_rgb(accent_hue, accent_sat, 0.39); - constexpr uint32_t accent_color_3 = hsl_to_rgb(accent_hue, accent_sat, 0.52); - constexpr uint32_t accent_color_4 = hsl_to_rgb(accent_hue, accent_sat, 0.65); - constexpr uint32_t accent_color_5 = hsl_to_rgb(accent_hue, accent_sat, 0.78); - constexpr uint32_t accent_color_6 = hsl_to_rgb(accent_hue, accent_sat, 0.91); // Lightest + constexpr uint32_t theme_darkest = gray_color_1; + constexpr uint32_t theme_dark = gray_color_2; + + constexpr uint32_t bg_color = gray_color_1; + constexpr uint32_t axis_label = gray_color_2; + + constexpr uint32_t bg_text_enabled = 0xFFFFFF; + constexpr uint32_t bg_text_disabled = gray_color_2; + constexpr uint32_t bg_normal = gray_color_1; + constexpr uint32_t fg_disabled = gray_color_1; + constexpr uint32_t fg_normal = gray_color_2; + constexpr uint32_t fg_action = accent_color_2; + + constexpr uint32_t logo_bg_rgb = accent_color_4; + constexpr uint32_t logo_fill_rgb = accent_color_3; + constexpr uint32_t logo_stroke_rgb = 0x000000; #endif - // Shades of gray - - constexpr float gray_sat = 0.14; + 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; - constexpr uint32_t gray_color_1 = hsl_to_rgb(accent_hue, gray_sat, 0.26); // Darkest - constexpr uint32_t gray_color_2 = hsl_to_rgb(accent_hue, gray_sat, 0.39); - constexpr uint32_t gray_color_3 = hsl_to_rgb(accent_hue, gray_sat, 0.52); - constexpr uint32_t gray_color_4 = hsl_to_rgb(accent_hue, gray_sat, 0.65); - constexpr uint32_t gray_color_5 = hsl_to_rgb(accent_hue, gray_sat, 0.78); - constexpr uint32_t gray_color_6 = hsl_to_rgb(accent_hue, gray_sat, 0.91); // Lightest - - #if NONE(TOUCH_UI_LULZBOT_BIO, TOUCH_UI_COCOA_PRESS) - // Lulzbot TAZ Pro - constexpr uint32_t theme_darkest = gray_color_1; - constexpr uint32_t theme_dark = gray_color_2; - - constexpr uint32_t bg_color = theme_darkest; - constexpr uint32_t bg_text_disabled = theme_dark; - constexpr uint32_t bg_text_enabled = 0xFFFFFF; - constexpr uint32_t bg_normal = theme_darkest; - - constexpr uint32_t fg_normal = theme_dark; - constexpr uint32_t fg_action = accent_color_2; - constexpr uint32_t fg_disabled = theme_darkest; + #if ENABLED(TOUCH_UI_ROYAL_THEME) + constexpr uint32_t x_axis = hsl_to_rgb(0, 1.00, 0.26); + constexpr uint32_t y_axis = hsl_to_rgb(120, 1.00, 0.13); + constexpr uint32_t z_axis = hsl_to_rgb(240, 1.00, 0.10); #else - // Lulzbot Bio - constexpr uint32_t theme_darkest = accent_color_1; - constexpr uint32_t theme_dark = accent_color_4; - - constexpr uint32_t bg_color = 0xFFFFFF; - constexpr uint32_t bg_text_disabled = gray_color_1; - constexpr uint32_t bg_text_enabled = accent_color_1; - constexpr uint32_t bg_normal = accent_color_4; - - constexpr uint32_t fg_normal = accent_color_1; - constexpr uint32_t fg_action = accent_color_4; - constexpr uint32_t fg_disabled = gray_color_6; - - 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; + constexpr uint32_t x_axis = hsl_to_rgb(0, 1.00, 0.5); + constexpr uint32_t y_axis = hsl_to_rgb(120, 1.00, 0.37); + constexpr uint32_t z_axis = hsl_to_rgb(240, 1.00, 0.37); #endif - - constexpr uint32_t x_axis = 0xFF0000; - constexpr uint32_t y_axis = 0x00BB00; - constexpr uint32_t z_axis = 0x0000BF; - constexpr uint32_t e_axis = gray_color_2; - constexpr uint32_t feedrate = gray_color_2; - constexpr uint32_t other = gray_color_2; + constexpr uint32_t e_axis = axis_label; + constexpr uint32_t feedrate = axis_label; + constexpr uint32_t other = axis_label; // Status screen - constexpr uint32_t progress = gray_color_2; - constexpr uint32_t status_msg = gray_color_2; - constexpr uint32_t fan_speed = 0x377198; - constexpr uint32_t temp = 0x892c78; - constexpr uint32_t axis_label = gray_color_2; + constexpr uint32_t progress = axis_label; + constexpr uint32_t status_msg = axis_label; + #if ENABLED(TOUCH_UI_ROYAL_THEME) + constexpr uint32_t fan_speed = hsl_to_rgb(240, 0.5, 0.13); + constexpr uint32_t temp = hsl_to_rgb(343, 1.0, 0.23); + #else + constexpr uint32_t fan_speed = hsl_to_rgb(204, 0.47, 0.41); + constexpr uint32_t temp = hsl_to_rgb(311, 0.51, 0.35); + #endif - constexpr uint32_t disabled_icon = gray_color_1; + constexpr uint32_t disabled_icon = gray_color_1; // Calibration Registers Screen - constexpr uint32_t transformA = 0x3010D0; - constexpr uint32_t transformB = 0x4010D0; - constexpr uint32_t transformC = 0x5010D0; - constexpr uint32_t transformD = 0x6010D0; - constexpr uint32_t transformE = 0x7010D0; - constexpr uint32_t transformF = 0x8010D0; - constexpr uint32_t transformVal = 0x104010; - - constexpr btn_colors disabled_btn = {.bg = bg_color, .grad = fg_disabled, .fg = fg_disabled, .rgb = fg_disabled }; - constexpr btn_colors normal_btn = {.bg = fg_action, .grad = 0xFFFFFF, .fg = fg_normal, .rgb = 0xFFFFFF }; - constexpr btn_colors action_btn = {.bg = bg_color, .grad = 0xFFFFFF, .fg = fg_action, .rgb = 0xFFFFFF }; - constexpr btn_colors red_btn = {.bg = 0xFF5555, .grad = 0xFFFFFF, .fg = 0xFF0000, .rgb = 0xFFFFFF }; - constexpr btn_colors ui_slider = {.bg = theme_darkest, .grad = 0xFFFFFF, .fg = theme_dark, .rgb = accent_color_3 }; - constexpr btn_colors ui_toggle = {.bg = theme_darkest, .grad = 0xFFFFFF, .fg = theme_dark, .rgb = 0xFFFFFF }; + constexpr uint32_t transformA = 0x3010D0; + constexpr uint32_t transformB = 0x4010D0; + constexpr uint32_t transformC = 0x5010D0; + constexpr uint32_t transformD = 0x6010D0; + constexpr uint32_t transformE = 0x7010D0; + constexpr uint32_t transformF = 0x8010D0; + constexpr uint32_t transformVal = 0x104010; + + constexpr btn_colors disabled_btn = {.bg = bg_color, .grad = fg_disabled, .fg = fg_disabled, .rgb = fg_disabled }; + constexpr btn_colors normal_btn = {.bg = fg_action, .grad = 0xFFFFFF, .fg = fg_normal, .rgb = 0xFFFFFF }; + constexpr btn_colors action_btn = {.bg = bg_color, .grad = 0xFFFFFF, .fg = fg_action, .rgb = 0xFFFFFF }; + constexpr btn_colors red_btn = {.bg = 0xFF5555, .grad = 0xFFFFFF, .fg = 0xFF0000, .rgb = 0xFFFFFF }; + constexpr btn_colors ui_slider = {.bg = theme_darkest, .grad = 0xFFFFFF, .fg = theme_dark, .rgb = accent_color_3 }; + constexpr btn_colors ui_toggle = {.bg = theme_darkest, .grad = 0xFFFFFF, .fg = theme_dark, .rgb = 0xFFFFFF }; // Temperature color scale diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/marlin_bootscreen_landscape.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/marlin_bootscreen_landscape.h index 5e01f0471c6b..a65cbea52ad8 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/marlin_bootscreen_landscape.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/marlin_bootscreen_landscape.h @@ -35,5 +35,5 @@ const PROGMEM uint16_t logo_stroke[] = {0xADF3, 0x546C, 0x419D, 0x546F, 0x3D05, #define LOGO_BACKGROUND logo_bg_rgb #define LOGO_PAINT_PATHS \ - LOGO_PAINT_PATH(logo_stroke_rgb, logo_stroke) \ - LOGO_PAINT_PATH(logo_fill_rgb, logo_fill) + LOGO_PAINT_PATH(logo_fill_rgb, logo_fill) \ + LOGO_PAINT_PATH(logo_stroke_rgb, logo_stroke) diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/marlin_bootscreen_portrait.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/marlin_bootscreen_portrait.h index a5af7a14cd9c..a9c1d4049e91 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/marlin_bootscreen_portrait.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/marlin_bootscreen_portrait.h @@ -35,5 +35,5 @@ const PROGMEM uint16_t logo_stroke[] = {0x3C19, 0x70C5, 0x371A, 0x7159, 0x3302, #define LOGO_BACKGROUND logo_bg_rgb #define LOGO_PAINT_PATHS \ - LOGO_PAINT_PATH(logo_stroke_rgb, logo_stroke) \ - LOGO_PAINT_PATH(logo_fill_rgb, logo_fill) + LOGO_PAINT_PATH(logo_fill_rgb, logo_fill) \ + LOGO_PAINT_PATH(logo_stroke_rgb, logo_stroke) diff --git a/Marlin/src/lcd/extui/ui_api.h b/Marlin/src/lcd/extui/ui_api.h index 61fecaed46a8..01e0d1b7a384 100644 --- a/Marlin/src/lcd/extui/ui_api.h +++ b/Marlin/src/lcd/extui/ui_api.h @@ -341,10 +341,10 @@ namespace ExtUI { void onConfigurationStoreWritten(bool success); void onConfigurationStoreRead(bool success); #if ENABLED(POWER_LOSS_RECOVERY) - void OnPowerLossResume(); + void onPowerLossResume(); #endif #if HAS_PID_HEATING - void OnPidTuning(const result_t rst); + void onPidTuning(const result_t rst); #endif }; diff --git a/Marlin/src/lcd/extui_dgus_lcd.cpp b/Marlin/src/lcd/extui_dgus_lcd.cpp index 66a58f82dc08..855d09033e85 100644 --- a/Marlin/src/lcd/extui_dgus_lcd.cpp +++ b/Marlin/src/lcd/extui_dgus_lcd.cpp @@ -123,7 +123,7 @@ namespace ExtUI { } #if ENABLED(POWER_LOSS_RECOVERY) - void OnPowerLossResume() { + void onPowerLossResume() { // Called on resume from power-loss ScreenHandler.GotoScreen(DGUSLCD_SCREEN_POWER_LOSS); } @@ -131,9 +131,9 @@ namespace ExtUI { #if HAS_PID_HEATING - void OnPidTuning(const result_t rst) { + void onPidTuning(const result_t rst) { // Called for temperature PID tuning result - SERIAL_ECHOLNPAIR("OnPidTuning:",rst); + SERIAL_ECHOLNPAIR("onPidTuning:",rst); switch(rst) { case PID_BAD_EXTRUDER_NUM: ScreenHandler.setstatusmessagePGM(PSTR(STR_PID_BAD_EXTRUDER_NUM)); diff --git a/Marlin/src/lcd/extui_example.cpp b/Marlin/src/lcd/extui_example.cpp index 741787dbe665..5c9a193ded3b 100644 --- a/Marlin/src/lcd/extui_example.cpp +++ b/Marlin/src/lcd/extui_example.cpp @@ -94,13 +94,13 @@ namespace ExtUI { } #if ENABLED(POWER_LOSS_RECOVERY) - void OnPowerLossResume() { + void onPowerLossResume() { // Called on resume from power-loss } #endif #if HAS_PID_HEATING - void OnPidTuning(const result_t rst) { + void onPidTuning(const result_t rst) { // Called for temperature PID tuning result } #endif diff --git a/Marlin/src/lcd/extui_malyan_lcd.cpp b/Marlin/src/lcd/extui_malyan_lcd.cpp index 0bb8060b07c0..ddb8b846cb07 100644 --- a/Marlin/src/lcd/extui_malyan_lcd.cpp +++ b/Marlin/src/lcd/extui_malyan_lcd.cpp @@ -483,7 +483,7 @@ namespace ExtUI { void onLoadSettings(const char*) {} void onConfigurationStoreWritten(bool) {} void onConfigurationStoreRead(bool) {} - void OnPidTuning(const result_t) {} + void onPidTuning(const result_t) {} } #endif // MALYAN_LCD diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index 8fa22e2c713e..a52d9652ac64 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -602,6 +602,9 @@ namespace Language_en { PROGMEM Language_Str MSG_BACKLASH_C = LCD_STR_C; PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Correction"); PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Smoothing"); + + PROGMEM Language_Str MSG_LEVEL_X_AXIS = _UxGT("Level X Axis"); + PROGMEM Language_Str MSG_AUTO_CALIBRATE = _UxGT("Auto Calibrate"); } #if FAN_COUNT == 1 diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 4e49fcfa2463..4018c7586c74 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -411,7 +411,7 @@ volatile bool Temperature::raw_temps_ready = false; if (target > GHV(BED_MAXTEMP - 10, temp_range[heater].maxtemp - 15)) { SERIAL_ECHOLNPGM(STR_PID_TEMP_TOO_HIGH); #if ENABLED(EXTENSIBLE_UI) - ExtUI::OnPidTuning(ExtUI::result_t::PID_TEMP_TOO_HIGH); + ExtUI::onPidTuning(ExtUI::result_t::PID_TEMP_TOO_HIGH); #endif return; } @@ -527,7 +527,7 @@ volatile bool Temperature::raw_temps_ready = false; if (current_temp > target + MAX_OVERSHOOT_PID_AUTOTUNE) { SERIAL_ECHOLNPGM(STR_PID_TEMP_TOO_HIGH); #if ENABLED(EXTENSIBLE_UI) - ExtUI::OnPidTuning(ExtUI::result_t::PID_TEMP_TOO_HIGH); + ExtUI::onPidTuning(ExtUI::result_t::PID_TEMP_TOO_HIGH); #endif break; } @@ -572,7 +572,7 @@ volatile bool Temperature::raw_temps_ready = false; #endif if (((ms - t1) + (ms - t2)) > (MAX_CYCLE_TIME_PID_AUTOTUNE * 60L * 1000L)) { #if ENABLED(EXTENSIBLE_UI) - ExtUI::OnPidTuning(ExtUI::result_t::PID_TUNING_TIMEOUT); + ExtUI::onPidTuning(ExtUI::result_t::PID_TUNING_TIMEOUT); #endif SERIAL_ECHOLNPGM(STR_PID_TIMEOUT); break; @@ -623,7 +623,7 @@ volatile bool Temperature::raw_temps_ready = false; printerEventLEDs.onPidTuningDone(color); #endif #if ENABLED(EXTENSIBLE_UI) - ExtUI::OnPidTuning(ExtUI::result_t::PID_DONE); + ExtUI::onPidTuning(ExtUI::result_t::PID_DONE); #endif goto EXIT_M303; @@ -637,7 +637,7 @@ volatile bool Temperature::raw_temps_ready = false; printerEventLEDs.onPidTuningDone(color); #endif #if ENABLED(EXTENSIBLE_UI) - ExtUI::OnPidTuning(ExtUI::result_t::PID_DONE); + ExtUI::onPidTuning(ExtUI::result_t::PID_DONE); #endif EXIT_M303: From e7f020f3f208db23450c845a6c4b67d784a64058 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 31 Mar 2020 14:42:32 -0500 Subject: [PATCH 08/37] Shorten some internal pin names --- Marlin/src/pins/ramps/pins_TRIGORILLA_14.h | 36 +++++++++++----------- 1 file changed, 18 insertions(+), 18 deletions(-) diff --git a/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h b/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h index 9016028055ca..f32f006e9268 100644 --- a/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h +++ b/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h @@ -47,43 +47,43 @@ #endif // Labeled pins -#define TRIGORILLA_HEATER_BED_PIN 8 -#define TRIGORILLA_HEATER_0_PIN 10 -#define TRIGORILLA_HEATER_1_PIN 45 // Anycubic Kossel: Unused +#define TG_HEATER_BED_PIN 8 +#define TG_HEATER_0_PIN 10 +#define TG_HEATER_1_PIN 45 // Anycubic Kossel: Unused -#define TRIGORILLA_FAN0_PIN 9 // Anycubic Kossel: Usually the part cooling fan -#define TRIGORILLA_FAN1_PIN 7 // Anycubic Kossel: Unused -#define TRIGORILLA_FAN2_PIN 44 // Anycubic Kossel: Hotend fan +#define TG_FAN0_PIN 9 // Anycubic Kossel: Usually the part cooling fan +#define TG_FAN1_PIN 7 // Anycubic Kossel: Unused +#define TG_FAN2_PIN 44 // Anycubic Kossel: Hotend fan // Remap MOSFET pins to common usages: -#define RAMPS_D10_PIN TRIGORILLA_HEATER_0_PIN // HEATER_0_PIN is always RAMPS_D10_PIN in pins_RAMPS.h +#define RAMPS_D10_PIN TG_HEATER_0_PIN // HEATER_0_PIN is always RAMPS_D10_PIN in pins_RAMPS.h #if HOTENDS > 1 // EEF and EEB - #define RAMPS_D9_PIN TRIGORILLA_HEATER_1_PIN + #define RAMPS_D9_PIN TG_HEATER_1_PIN #if !TEMP_SENSOR_BED // EEF - #define RAMPS_D8_PIN TRIGORILLA_FAN0_PIN + #define RAMPS_D8_PIN TG_FAN0_PIN #else // EEB - #define RAMPS_D8_PIN TRIGORILLA_HEATER_BED_PIN - #define FAN_PIN TRIGORILLA_FAN0_PIN // Override pin 4 in pins_RAMPS.h + #define RAMPS_D8_PIN TG_HEATER_BED_PIN + #define FAN_PIN TG_FAN0_PIN // Override pin 4 in pins_RAMPS.h #endif #elif TEMP_SENSOR_BED // EFB (Anycubic Kossel default) - #define RAMPS_D9_PIN TRIGORILLA_FAN0_PIN - #define RAMPS_D8_PIN TRIGORILLA_HEATER_BED_PIN + #define RAMPS_D9_PIN TG_FAN0_PIN + #define RAMPS_D8_PIN TG_HEATER_BED_PIN #else // EFF - #define RAMPS_D9_PIN TRIGORILLA_FAN1_PIN - #define RAMPS_D8_PIN TRIGORILLA_FAN0_PIN + #define RAMPS_D9_PIN TG_FAN1_PIN + #define RAMPS_D8_PIN TG_FAN0_PIN #endif #if HOTENDS > 1 || TEMP_SENSOR_BED // EEF, EEB, EFB - #define FAN1_PIN TRIGORILLA_FAN1_PIN + #define FAN1_PIN TG_FAN1_PIN #endif -#define FAN2_PIN TRIGORILLA_FAN2_PIN -#define ORIG_E0_AUTO_FAN_PIN TRIGORILLA_FAN2_PIN // Used in Anycubic Kossel example config +#define FAN2_PIN TG_FAN2_PIN +#define ORIG_E0_AUTO_FAN_PIN TG_FAN2_PIN // Used in Anycubic Kossel example config #include "pins_RAMPS.h" From 5236889377c3cef48644696372db7e5bb2a92d3e Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 1 Apr 2020 00:03:36 +0000 Subject: [PATCH 09/37] [cron] Bump distribution date (2020-04-01) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 33b9bbfbea6d..00d24330a6dc 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-03-31" + #define STRING_DISTRIBUTION_DATE "2020-04-01" #endif /** From 178ca2bcdffcdd185cd38ba77627ee6e64cbec0b Mon Sep 17 00:00:00 2001 From: Marcelo Castagna Date: Tue, 31 Mar 2020 21:13:37 -0300 Subject: [PATCH 10/37] Fix M710 report formatting (#17356) --- Marlin/src/gcode/feature/controllerfan/M710.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/Marlin/src/gcode/feature/controllerfan/M710.cpp b/Marlin/src/gcode/feature/controllerfan/M710.cpp index e00fa77d62b6..c19919b2d486 100644 --- a/Marlin/src/gcode/feature/controllerfan/M710.cpp +++ b/Marlin/src/gcode/feature/controllerfan/M710.cpp @@ -29,11 +29,11 @@ void M710_report(const bool forReplay) { if (!forReplay) { SERIAL_ECHOLNPGM("; Controller Fan"); SERIAL_ECHO_START(); } - SERIAL_ECHOLNPAIR("M710 " - "S", int(controllerFan.settings.active_speed), - "I", int(controllerFan.settings.idle_speed), - "A", int(controllerFan.settings.auto_mode), - "D", controllerFan.settings.duration, + SERIAL_ECHOLNPAIR(" M710" + " S", int(controllerFan.settings.active_speed), + " I", int(controllerFan.settings.idle_speed), + " A", int(controllerFan.settings.auto_mode), + " D", controllerFan.settings.duration, " ; (", (int(controllerFan.settings.active_speed) * 100) / 255, "%" " ", (int(controllerFan.settings.idle_speed) * 100) / 255, "%)" ); From 192c7c27b9130d5e13f6a1a96ccf490c48d2e26c Mon Sep 17 00:00:00 2001 From: Simon Jouet Date: Wed, 1 Apr 2020 22:20:38 +0100 Subject: [PATCH 11/37] Fix extra TMC serial begin calls (#17351) --- Marlin/src/module/stepper/trinamic.cpp | 43 ++++++++++++++++---------- 1 file changed, 27 insertions(+), 16 deletions(-) diff --git a/Marlin/src/module/stepper/trinamic.cpp b/Marlin/src/module/stepper/trinamic.cpp index 14598f9c73dc..f0ac48f51405 100644 --- a/Marlin/src/module/stepper/trinamic.cpp +++ b/Marlin/src/module/stepper/trinamic.cpp @@ -331,115 +331,126 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; #endif #endif + enum TMCAxis : uint8_t { X, Y, Z, X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5, E6, E7, TOTAL }; + void tmc_serial_begin() { + struct { + const void *ptr[TMCAxis::TOTAL]; + bool began(const TMCAxis a, const void * const p) { + LOOP_L_N(i, a) if (p == ptr[i]) return true; + ptr[a] = p; return false; + }; + } sp_helper; + #define HW_SERIAL_BEGIN(A) do{ if (sp_helper.began(TMCAxis::A, &A##_HARDWARE_SERIAL)) \ + A##_HARDWARE_SERIAL.begin(TMC_BAUD_RATE); }while(0) #if AXIS_HAS_UART(X) #ifdef X_HARDWARE_SERIAL - X_HARDWARE_SERIAL.begin(TMC_BAUD_RATE); + HW_SERIAL_BEGIN(X); #else stepperX.beginSerial(TMC_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(X2) #ifdef X2_HARDWARE_SERIAL - X2_HARDWARE_SERIAL.begin(TMC_BAUD_RATE); + HW_SERIAL_BEGIN(X2); #else stepperX2.beginSerial(TMC_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(Y) #ifdef Y_HARDWARE_SERIAL - Y_HARDWARE_SERIAL.begin(TMC_BAUD_RATE); + HW_SERIAL_BEGIN(Y); #else stepperY.beginSerial(TMC_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(Y2) #ifdef Y2_HARDWARE_SERIAL - Y2_HARDWARE_SERIAL.begin(TMC_BAUD_RATE); + HW_SERIAL_BEGIN(Y2); #else stepperY2.beginSerial(TMC_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(Z) #ifdef Z_HARDWARE_SERIAL - Z_HARDWARE_SERIAL.begin(TMC_BAUD_RATE); + HW_SERIAL_BEGIN(Z); #else stepperZ.beginSerial(TMC_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(Z2) #ifdef Z2_HARDWARE_SERIAL - Z2_HARDWARE_SERIAL.begin(TMC_BAUD_RATE); + HW_SERIAL_BEGIN(Z2); #else stepperZ2.beginSerial(TMC_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(Z3) #ifdef Z3_HARDWARE_SERIAL - Z3_HARDWARE_SERIAL.begin(TMC_BAUD_RATE); + HW_SERIAL_BEGIN(Z3); #else stepperZ3.beginSerial(TMC_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(Z4) #ifdef Z4_HARDWARE_SERIAL - Z4_HARDWARE_SERIAL.begin(TMC_BAUD_RATE); + HW_SERIAL_BEGIN(Z4); #else stepperZ4.beginSerial(TMC_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(E0) #ifdef E0_HARDWARE_SERIAL - E0_HARDWARE_SERIAL.begin(TMC_BAUD_RATE); + HW_SERIAL_BEGIN(E0); #else stepperE0.beginSerial(TMC_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(E1) #ifdef E1_HARDWARE_SERIAL - E1_HARDWARE_SERIAL.begin(TMC_BAUD_RATE); + HW_SERIAL_BEGIN(E1); #else stepperE1.beginSerial(TMC_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(E2) #ifdef E2_HARDWARE_SERIAL - E2_HARDWARE_SERIAL.begin(TMC_BAUD_RATE); + HW_SERIAL_BEGIN(E2); #else stepperE2.beginSerial(TMC_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(E3) #ifdef E3_HARDWARE_SERIAL - E3_HARDWARE_SERIAL.begin(TMC_BAUD_RATE); + HW_SERIAL_BEGIN(E3); #else stepperE3.beginSerial(TMC_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(E4) #ifdef E4_HARDWARE_SERIAL - E4_HARDWARE_SERIAL.begin(TMC_BAUD_RATE); + HW_SERIAL_BEGIN(E4); #else stepperE4.beginSerial(TMC_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(E5) #ifdef E5_HARDWARE_SERIAL - E5_HARDWARE_SERIAL.begin(TMC_BAUD_RATE); + HW_SERIAL_BEGIN(E5); #else stepperE5.beginSerial(TMC_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(E6) #ifdef E6_HARDWARE_SERIAL - E6_HARDWARE_SERIAL.begin(TMC_BAUD_RATE); + HW_SERIAL_BEGIN(E6); #else stepperE6.beginSerial(TMC_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(E7) #ifdef E7_HARDWARE_SERIAL - E7_HARDWARE_SERIAL.begin(TMC_BAUD_RATE); + HW_SERIAL_BEGIN(E7); #else stepperE7.beginSerial(TMC_BAUD_RATE); #endif From c47bdae9f20207b08f3f8b581c2e9a00bbf6b15b Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 2 Apr 2020 00:03:23 +0000 Subject: [PATCH 12/37] [cron] Bump distribution date (2020-04-02) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 00d24330a6dc..0316c69672e7 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-04-01" + #define STRING_DISTRIBUTION_DATE "2020-04-02" #endif /** From 7f5dc7b91920ffd4ecd8b70e58bc97cc6be39fa2 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 1 Apr 2020 15:00:43 -0500 Subject: [PATCH 13/37] More 8 extruders (TMC) support --- Marlin/src/module/configuration_store.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/Marlin/src/module/configuration_store.cpp b/Marlin/src/module/configuration_store.cpp index 2ecc9299c9b3..b2c728fbe0e5 100644 --- a/Marlin/src/module/configuration_store.cpp +++ b/Marlin/src/module/configuration_store.cpp @@ -37,7 +37,7 @@ */ // Change EEPROM version if the structure changes -#define EEPROM_VERSION "V76" +#define EEPROM_VERSION "V77" #define EEPROM_OFFSET 100 // Check the integrity of data offsets. @@ -134,10 +134,10 @@ #pragma pack(push, 1) // No padding between variables -typedef struct { uint16_t X, Y, Z, X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5; } tmc_stepper_current_t; -typedef struct { uint32_t X, Y, Z, X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5; } tmc_hybrid_threshold_t; -typedef struct { int16_t X, Y, Z, X2; } tmc_sgt_t; -typedef struct { bool X, Y, Z, X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5; } tmc_stealth_enabled_t; +typedef struct { uint16_t X, Y, Z, X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5, E6, E7; } tmc_stepper_current_t; +typedef struct { uint32_t X, Y, Z, X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5, E6, E7; } tmc_hybrid_threshold_t; +typedef struct { int16_t X, Y, Z, X2; } tmc_sgt_t; +typedef struct { bool X, Y, Z, X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5, E6, E7; } tmc_stealth_enabled_t; // Limit an index to an array size #define ALIM(I,ARR) _MIN(I, COUNT(ARR) - 1) From 514afddeb4b3a7ede9ff481504aae69219a95f68 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 1 Apr 2020 18:53:58 -0500 Subject: [PATCH 14/37] Minor code cleanup --- Marlin/src/feature/tmc_util.cpp | 2 +- Marlin/src/inc/Conditionals_post.h | 2 +- Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp | 4 ++-- Marlin/src/lcd/dogm/ultralcd_DOGM.cpp | 8 +------ Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp | 1 - Marlin/src/lcd/ultralcd.cpp | 6 ++--- Marlin/src/module/configuration_store.cpp | 6 ++--- Marlin/src/module/temperature.cpp | 22 ++++++------------- 8 files changed, 17 insertions(+), 34 deletions(-) diff --git a/Marlin/src/feature/tmc_util.cpp b/Marlin/src/feature/tmc_util.cpp index e5e69eed50b3..bfc2e1a555cc 100644 --- a/Marlin/src/feature/tmc_util.cpp +++ b/Marlin/src/feature/tmc_util.cpp @@ -1254,7 +1254,7 @@ void test_tmc_connection(const bool test_x, const bool test_y, const bool test_z #endif } - if (axis_connection) ui.set_status_P(GET_TEXT(MSG_ERROR_TMC)); + if (axis_connection) LCD_MESSAGEPGM(MSG_ERROR_TMC); } #endif // HAS_TRINAMIC_CONFIG diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 9ea298f02d46..20867b4fea08 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -2164,7 +2164,7 @@ #define SHARED_SD_CARD #endif #if DISABLED(SHARED_SD_CARD) - #define INIT_SDCARD_ON_BOOT + #define INIT_SDCARD_ON_BOOT 1 #endif #endif diff --git a/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp b/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp index ee025f6585d6..3c89d1803c55 100644 --- a/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp +++ b/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp @@ -367,11 +367,11 @@ void MarlinUI::init_lcd() { } bool MarlinUI::detected() { - return true + return (true #if EITHER(LCD_I2C_TYPE_MCP23017, LCD_I2C_TYPE_MCP23008) && defined(DETECT_DEVICE) && lcd.LcdDetected() == 1 #endif - ; + ); } #if HAS_SLOW_BUTTONS diff --git a/Marlin/src/lcd/dogm/ultralcd_DOGM.cpp b/Marlin/src/lcd/dogm/ultralcd_DOGM.cpp index fc7656f1cd7e..4e07999bf6f6 100644 --- a/Marlin/src/lcd/dogm/ultralcd_DOGM.cpp +++ b/Marlin/src/lcd/dogm/ultralcd_DOGM.cpp @@ -244,13 +244,7 @@ void MarlinUI::init_lcd() { #if DISABLED(MKS_LCD12864B) #if PIN_EXISTS(LCD_BACKLIGHT) - OUT_WRITE(LCD_BACKLIGHT_PIN, ( - #if ENABLED(DELAYED_BACKLIGHT_INIT) - LOW // Illuminate after reset - #else - HIGH // Illuminate right away - #endif - )); + OUT_WRITE(LCD_BACKLIGHT_PIN, DISABLED(DELAYED_BACKLIGHT_INIT)); // Illuminate after reset or right away #endif #if EITHER(MKS_12864OLED, MKS_12864OLED_SSD1306) diff --git a/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp b/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp index 6ac84c2bb0af..bd73e811d125 100644 --- a/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp +++ b/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp @@ -441,7 +441,6 @@ void DGUSScreenVariableHandler::DGUSLCD_SendHeaterStatusToDisplay(DGUS_VP_Variab DGUSLCD_SendStringToDisplay(var); } - void DGUSScreenVariableHandler::SDCardInserted() { top_file = 0; auto cs = ScreenHandler.getCurrentScreen(); diff --git a/Marlin/src/lcd/ultralcd.cpp b/Marlin/src/lcd/ultralcd.cpp index bbcb678dd84a..ff0331eb2072 100644 --- a/Marlin/src/lcd/ultralcd.cpp +++ b/Marlin/src/lcd/ultralcd.cpp @@ -351,10 +351,8 @@ void MarlinUI::init() { #endif #endif - #if HAS_ENCODER_ACTION - #if HAS_SLOW_BUTTONS - slow_buttons = 0; - #endif + #if HAS_ENCODER_ACTION && HAS_SLOW_BUTTONS + slow_buttons = 0; #endif update_buttons(); diff --git a/Marlin/src/module/configuration_store.cpp b/Marlin/src/module/configuration_store.cpp index b2c728fbe0e5..a2beb322f96f 100644 --- a/Marlin/src/module/configuration_store.cpp +++ b/Marlin/src/module/configuration_store.cpp @@ -1391,7 +1391,7 @@ void MarlinSettings::postprocess() { DEBUG_ECHO_START(); DEBUG_ECHOLNPAIR("EEPROM version mismatch (EEPROM=", stored_ver, " Marlin=" EEPROM_VERSION ")"); #if HAS_LCD_MENU && DISABLED(EEPROM_AUTO_INIT) - ui.set_status_P(GET_TEXT(MSG_ERR_EEPROM_VERSION)); + LCD_MESSAGEPGM(MSG_ERR_EEPROM_VERSION); #endif eeprom_error = true; } @@ -2199,7 +2199,7 @@ void MarlinSettings::postprocess() { DEBUG_ECHO_START(); DEBUG_ECHOLNPAIR("Index: ", int(eeprom_index - (EEPROM_OFFSET)), " Size: ", datasize()); #if HAS_LCD_MENU && DISABLED(EEPROM_AUTO_INIT) - ui.set_status_P(GET_TEXT(MSG_ERR_EEPROM_INDEX)); + LCD_MESSAGEPGM(MSG_ERR_EEPROM_INDEX); #endif } else if (working_crc != stored_crc) { @@ -2207,7 +2207,7 @@ void MarlinSettings::postprocess() { DEBUG_ERROR_START(); DEBUG_ECHOLNPAIR("EEPROM CRC mismatch - (stored) ", stored_crc, " != ", working_crc, " (calculated)!"); #if HAS_LCD_MENU && DISABLED(EEPROM_AUTO_INIT) - ui.set_status_P(GET_TEXT(MSG_ERR_EEPROM_CRC)); + LCD_MESSAGEPGM(MSG_ERR_EEPROM_CRC); #endif } else if (!validating) { diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 4018c7586c74..42c79fdd1988 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -542,22 +542,14 @@ volatile bool Temperature::raw_temps_ready = false; // Make sure heating is actually working #if WATCH_BED || WATCH_HOTENDS - if ( - #if WATCH_BED && WATCH_HOTENDS - true - #elif WATCH_HOTENDS - !isbed - #else - isbed - #endif - ) { - if (!heated) { // If not yet reached target... - if (current_temp > next_watch_temp) { // Over the watch temp? - next_watch_temp = current_temp + watch_temp_increase; // - set the next temp to watch for - temp_change_ms = ms + watch_temp_period * 1000UL; // - move the expiration timer up - if (current_temp > watch_temp_target) heated = true; // - Flag if target temperature reached + if (BOTH(WATCH_BED, WATCH_HOTENDS) || isbed == DISABLED(WATCH_HOTENDS)) { + if (!heated) { // If not yet reached target... + if (current_temp > next_watch_temp) { // Over the watch temp? + next_watch_temp = current_temp + watch_temp_increase; // - set the next temp to watch for + temp_change_ms = ms + watch_temp_period * 1000UL; // - move the expiration timer up + if (current_temp > watch_temp_target) heated = true; // - Flag if target temperature reached } - else if (ELAPSED(ms, temp_change_ms)) // Watch timer expired + else if (ELAPSED(ms, temp_change_ms)) // Watch timer expired _temp_error(heater, 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? From 62e8c2dd871f62d80122fe919d065ee3a3e5d520 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 1 Apr 2020 23:50:08 -0500 Subject: [PATCH 15/37] Fix up 'system' includes --- Marlin/src/HAL/ESP32/eeprom_impl.cpp | 2 +- Marlin/src/HAL/SAMD51/QSPIFlash.h | 2 +- Marlin/src/feature/digipot/digipot_mcp4018.cpp | 4 ++-- Marlin/src/feature/digipot/digipot_mcp4451.cpp | 2 +- Marlin/src/module/temperature.cpp | 2 +- 5 files changed, 6 insertions(+), 6 deletions(-) diff --git a/Marlin/src/HAL/ESP32/eeprom_impl.cpp b/Marlin/src/HAL/ESP32/eeprom_impl.cpp index dbfee14055c4..f36aabf28e3a 100644 --- a/Marlin/src/HAL/ESP32/eeprom_impl.cpp +++ b/Marlin/src/HAL/ESP32/eeprom_impl.cpp @@ -27,7 +27,7 @@ #if ENABLED(EEPROM_SETTINGS) && DISABLED(FLASH_EEPROM_EMULATION) #include "../shared/eeprom_api.h" -#include "EEPROM.h" +#include #define EEPROM_SIZE 4096 diff --git a/Marlin/src/HAL/SAMD51/QSPIFlash.h b/Marlin/src/HAL/SAMD51/QSPIFlash.h index 7f75286ebfc1..b6f22769ff60 100644 --- a/Marlin/src/HAL/SAMD51/QSPIFlash.h +++ b/Marlin/src/HAL/SAMD51/QSPIFlash.h @@ -29,7 +29,7 @@ #pragma once -#include "Adafruit_SPIFlashBase.h" +#include // This class extends Adafruit_SPIFlashBase by adding caching support. // diff --git a/Marlin/src/feature/digipot/digipot_mcp4018.cpp b/Marlin/src/feature/digipot/digipot_mcp4018.cpp index e8df4a475fee..ebfbee794ab5 100644 --- a/Marlin/src/feature/digipot/digipot_mcp4018.cpp +++ b/Marlin/src/feature/digipot/digipot_mcp4018.cpp @@ -24,8 +24,8 @@ #if BOTH(DIGIPOT_I2C, DIGIPOT_MCP4018) -#include "Stream.h" -#include "utility/twi.h" +#include +#include #include //https://github.com/stawel/SlowSoftI2CMaster // Settings for the I2C based DIGIPOT (MCP4018) based on WT150 diff --git a/Marlin/src/feature/digipot/digipot_mcp4451.cpp b/Marlin/src/feature/digipot/digipot_mcp4451.cpp index 1183c96aa515..79bb6eb3c28a 100644 --- a/Marlin/src/feature/digipot/digipot_mcp4451.cpp +++ b/Marlin/src/feature/digipot/digipot_mcp4451.cpp @@ -24,7 +24,7 @@ #if ENABLED(DIGIPOT_I2C) && DISABLED(DIGIPOT_MCP4018) -#include "Stream.h" +#include #include #if MB(MKS_SBASE) diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 42c79fdd1988..af2f1a10e8dd 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -37,7 +37,7 @@ #endif #if ENABLED(MAX6675_IS_MAX31865) - #include "Adafruit_MAX31865.h" + #include #ifndef MAX31865_CS_PIN #define MAX31865_CS_PIN MAX6675_SS_PIN // HW:49 SW:65 for example #endif From f263782f1b1fa981c292f6cdeea8e00bc6f73df3 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 1 Apr 2020 23:50:32 -0500 Subject: [PATCH 16/37] Fix ESP32 eeprom flag --- Marlin/src/HAL/ESP32/eeprom_impl.cpp | 4 ++-- Marlin/src/HAL/ESP32/inc/Conditionals_post.h | 6 +++--- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/Marlin/src/HAL/ESP32/eeprom_impl.cpp b/Marlin/src/HAL/ESP32/eeprom_impl.cpp index f36aabf28e3a..1c005ff3d4a3 100644 --- a/Marlin/src/HAL/ESP32/eeprom_impl.cpp +++ b/Marlin/src/HAL/ESP32/eeprom_impl.cpp @@ -24,7 +24,7 @@ #include "../../inc/MarlinConfig.h" -#if ENABLED(EEPROM_SETTINGS) && DISABLED(FLASH_EEPROM_EMULATION) +#if USE_WIRED_EEPROM #include "../shared/eeprom_api.h" #include @@ -59,5 +59,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t size_t PersistentStore::capacity() { return EEPROM_SIZE; } -#endif // EEPROM_SETTINGS +#endif // USE_WIRED_EEPROM #endif // ARDUINO_ARCH_ESP32 diff --git a/Marlin/src/HAL/ESP32/inc/Conditionals_post.h b/Marlin/src/HAL/ESP32/inc/Conditionals_post.h index 11603c9ef41d..8849c06e9355 100644 --- a/Marlin/src/HAL/ESP32/inc/Conditionals_post.h +++ b/Marlin/src/HAL/ESP32/inc/Conditionals_post.h @@ -21,7 +21,7 @@ */ #pragma once -// If no real EEPROM, Flash emulation, or SRAM emulation is available fall back to SD emulation -#if ENABLED(EEPROM_SETTINGS) && NONE(USE_WIRED_EEPROM, FLASH_EEPROM_EMULATION, SRAM_EEPROM_EMULATION) - #define SDCARD_EEPROM_EMULATION +#undef USE_WIRED_EEPROM +#if ENABLED(EEPROM_SETTINGS) && DISABLED(FLASH_EEPROM_EMULATION) + #define USE_WIRED_EEPROM 1 #endif From 9f86dde19525af511b07239c23d93d586a045122 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 2 Apr 2020 01:22:48 -0500 Subject: [PATCH 17/37] Clean up UI declarations, apply TERN_ --- Marlin/src/MarlinCore.cpp | 38 ++++++++++++++++++++------------------ Marlin/src/MarlinCore.h | 16 +++------------- Marlin/src/lcd/ultralcd.h | 23 +++++++++++++---------- 3 files changed, 36 insertions(+), 41 deletions(-) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 8130affe301c..3a6582bbb1e6 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -218,13 +218,8 @@ bool wait_for_heatup = true; KEEPALIVE_STATE(PAUSED_FOR_USER); wait_for_user = true; if (ms) ms += millis(); // expire time - while (wait_for_user && !(ms && ELAPSED(millis(), ms))) { - idle( - #if ENABLED(ADVANCED_PAUSE_FEATURE) - no_sleep - #endif - ); - } + while (wait_for_user && !(ms && ELAPSED(millis(), ms))) + idle(TERN_(ADVANCED_PAUSE_FEATURE, no_sleep)); wait_for_user = false; } @@ -647,52 +642,54 @@ inline void manage_inactivity(const bool ignore_stepper_queue=false) { /** * Standard idle routine keeps the machine alive */ -void idle( - #if ENABLED(ADVANCED_PAUSE_FEATURE) - bool no_stepper_sleep/*=false*/ - #endif -) { +void idle(TERN_(ADVANCED_PAUSE_FEATURE, bool no_stepper_sleep/*=false*/)) { + // Handle Power-Loss Recovery #if ENABLED(POWER_LOSS_RECOVERY) && PIN_EXISTS(POWER_LOSS) recovery.outage(); #endif + // Run StallGuard endstop checks #if ENABLED(SPI_ENDSTOPS) if (endstops.tmc_spi_homing.any - #if ENABLED(IMPROVE_HOMING_RELIABILITY) - && ELAPSED(millis(), sg_guard_period) - #endif - ) { - for (uint8_t i = 4; i--;) // Read SGT 4 times per idle loop + && TERN1(IMPROVE_HOMING_RELIABILITY, ELAPSED(millis(), sg_guard_period)) + ) LOOP_L_N(i, 4) // Read SGT 4 times per idle loop if (endstops.tmc_spi_homing_check()) break; - } #endif + // Max7219 heartbeat, animation, etc. #if ENABLED(MAX7219_DEBUG) max7219.idle_tasks(); #endif + // Read Buttons and Update the LCD ui.update(); + // Announce Host Keepalive state (if any) #if ENABLED(HOST_KEEPALIVE_FEATURE) gcode.host_keepalive(); #endif + // Core Marlin activities manage_inactivity( #if ENABLED(ADVANCED_PAUSE_FEATURE) no_stepper_sleep #endif ); + // Manage heaters (and Watchdog) thermalManager.manage_heater(); + // Update the Print Job Timer state #if ENABLED(PRINTCOUNTER) print_job_timer.tick(); #endif + // Update the Beeper queue #if USE_BEEPER buzzer.tick(); #endif + // Run i2c Position Encoders #if ENABLED(I2C_POSITION_ENCODERS) static millis_t i2cpem_next_update_ms; if (planner.has_blocks_queued()) { @@ -704,10 +701,12 @@ void idle( } #endif + // Run HAL idle tasks #ifdef HAL_IDLETASK HAL_idletask(); #endif + // Auto-report Temperatures / SD Status #if HAS_AUTO_REPORTING if (!gcode.autoreport_paused) { #if ENABLED(AUTO_REPORT_TEMPERATURES) @@ -719,14 +718,17 @@ void idle( } #endif + // Handle USB Flash Drive insert / remove #if ENABLED(USB_FLASH_DRIVE_SUPPORT) Sd2Card::idle(); #endif + // Update the Prusa MMU2 #if ENABLED(PRUSA_MMU2) mmu2.mmu_loop(); #endif + // Handle Joystick jogging #if ENABLED(POLL_JOG) joystick.inject_jog_moves(); #endif diff --git a/Marlin/src/MarlinCore.h b/Marlin/src/MarlinCore.h index e6678c5b1888..3f8b72b88a53 100644 --- a/Marlin/src/MarlinCore.h +++ b/Marlin/src/MarlinCore.h @@ -38,19 +38,9 @@ void stop(); -void idle( - #if ENABLED(ADVANCED_PAUSE_FEATURE) - bool no_stepper_sleep=false // Pass true to keep steppers from timing out - #endif -); - -inline void idle_no_sleep() { - idle( - #if ENABLED(ADVANCED_PAUSE_FEATURE) - true - #endif - ); -} +// Pass true to keep steppers from timing out +void idle(TERN_(ADVANCED_PAUSE_FEATURE, bool no_stepper_sleep=false)); +inline void idle_no_sleep() { idle(TERN_(ADVANCED_PAUSE_FEATURE, true)); } #if ENABLED(EXPERIMENTAL_I2CBUS) #include "feature/twibus.h" diff --git a/Marlin/src/lcd/ultralcd.h b/Marlin/src/lcd/ultralcd.h index 1bcf9956feee..2737a1a64883 100644 --- a/Marlin/src/lcd/ultralcd.h +++ b/Marlin/src/lcd/ultralcd.h @@ -273,7 +273,16 @@ class MarlinUI { // LCD implementations static void clear_lcd(); - static void init_lcd(); + + #if HAS_SPI_LCD + static bool detected(); + static void init_lcd(); + FORCE_INLINE static void refresh() { refresh(LCDVIEW_CLEAR_CALL_REDRAW); } + #else + static inline bool detected() { return true; } + static inline void init_lcd() {} + static inline void refresh() {} + #endif #if HAS_DISPLAY @@ -332,12 +341,9 @@ class MarlinUI { static millis_t next_button_update_ms; - static bool detected(); - static LCDViewAction lcdDrawUpdate; FORCE_INLINE static bool should_draw() { return bool(lcdDrawUpdate); } FORCE_INLINE static void refresh(const LCDViewAction type) { lcdDrawUpdate = type; } - FORCE_INLINE static void refresh() { refresh(LCDVIEW_CLEAR_CALL_REDRAW); } #if ENABLED(SHOW_CUSTOM_BOOTSCREEN) static void draw_custom_bootscreen(const uint8_t frame=0); @@ -403,8 +409,6 @@ class MarlinUI { static void status_screen(); - #else - static void refresh() {} #endif static bool get_blink(); @@ -418,13 +422,12 @@ class MarlinUI { #else // No LCD // Send status to host as a notification - void set_status(const char* message, const bool=false); - void set_status_P(PGM_P message, const int8_t=0); - void status_printf_P(const uint8_t, PGM_P message, ...); + static void set_status(const char* message, const bool=false); + static void set_status_P(PGM_P message, const int8_t=0); + static void status_printf_P(const uint8_t, PGM_P message, ...); static inline void init() {} static inline void update() {} - static inline void refresh() {} static inline void return_to_status() {} static inline void set_alert_status_P(PGM_P const) {} static inline void reset_status(const bool=false) {} From 11ce281694c08565e14023f379f72e4765738442 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 2 Apr 2020 13:32:49 -0500 Subject: [PATCH 18/37] Followup to #17351 --- Marlin/src/module/stepper/trinamic.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/module/stepper/trinamic.cpp b/Marlin/src/module/stepper/trinamic.cpp index f0ac48f51405..1440c24cf8b1 100644 --- a/Marlin/src/module/stepper/trinamic.cpp +++ b/Marlin/src/module/stepper/trinamic.cpp @@ -341,7 +341,7 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; ptr[a] = p; return false; }; } sp_helper; - #define HW_SERIAL_BEGIN(A) do{ if (sp_helper.began(TMCAxis::A, &A##_HARDWARE_SERIAL)) \ + #define HW_SERIAL_BEGIN(A) do{ if (!sp_helper.began(TMCAxis::A, &A##_HARDWARE_SERIAL)) \ A##_HARDWARE_SERIAL.begin(TMC_BAUD_RATE); }while(0) #if AXIS_HAS_UART(X) #ifdef X_HARDWARE_SERIAL From be0e313c078c7425de7bc45a0371756ee2571056 Mon Sep 17 00:00:00 2001 From: Marcio T Date: Thu, 2 Apr 2020 13:24:55 -0600 Subject: [PATCH 19/37] Touch UI additions, bug fixes (#17379) --- Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp | 4 + Marlin/src/feature/pause.cpp | 12 +- .../lib/ftdi_eve_touch_ui/marlin_events.cpp | 7 +- .../screens/bed_mesh_screen.cpp | 268 ++++++++++++++++++ .../ftdi_eve_touch_ui/screens/main_menu.cpp | 20 +- .../ftdi_eve_touch_ui/screens/screen_data.h | 6 + .../lib/ftdi_eve_touch_ui/screens/screens.cpp | 3 + .../lib/ftdi_eve_touch_ui/screens/screens.h | 30 ++ Marlin/src/lcd/extui/ui_api.cpp | 14 +- Marlin/src/lcd/extui/ui_api.h | 4 + Marlin/src/lcd/extui_dgus_lcd.cpp | 4 + Marlin/src/lcd/extui_example.cpp | 4 + Marlin/src/lcd/language/language_en.h | 6 +- 13 files changed, 364 insertions(+), 18 deletions(-) create mode 100644 Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bed_mesh_screen.cpp diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index 217d8945437f..940b4eaeb466 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -776,12 +776,16 @@ : find_closest_mesh_point_of_type(INVALID, near, true); if (best.pos.x >= 0) { // mesh point found and is reachable by probe + #if ENABLED(EXTENSIBLE_UI) + ExtUI::onMeshUpdate(best.pos, ExtUI::PROBE_START); + #endif const float measured_z = probe.probe_at_point( best.meshpos(), stow_probe ? PROBE_PT_STOW : PROBE_PT_RAISE, g29_verbose_level ); z_values[best.pos.x][best.pos.y] = measured_z; #if ENABLED(EXTENSIBLE_UI) + ExtUI::onMeshUpdate(best.pos, ExtUI::PROBE_FINISH); ExtUI::onMeshUpdate(best.pos, measured_z); #endif } diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index 9c615b6ff82f..23fa2fee0187 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -499,10 +499,10 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep // Wait for filament insert by user and press button KEEPALIVE_STATE(PAUSED_FOR_USER); #if ENABLED(HOST_PROMPT_SUPPORT) - host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Nozzle Parked"), CONTINUE_STR); + host_prompt_do(PROMPT_USER_CONTINUE, GET_TEXT(MSG_NOZZLE_PARKED), CONTINUE_STR); #endif #if ENABLED(EXTENSIBLE_UI) - ExtUI::onUserConfirmRequired_P(PSTR("Nozzle Parked")); + ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_NOZZLE_PARKED)); #endif wait_for_user = true; // LCD click or M108 will clear this while (wait_for_user) { @@ -523,20 +523,20 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep SERIAL_ECHO_MSG(_PMSG(STR_FILAMENT_CHANGE_HEAT)); #if ENABLED(HOST_PROMPT_SUPPORT) - host_prompt_do(PROMPT_USER_CONTINUE, PSTR("HeaterTimeout"), PSTR("Reheat")); + host_prompt_do(PROMPT_USER_CONTINUE, GET_TEXT(MSG_HEATER_TIMEOUT), GET_TEXT(MSG_REHEAT)); #endif #if ENABLED(EXTENSIBLE_UI) - ExtUI::onUserConfirmRequired_P(PSTR("HeaterTimeout")); + ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_HEATER_TIMEOUT)); #endif wait_for_user_response(0, true); // Wait for LCD click or M108 #if ENABLED(HOST_PROMPT_SUPPORT) - host_prompt_do(PROMPT_INFO, PSTR("Reheating")); + host_prompt_do(PROMPT_INFO, GET_TEXT(MSG_REHEATING)); #endif #if ENABLED(EXTENSIBLE_UI) - ExtUI::onStatusChanged(PSTR("Reheating...")); + ExtUI::onStatusChanged(GET_TEXT(MSG_REHEATING)); #endif // Re-enable the heaters if they timed out 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 bed32cc6064d..9271f2a0cda0 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 @@ -127,7 +127,12 @@ namespace ExtUI { } #if HAS_LEVELING && HAS_MESH - void onMeshUpdate(const int8_t, const int8_t, const float) { + void onMeshUpdate(const int8_t x, const int8_t y, const float val) { + BedMeshScreen::onMeshUpdate(x, y, val); + } + + void onMeshUpdate(const int8_t x, const int8_t y, const ExtUI::probe_state_t state) { + BedMeshScreen::onMeshUpdate(x, y, state); } #endif 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 new file mode 100644 index 000000000000..bce39a6ec0d4 --- /dev/null +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bed_mesh_screen.cpp @@ -0,0 +1,268 @@ +/*********************** + * bed_mesh_screen.cpp * + ***********************/ + +/**************************************************************************** + * Written By Marcio Teixeira 2020 * + * * + * 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 ENABLED(TOUCH_UI_FTDI_EVE) && HAS_MESH + +#include "screens.h" +#include "screen_data.h" + +using namespace FTDI; +using namespace Theme; +using namespace ExtUI; + +#ifdef TOUCH_UI_PORTRAIT + #define GRID_COLS 2 + #define GRID_ROWS 10 + + #define MESH_POS BTN_POS(1, 2), BTN_SIZE(2,5) + #define Z_LABEL_POS BTN_POS(1, 8), BTN_SIZE(1,1) + #define Z_VALUE_POS BTN_POS(2, 8), BTN_SIZE(1,1) + #define WAIT_POS BTN_POS(1, 8), BTN_SIZE(2,1) + #define BACK_POS BTN_POS(1,10), BTN_SIZE(2,1) +#else + #define GRID_COLS 5 + #define GRID_ROWS 5 + + #define MESH_POS BTN_POS(2,1), BTN_SIZE(4,5) + #define Z_LABEL_POS BTN_POS(1,3), BTN_SIZE(1,1) + #define Z_VALUE_POS BTN_POS(1,4), BTN_SIZE(2,1) + #define WAIT_POS BTN_POS(1,3), BTN_SIZE(2,2) + #define BACK_POS BTN_POS(1,5), BTN_SIZE(2,1) +#endif + +void BedMeshScreen::drawMesh(int16_t x, int16_t y, int16_t w, int16_t h, ExtUI::bed_mesh_t data, uint8_t opts) { + CommandProcessor cmd; + + #define TRANSFORM_2(X,Y,Z) (X), (Y) // No transform + #define TRANSFORM_1(X,Y,Z) TRANSFORM_2((X) + (Y) * slant, (Y) - (Z), 0) // Perspective + #define TRANSFORM(X,Y,Z) TRANSFORM_1(float(X)/(cols-1) - 0.5, float(Y)/(rows-1) - 0.5, (Z)) // Normalize + + constexpr uint8_t rows = GRID_MAX_POINTS_Y; + constexpr uint8_t cols = GRID_MAX_POINTS_X; + const float slant = 0.5; + const float bounds_min[] = {TRANSFORM(0 ,0 ,0)}; + const float bounds_max[] = {TRANSFORM(cols,rows,0)}; + const float scale_x = float(w)/(bounds_max[0] - bounds_min[0]); + const float scale_y = float(h)/(bounds_max[1] - bounds_min[1]); + const float center_x = x + w/2; + const float center_y = y + h/2; + + float val_mean = 0; + float val_max = -INFINITY; + float val_min = INFINITY; + uint8_t val_cnt = 0; + + if (opts & USE_AUTOSCALE) { + // Compute the mean + for (uint8_t y = 0; y < rows; y++) { + for (uint8_t x = 0; x < cols; x++) { + const float val = data[x][y]; + if (!isnan(val)) { + val_mean += val; + val_max = max(val_max, val); + val_min = min(val_min, val); + val_cnt++; + } + } + } + if (val_cnt) { + val_mean /= val_cnt; + val_min -= val_mean; + val_max -= val_mean; + } else { + val_mean = 0; + val_min = 0; + val_max = 0; + } + } + + const float scale_z = ((val_max == val_min) ? 1 : 1/(val_max - val_min)) * 0.1; + + #undef TRANSFORM_2 + #define TRANSFORM_2(X,Y,Z) center_x + (X) * scale_x, center_y + (Y) * scale_y // Scale and position + #define VALUE(X,Y) ((data && ISVAL(X,Y)) ? data[X][Y] : 0) + #define ISVAL(X,Y) (data ? !isnan(data[X][Y]) : true) + #define HEIGHT(X,Y) (VALUE(X,Y) * scale_z) + + uint16_t basePointSize = min(scale_x,scale_y) / max(cols,rows); + + cmd.cmd(SAVE_CONTEXT()) + .cmd(VERTEX_FORMAT(0)) + .cmd(TAG_MASK(false)) + .cmd(SAVE_CONTEXT()); + + for (uint8_t y = 0; y < rows; y++) { + for (uint8_t x = 0; x < cols; x++) { + if (ISVAL(x,y)) { + const bool hasLeftSegment = x < cols - 1 && ISVAL(x+1,y); + const bool hasRightSegment = y < rows - 1 && ISVAL(x,y+1); + if (hasLeftSegment || hasRightSegment) { + cmd.cmd(BEGIN(LINE_STRIP)); + if (hasLeftSegment) cmd.cmd(VERTEX2F(TRANSFORM(x + 1, y , HEIGHT(x + 1, y )))); + cmd.cmd( VERTEX2F(TRANSFORM(x , y , HEIGHT(x , y )))); + if (hasRightSegment) cmd.cmd(VERTEX2F(TRANSFORM(x , y + 1, HEIGHT(x , y + 1)))); + } + } + } + + if (opts & USE_POINTS) { + cmd.cmd(POINT_SIZE(basePointSize * 2)); + cmd.cmd(BEGIN(POINTS)); + for (uint8_t x = 0; x < cols; x++) { + if (ISVAL(x,y)) { + if (opts & USE_COLORS) { + const float val_dev = VALUE(x, y) - val_mean; + const uint8_t neg_byte = sq(val_dev) / sq(val_dev < 0 ? val_min : val_max) * 0xFF; + const uint8_t pos_byte = 255 - neg_byte; + cmd.cmd(COLOR_RGB(pos_byte, pos_byte, 0xFF)); + } + cmd.cmd(VERTEX2F(TRANSFORM(x, y, HEIGHT(x, y)))); + } + } + if (opts & USE_COLORS) { + cmd.cmd(RESTORE_CONTEXT()) + .cmd(SAVE_CONTEXT()); + } + } + } + cmd.cmd(RESTORE_CONTEXT()) + .cmd(TAG_MASK(true)); + + if (opts & USE_TAGS) { + cmd.cmd(COLOR_MASK(false, false, false, false)) + .cmd(POINT_SIZE(basePointSize * 10)) + .cmd(BEGIN(POINTS)); + for (uint8_t y = 0; y < rows; y++) { + for (uint8_t x = 0; x < cols; x++) { + const uint8_t tag = pointToTag(x, y); + cmd.tag(tag).cmd(VERTEX2F(TRANSFORM(x, y, HEIGHT(x, y)))); + } + } + cmd.cmd(COLOR_MASK(true, true, true, true)); + } + + if (opts & USE_HIGHLIGHT) { + const uint8_t tag = screen_data.BedMeshScreen.highlightedTag; + uint8_t x, y; + tagToPoint(tag, x, y); + cmd.cmd(COLOR_A(128)) + .cmd(POINT_SIZE(basePointSize * 6)) + .cmd(BEGIN(POINTS)) + .tag(tag).cmd(VERTEX2F(TRANSFORM(x, y, HEIGHT(x, y)))); + } + cmd.cmd(END()); + cmd.cmd(RESTORE_CONTEXT()); +} + +uint8_t BedMeshScreen::pointToTag(uint8_t x, uint8_t y) { + return y * (GRID_MAX_POINTS_X) + x + 10; +} + +void BedMeshScreen::tagToPoint(uint8_t tag, uint8_t &x, uint8_t &y) { + x = (tag - 10) % (GRID_MAX_POINTS_X); + y = (tag - 10) / (GRID_MAX_POINTS_X); +} + +void BedMeshScreen::onEntry() { + screen_data.BedMeshScreen.highlightedTag = 0; + screen_data.BedMeshScreen.count = 0; + BaseScreen::onEntry(); +} + +float BedMeshScreen::getHightlightedValue() { + if (screen_data.BedMeshScreen.highlightedTag) { + xy_uint8_t pt; + tagToPoint(screen_data.BedMeshScreen.highlightedTag, pt.x, pt.y); + return ExtUI::getMeshPoint(pt); + } + return NAN; +} + +void BedMeshScreen::drawHighlightedPointValue() { + char str[16]; + const float val = getHightlightedValue(); + const bool isGood = !isnan(val); + if (isGood) + dtostrf(val, 5, 3, str); + else + strcpy_P(str, PSTR("-")); + + CommandProcessor cmd; + cmd.font(Theme::font_medium) + .text(Z_LABEL_POS, GET_TEXT_F(MSG_MESH_EDIT_Z)) + .text(Z_VALUE_POS, str) + .colors(action_btn) + .tag(1).button( BACK_POS, GET_TEXT_F(MSG_BACK)) + .tag(0); +} + +void BedMeshScreen::onRedraw(draw_mode_t what) { + if (what & BACKGROUND) { + CommandProcessor cmd; + cmd.cmd(CLEAR_COLOR_RGB(bg_color)) + .cmd(CLEAR(true,true,true)); + + // Draw the shadow and tags + cmd.cmd(COLOR_RGB(0x444444)); + BedMeshScreen::drawMesh(MESH_POS, nullptr, USE_POINTS | USE_TAGS); + cmd.cmd(COLOR_RGB(bg_text_enabled)); + } + + if (what & FOREGROUND) { + const bool levelingFinished = screen_data.BedMeshScreen.count >= GRID_MAX_POINTS; + if (levelingFinished) drawHighlightedPointValue(); + + BedMeshScreen::drawMesh(MESH_POS, ExtUI::getMeshArray(), + USE_POINTS | USE_HIGHLIGHT | USE_AUTOSCALE | (levelingFinished ? USE_COLORS : 0)); + } +} + +bool BedMeshScreen::onTouchStart(uint8_t tag) { + screen_data.BedMeshScreen.highlightedTag = tag; + return true; +} + +bool BedMeshScreen::onTouchEnd(uint8_t tag) { + switch(tag) { + case 1: + GOTO_PREVIOUS(); + return true; + default: + return false; + } +} + +void BedMeshScreen::onMeshUpdate(const int8_t, const int8_t, const float) { + if (AT_SCREEN(BedMeshScreen)) + onRefresh(); +} + +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++; + } + BedMeshScreen::onMeshUpdate(x, y, 0); +} + +#endif // TOUCH_UI_FTDI_EVE 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 5d165edef0fa..5a81a4825705 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 @@ -146,14 +146,18 @@ bool MainMenu::onTouchEnd(uint8_t tag) { #ifdef AXIS_LEVELING_COMMANDS case 9: SpinnerDialogBox::enqueueAndWait_P(F(AXIS_LEVELING_COMMANDS)); break; #endif - #ifdef HAS_LEVELING - case 10: SpinnerDialogBox::enqueueAndWait_P(F( - #ifdef BED_LEVELING_COMMANDS - BED_LEVELING_COMMANDS - #else - "G29" - #endif - )); break; + #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; #endif case 11: GOTO_SCREEN(AboutScreen); break; default: 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 6e2cb97a984a..a0bc60d4884a 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 @@ -60,6 +60,12 @@ union screen_data_t { struct base_numeric_adjustment_t placeholder; float e_rel[ExtUI::extruderCount]; } MoveAxisScreen; +#if HAS_MESH + struct { + uint8_t count; + uint8_t highlightedTag; + } BedMeshScreen; +#endif #if ENABLED(TOUCH_UI_DEVELOPER_MENU) struct { uint32_t next_watchdog_trigger; 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 ce7546204021..5f59843bbe23 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,6 +55,9 @@ SCREEN_TABLE { #endif #if ENABLED(BABYSTEPPING) DECL_SCREEN(NudgeNozzleScreen), +#endif +#if HAS_MESH + DECL_SCREEN(BedMeshScreen), #endif DECL_SCREEN(MoveAxisScreen), DECL_SCREEN(StepsScreen), 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 346d122a0f25..8fa4800d6a8a 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 @@ -55,6 +55,9 @@ enum { MAX_VELOCITY_SCREEN_CACHE, MAX_ACCELERATION_SCREEN_CACHE, DEFAULT_ACCELERATION_SCREEN_CACHE, +#if HAS_MESH + BED_MESH_SCREEN_CACHE, +#endif #if DISABLED(CLASSIC_JERK) JUNC_DEV_SCREEN_CACHE, #else @@ -130,6 +133,33 @@ 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 void 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); + + 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: diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index 79e12f36d19c..a5b1460c90af 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -112,6 +112,9 @@ namespace ExtUI { #if ENABLED(JOYSTICK) uint8_t jogging : 1; #endif + #if ENABLED(SDSUPPORT) + uint8_t was_sd_printing : 1; + #endif } flags; #ifdef __SAM3X8E__ @@ -1032,11 +1035,18 @@ namespace ExtUI { } bool isPrintingFromMedia() { - return IFSD(card.isFileOpen(), false); + #if ENABLED(SDSUPPORT) + // Account for when IS_SD_PRINTING() reports the end of the + // print when there is still SD card data in the planner. + flags.was_sd_printing = card.isFileOpen() || (flags.was_sd_printing && commandsInQueue()); + return flags.was_sd_printing; + #else + return false; + #endif } bool isPrinting() { - return (planner.movesplanned() || isPrintingFromMedia() || IFSD(IS_SD_PRINTING(), false)); + return (commandsInQueue() || isPrintingFromMedia() || IFSD(IS_SD_PRINTING(), false)); } bool isMediaInserted() { diff --git a/Marlin/src/lcd/extui/ui_api.h b/Marlin/src/lcd/extui/ui_api.h index 01e0d1b7a384..43e337e87773 100644 --- a/Marlin/src/lcd/extui/ui_api.h +++ b/Marlin/src/lcd/extui/ui_api.h @@ -141,6 +141,10 @@ namespace ExtUI { void setMeshPoint(const xy_uint8_t &pos, const float zval); 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; + 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 #endif diff --git a/Marlin/src/lcd/extui_dgus_lcd.cpp b/Marlin/src/lcd/extui_dgus_lcd.cpp index 855d09033e85..8880be7ef38f 100644 --- a/Marlin/src/lcd/extui_dgus_lcd.cpp +++ b/Marlin/src/lcd/extui_dgus_lcd.cpp @@ -122,6 +122,10 @@ namespace ExtUI { // Called when any mesh points are updated } + void onMeshUpdate(const int8_t xpos, const int8_t ypos, const ExtUI::probe_state_t state) { + // Called to indicate a special condition + } + #if ENABLED(POWER_LOSS_RECOVERY) void onPowerLossResume() { // Called on resume from power-loss diff --git a/Marlin/src/lcd/extui_example.cpp b/Marlin/src/lcd/extui_example.cpp index 5c9a193ded3b..900afdea04e7 100644 --- a/Marlin/src/lcd/extui_example.cpp +++ b/Marlin/src/lcd/extui_example.cpp @@ -93,6 +93,10 @@ namespace ExtUI { // Called when any mesh points are updated } + void onMeshUpdate(const int8_t xpos, const int8_t ypos, const ExtUI::probe_state_t state) { + // Called to indicate a special condition + } + #if ENABLED(POWER_LOSS_RECOVERY) void onPowerLossResume() { // Called on resume from power-loss diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index a52d9652ac64..79a6f814b2ee 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -240,6 +240,8 @@ namespace Language_en { PROGMEM Language_Str MSG_BED_Z = _UxGT("Bed Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Nozzle"); PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Nozzle ~"); + PROGMEM Language_Str MSG_NOZZLE_PARKED = _UxGT("Nozzle Parked"); + PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Nozzle Standby"); PROGMEM Language_Str MSG_BED = _UxGT("Bed"); PROGMEM Language_Str MSG_CHAMBER = _UxGT("Enclosure"); PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Fan Speed"); @@ -371,7 +373,6 @@ namespace Language_en { PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Z Raise"); PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPD = _UxGT("Prime Speed"); PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPD = _UxGT("Retract Speed"); - PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Nozzle Standby"); PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Change Filament"); PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Change Filament *"); PROGMEM Language_Str MSG_FILAMENTLOAD = _UxGT("Load Filament"); @@ -605,6 +606,9 @@ namespace Language_en { PROGMEM Language_Str MSG_LEVEL_X_AXIS = _UxGT("Level X Axis"); PROGMEM Language_Str MSG_AUTO_CALIBRATE = _UxGT("Auto Calibrate"); + PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Heater Timeout"); + PROGMEM Language_Str MSG_REHEAT = _UxGT("Reheat"); + PROGMEM Language_Str MSG_REHEATING = _UxGT("Reheating..."); } #if FAN_COUNT == 1 From 2b9d2dce16dac5be0e489f2bc74be6555e245763 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 2 Apr 2020 14:32:49 -0500 Subject: [PATCH 20/37] Apply GRID_LOOP --- Marlin/src/feature/bedlevel/ubl/ubl.cpp | 15 +++++++------ Marlin/src/gcode/bedlevel/M420.cpp | 28 +++++++++++-------------- 2 files changed, 19 insertions(+), 24 deletions(-) diff --git a/Marlin/src/feature/bedlevel/ubl/ubl.cpp b/Marlin/src/feature/bedlevel/ubl/ubl.cpp index 8ef2ad564c06..cf8e935be97e 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl.cpp @@ -49,14 +49,13 @@ void unified_bed_leveling::report_current_mesh() { if (!leveling_is_valid()) return; SERIAL_ECHO_MSG(" G29 I99"); - LOOP_L_N(x, GRID_MAX_POINTS_X) - for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++) - if (!isnan(z_values[x][y])) { - SERIAL_ECHO_START(); - SERIAL_ECHOPAIR(" M421 I", int(x), " J", int(y)); - SERIAL_ECHOLNPAIR_F_P(SP_Z_STR, z_values[x][y], 4); - serial_delay(75); // Prevent Printrun from exploding - } + GRID_LOOP(x, y) + if (!isnan(z_values[x][y])) { + SERIAL_ECHO_START(); + SERIAL_ECHOPAIR(" M421 I", int(x), " J", int(y)); + SERIAL_ECHOLNPAIR_F_P(SP_Z_STR, z_values[x][y], 4); + serial_delay(75); // Prevent Printrun from exploding + } } void unified_bed_leveling::report_state() { diff --git a/Marlin/src/gcode/bedlevel/M420.cpp b/Marlin/src/gcode/bedlevel/M420.cpp index d042ace8da1f..ad2e01f09398 100644 --- a/Marlin/src/gcode/bedlevel/M420.cpp +++ b/Marlin/src/gcode/bedlevel/M420.cpp @@ -155,21 +155,18 @@ void GcodeSuite::M420() { // Get the sum and average of all mesh values float mesh_sum = 0; - for (uint8_t x = GRID_MAX_POINTS_X; x--;) - for (uint8_t y = GRID_MAX_POINTS_Y; y--;) - mesh_sum += Z_VALUES(x, y); + GRID_LOOP(x, y) mesh_sum += Z_VALUES(x, y); const float zmean = mesh_sum / float(GRID_MAX_POINTS); #else // Find the low and high mesh values float lo_val = 100, hi_val = -100; - for (uint8_t x = GRID_MAX_POINTS_X; x--;) - for (uint8_t y = GRID_MAX_POINTS_Y; y--;) { - const float z = Z_VALUES(x, y); - NOMORE(lo_val, z); - NOLESS(hi_val, z); - } + GRID_LOOP(x, y) { + const float z = Z_VALUES(x, y); + NOMORE(lo_val, z); + NOLESS(hi_val, z); + } // Take the mean of the lowest and highest const float zmean = (lo_val + hi_val) / 2.0 + cval; @@ -179,13 +176,12 @@ void GcodeSuite::M420() { if (!NEAR_ZERO(zmean)) { set_bed_leveling_enabled(false); // Subtract the mean from all values - for (uint8_t x = GRID_MAX_POINTS_X; x--;) - for (uint8_t y = GRID_MAX_POINTS_Y; y--;) { - Z_VALUES(x, y) -= zmean; - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMeshUpdate(x, y, Z_VALUES(x, y)); - #endif - } + GRID_LOOP(x, y) { + Z_VALUES(x, y) -= zmean; + #if ENABLED(EXTENSIBLE_UI) + ExtUI::onMeshUpdate(x, y, Z_VALUES(x, y)); + #endif + } #if ENABLED(ABL_BILINEAR_SUBDIVISION) bed_level_virt_interpolate(); #endif From e7e9304819f659cfd09d82597fc6ded871df405c Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 3 Apr 2020 00:03:31 +0000 Subject: [PATCH 21/37] [cron] Bump distribution date (2020-04-03) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 0316c69672e7..fce0c46b5c8a 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-04-02" + #define STRING_DISTRIBUTION_DATE "2020-04-03" #endif /** From df8b7dfc406be095a62b5445b69c40034d418823 Mon Sep 17 00:00:00 2001 From: Ben Date: Fri, 3 Apr 2020 01:31:08 +0100 Subject: [PATCH 22/37] Various Laser / Spindle improvements (#15335) --- Marlin/Configuration_adv.h | 122 ++++++++++++-- Marlin/src/HAL/AVR/HAL.h | 2 + Marlin/src/HAL/AVR/fast_pwm.cpp | 4 +- Marlin/src/HAL/LPC1768/HAL.h | 2 + Marlin/src/HAL/LPC1768/fast_pwm.cpp | 2 +- Marlin/src/MarlinCore.cpp | 22 ++- Marlin/src/core/drivers.h | 9 - Marlin/src/feature/spindle_laser.cpp | 49 +++--- Marlin/src/feature/spindle_laser.h | 143 ++++++++++++---- Marlin/src/feature/spindle_laser_types.h | 50 ++++++ Marlin/src/gcode/control/M3-M5.cpp | 41 ++++- Marlin/src/gcode/gcode.cpp | 16 ++ Marlin/src/gcode/motion/G0_G1.cpp | 2 +- Marlin/src/gcode/motion/G2_G3.cpp | 2 +- Marlin/src/inc/Conditionals_adv.h | 32 +++- Marlin/src/inc/Conditionals_post.h | 48 +++--- Marlin/src/inc/SanityCheck.h | 51 +++++- Marlin/src/lcd/dogm/status_screen_DOGM.cpp | 8 +- Marlin/src/lcd/language/language_en.h | 3 +- Marlin/src/lcd/menu/menu_spindle_laser.cpp | 21 ++- Marlin/src/module/planner.cpp | 54 +++++- Marlin/src/module/planner.h | 46 ++++- Marlin/src/module/stepper.cpp | 186 ++++++++++++++++++--- Marlin/src/module/stepper.h | 28 +++- 24 files changed, 775 insertions(+), 168 deletions(-) create mode 100644 Marlin/src/feature/spindle_laser_types.h diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 00f89662c785..7d1547c0d027 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -2662,31 +2662,123 @@ #define SPINDLE_LASER_ACTIVE_HIGH false // Set to "true" if the on/off function is active HIGH #define SPINDLE_LASER_PWM true // Set to "true" if your controller supports setting the speed/power #define SPINDLE_LASER_PWM_INVERT true // Set to "true" if the speed/power goes up when you want it to go slower - #define SPINDLE_LASER_POWERUP_DELAY 5000 // (ms) Delay to allow the spindle/laser to come up to speed/power - #define SPINDLE_LASER_POWERDOWN_DELAY 5000 // (ms) Delay to allow the spindle to stop + + #define SPINDLE_LASER_FREQUENCY 2500 // (Hz) Spindle/laser frequency (only on supported HALs: AVR and LPC) + + /** + * Speed / Power can be set ('M3 S') and displayed in terms of: + * - PWM (S0 - S255) + * - PERCENT (S0 - S100) + * - RPM (S0 - S50000) Best for use with a spindle + */ + #define CUTTER_POWER_DISPLAY PWM + + /** + * Relative mode uses relative range (SPEED_POWER_MIN to SPEED_POWER_MAX) instead of normal range (0 to SPEED_POWER_MAX) + * Best use with SuperPID router controller where for example S0 = 5,000 RPM and S255 = 30,000 RPM + */ + //#define CUTTER_POWER_RELATIVE // Set speed proportional to [SPEED_POWER_MIN...SPEED_POWER_MAX] instead of directly #if ENABLED(SPINDLE_FEATURE) //#define SPINDLE_CHANGE_DIR // Enable if your spindle controller can change spindle direction #define SPINDLE_CHANGE_DIR_STOP // Enable if the spindle should stop before changing spin direction #define SPINDLE_INVERT_DIR false // Set to "true" if the spin direction is reversed + #define SPINDLE_LASER_POWERUP_DELAY 5000 // (ms) Delay to allow the spindle/laser to come up to speed/power + #define SPINDLE_LASER_POWERDOWN_DELAY 5000 // (ms) Delay to allow the spindle to stop + /** - * The M3 & M4 commands use the following equation to convert PWM duty cycle to speed/power + * M3/M4 uses the following equation to convert speed/power to PWM duty cycle + * Power = ((DC / 255 * 100) - SPEED_POWER_INTERCEPT)) * (1 / SPEED_POWER_SLOPE) + * where PWM DC varies from 0 to 255 * - * SPEED/POWER = PWM duty cycle * SPEED_POWER_SLOPE + SPEED_POWER_INTERCEPT - * where PWM duty cycle varies from 0 to 255 - * - * set the following for your controller (ALL MUST BE SET) + * Set these required parameters for your controller */ - #define SPEED_POWER_SLOPE 118.4 - #define SPEED_POWER_INTERCEPT 0 - #define SPEED_POWER_MIN 5000 - #define SPEED_POWER_MAX 30000 // SuperPID router controller 0 - 30,000 RPM + #define SPEED_POWER_SLOPE 118.4 // SPEED_POWER_SLOPE = SPEED_POWER_MAX / 255 + #define SPEED_POWER_INTERCEPT 0 + #define SPEED_POWER_MIN 5000 + #define SPEED_POWER_MAX 30000 // SuperPID router controller 0 - 30,000 RPM + #define SPEED_POWER_STARTUP 25000 // The default value for speed power when M3 is called without arguments + #else - #define SPEED_POWER_SLOPE 0.3922 - #define SPEED_POWER_INTERCEPT 0 - #define SPEED_POWER_MIN 10 - #define SPEED_POWER_MAX 100 // 0-100% + + #define SPEED_POWER_SLOPE 0.3922 // SPEED_POWER_SLOPE = SPEED_POWER_MAX / 255 + #define SPEED_POWER_INTERCEPT 0 + #define SPEED_POWER_MIN 0 + #define SPEED_POWER_MAX 100 // 0-100% + #define SPEED_POWER_STARTUP 80 // The default value for speed power when M3 is called without arguments + + /** + * Enable inline laser power to be handled in the planner / stepper routines. + * Inline power is specified by the I (inline) flag in an M3 command (e.g., M3 S20 I) + * or by the 'S' parameter in G0/G1/G2/G3 moves (see LASER_MOVE_POWER). + * + * This allows the laser to keep in perfect sync with the planner and removes + * the powerup/down delay since lasers require negligible time. + */ + #define LASER_POWER_INLINE + + #if ENABLED(LASER_POWER_INLINE) + /** + * Scale the laser's power in proportion to the movement rate. + * + * - Sets the entry power proportional to the entry speed over the nominal speed. + * - Ramps the power up every N steps to approximate the speed trapezoid. + * - Due to the limited power resolution this is only approximate. + */ + #define LASER_POWER_INLINE_TRAPEZOID + + /** + * Continuously calculate the current power (nominal_power * current_rate / nominal_rate). + * Required for accurate power with non-trapezoidal acceleration (e.g., S_CURVE_ACCELERATION). + * This is a costly calculation so this option is discouraged on 8-bit AVR boards. + * + * LASER_POWER_INLINE_TRAPEZOID_CONT_PER defines how many step cycles there are between power updates. If your + * board isn't able to generate steps fast enough (and you are using LASER_POWER_INLINE_TRAPEZOID_CONT), increase this. + * Note that when this is zero it means it occurs every cycle; 1 means a delay wait one cycle then run, etc. + */ + //#define LASER_POWER_INLINE_TRAPEZOID_CONT + + /** + * Stepper iterations between power updates. Increase this value if the board + * can't keep up with the processing demands of LASER_POWER_INLINE_TRAPEZOID_CONT. + * Disable (or set to 0) to recalculate power on every stepper iteration. + */ + //#define LASER_POWER_INLINE_TRAPEZOID_CONT_PER 10 + + /** + * Include laser power in G0/G1/G2/G3/G5 commands with the 'S' parameter + */ + //#define LASER_MOVE_POWER + + #if ENABLED(LASER_MOVE_POWER) + // Turn off the laser on G0 moves with no power parameter. + // If a power parameter is provided, use that instead. + //#define LASER_MOVE_G0_OFF + #endif + + /** + * Inline flag inverted + * + * WARNING: M5 will NOT turn off the laser unless another move + * is done (so G-code files must end with 'M5 I'). + */ + //#define LASER_POWER_INLINE_INVERT + + /** + * Continuously apply inline power. ('M3 S3' == 'G1 S3' == 'M3 S3 I') + * + * The laser might do some weird things, so only enable this + * feature if you understand the implications. + */ + //#define LASER_POWER_INLINE_CONTINUOUS + + #else + + #define SPINDLE_LASER_POWERUP_DELAY 50 // (ms) Delay to allow the spindle/laser to come up to speed/power + #define SPINDLE_LASER_POWERDOWN_DELAY 50 // (ms) Delay to allow the spindle to stop + + #endif #endif #endif diff --git a/Marlin/src/HAL/AVR/HAL.h b/Marlin/src/HAL/AVR/HAL.h index 025516981955..f715295d0ad9 100644 --- a/Marlin/src/HAL/AVR/HAL.h +++ b/Marlin/src/HAL/AVR/HAL.h @@ -395,6 +395,8 @@ inline void HAL_adc_init() { // AVR compatibility #define strtof strtod +#define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment + /** * set_pwm_frequency * Sets the frequency of the timer corresponding to the provided pin diff --git a/Marlin/src/HAL/AVR/fast_pwm.cpp b/Marlin/src/HAL/AVR/fast_pwm.cpp index 42e7cc3f107e..e85505748649 100644 --- a/Marlin/src/HAL/AVR/fast_pwm.cpp +++ b/Marlin/src/HAL/AVR/fast_pwm.cpp @@ -23,7 +23,7 @@ #include "../../inc/MarlinConfigPre.h" -#if ENABLED(FAST_PWM_FAN) || SPINDLE_LASER_PWM +#if NEEDS_HARDWARE_PWM // Specific meta-flag for features that mandate PWM #include "HAL.h" @@ -278,5 +278,5 @@ void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255 } } -#endif // FAST_PWM_FAN || SPINDLE_LASER_PWM +#endif // NEEDS_HARDWARE_PWM #endif // __AVR__ diff --git a/Marlin/src/HAL/LPC1768/HAL.h b/Marlin/src/HAL/LPC1768/HAL.h index f5ea629f1694..70bb50e6920f 100644 --- a/Marlin/src/HAL/LPC1768/HAL.h +++ b/Marlin/src/HAL/LPC1768/HAL.h @@ -197,6 +197,8 @@ void HAL_idletask(); #define PLATFORM_M997_SUPPORT void flashFirmware(const int16_t); +#define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment + /** * set_pwm_frequency * Set the frequency of the timer corresponding to the provided pin diff --git a/Marlin/src/HAL/LPC1768/fast_pwm.cpp b/Marlin/src/HAL/LPC1768/fast_pwm.cpp index a1feb2590324..4f2e30ee725c 100644 --- a/Marlin/src/HAL/LPC1768/fast_pwm.cpp +++ b/Marlin/src/HAL/LPC1768/fast_pwm.cpp @@ -24,7 +24,7 @@ #include "../../inc/MarlinConfigPre.h" -#if ENABLED(FAST_PWM_FAN) || SPINDLE_LASER_PWM +#if NEEDS_HARDWARE_PWM // Specific meta-flag for features that mandate PWM #include diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 3a6582bbb1e6..5073c339cd1a 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -420,7 +420,11 @@ void startOrResumeJob() { #if DISABLED(SD_ABORT_NO_COOLDOWN) thermalManager.disable_all_heaters(); #endif - thermalManager.zero_fan_speeds(); + #if !HAS_CUTTER + thermalManager.zero_fan_speeds(); + #else + cutter.kill(); // Full cutter shutdown including ISR control + #endif wait_for_heatup = false; #if ENABLED(POWER_LOSS_RECOVERY) recovery.purge(); @@ -741,6 +745,10 @@ void idle(TERN_(ADVANCED_PAUSE_FEATURE, bool no_stepper_sleep/*=false*/)) { void kill(PGM_P const lcd_error/*=nullptr*/, PGM_P const lcd_component/*=nullptr*/, const bool steppers_off/*=false*/) { thermalManager.disable_all_heaters(); + #if HAS_CUTTER + cutter.kill(); // Full cutter shutdown including ISR control + #endif + SERIAL_ERROR_MSG(STR_ERR_KILLED); #if HAS_DISPLAY @@ -770,6 +778,10 @@ void minkill(const bool steppers_off/*=false*/) { // Reiterate heaters off thermalManager.disable_all_heaters(); + #if HAS_CUTTER + cutter.kill(); // Reiterate cutter shutdown + #endif + // Power off all steppers (for M112) or just the E steppers steppers_off ? disable_all_steppers() : disable_e_steppers(); @@ -789,14 +801,14 @@ void minkill(const bool steppers_off/*=false*/) { // Wait for kill to be pressed while (READ(KILL_PIN)) watchdog_refresh(); - void (*resetFunc)() = 0; // Declare resetFunc() at address 0 + void (*resetFunc)() = 0; // Declare resetFunc() at address 0 resetFunc(); // Jump to address 0 - #else // !HAS_KILL + #else - for (;;) watchdog_refresh(); // Wait for reset + for (;;) watchdog_refresh(); // Wait for reset - #endif // !HAS_KILL + #endif } /** diff --git a/Marlin/src/core/drivers.h b/Marlin/src/core/drivers.h index 833899bdcbc1..418a24ec925d 100644 --- a/Marlin/src/core/drivers.h +++ b/Marlin/src/core/drivers.h @@ -174,15 +174,6 @@ // Defines that can't be evaluated now #define HAS_TMC_SW_SERIAL ANY_AXIS_HAS(SW_SERIAL) -// -// Stretching 'drivers.h' to include LPC/SAMD51 SD options -// -#define _SDCARD_LCD 1 -#define _SDCARD_ONBOARD 2 -#define _SDCARD_CUSTOM_CABLE 3 -#define _SDCARD_ID(V) _CAT(_SDCARD_, V) -#define SD_CONNECTION_IS(V) (_SDCARD_ID(SDCARD_CONNECTION) == _SDCARD_ID(V)) - #if HAS_DRIVER(L6470) || HAS_DRIVER(L6474) || HAS_DRIVER(L6480) || HAS_DRIVER(POWERSTEP01) #define HAS_L64XX 1 #endif diff --git a/Marlin/src/feature/spindle_laser.cpp b/Marlin/src/feature/spindle_laser.cpp index 0567ba5d3e2f..63c98911099a 100644 --- a/Marlin/src/feature/spindle_laser.cpp +++ b/Marlin/src/feature/spindle_laser.cpp @@ -32,10 +32,17 @@ SpindleLaser cutter; -cutter_power_t SpindleLaser::power; // = 0 - +cutter_power_t SpindleLaser::power; +bool SpindleLaser::isOn; // state to determine when to apply setPower to power +cutter_setPower_t SpindleLaser::setPower = interpret_power(SPEED_POWER_MIN); // spindle/laser speed/power control in PWM, Percentage or RPM +#if ENABLED(MARLIN_DEV_MODE) + cutter_frequency_t SpindleLaser::frequency; // setting PWM frequency; range: 2K - 50K +#endif #define SPINDLE_LASER_PWM_OFF ((SPINDLE_LASER_PWM_INVERT) ? 255 : 0) +// +// Init the cutter to a safe OFF state +// void SpindleLaser::init() { OUT_WRITE(SPINDLE_LASER_ENA_PIN, !SPINDLE_LASER_ACTIVE_HIGH); // Init spindle to off #if ENABLED(SPINDLE_CHANGE_DIR) @@ -45,41 +52,39 @@ void SpindleLaser::init() { SET_PWM(SPINDLE_LASER_PWM_PIN); analogWrite(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_PWM_OFF); // set to lowest speed #endif + #if ENABLED(HAL_CAN_SET_PWM_FREQ) && defined(SPINDLE_LASER_FREQUENCY) + set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_FREQUENCY); + #if ENABLED(MARLIN_DEV_MODE) + frequency = SPINDLE_LASER_FREQUENCY; + #endif + #endif } #if ENABLED(SPINDLE_LASER_PWM) /** - * ocr_val_mode() is used for debugging and to get the points needed to compute the RPM vs ocr_val line - * - * it accepts inputs of 0-255 - */ + * Set the cutter PWM directly to the given ocr value + **/ void SpindleLaser::set_ocr(const uint8_t ocr) { - WRITE(SPINDLE_LASER_ENA_PIN, SPINDLE_LASER_ACTIVE_HIGH); // turn spindle on (active low) + WRITE(SPINDLE_LASER_ENA_PIN, SPINDLE_LASER_ACTIVE_HIGH); // turn spindle on analogWrite(pin_t(SPINDLE_LASER_PWM_PIN), ocr ^ SPINDLE_LASER_PWM_OFF); } #endif +// +// Set cutter ON state (and PWM) to the given cutter power value +// void SpindleLaser::apply_power(const cutter_power_t inpow) { static cutter_power_t last_power_applied = 0; if (inpow == last_power_applied) return; last_power_applied = inpow; #if ENABLED(SPINDLE_LASER_PWM) - if (enabled()) { - #define _scaled(F) ((F - (SPEED_POWER_INTERCEPT)) * inv_slope) - constexpr float inv_slope = RECIPROCAL(SPEED_POWER_SLOPE), - min_ocr = _scaled(SPEED_POWER_MIN), - max_ocr = _scaled(SPEED_POWER_MAX); - int16_t ocr_val; - if (inpow <= SPEED_POWER_MIN) ocr_val = min_ocr; // Use minimum if set below - else if (inpow >= SPEED_POWER_MAX) ocr_val = max_ocr; // Use maximum if set above - else ocr_val = _scaled(inpow); // Use calculated OCR value - set_ocr(ocr_val & 0xFF); // ...limited to Atmel PWM max - } + if (enabled()) + set_ocr(translate_power(inpow)); else { - WRITE(SPINDLE_LASER_ENA_PIN, !SPINDLE_LASER_ACTIVE_HIGH); // Turn spindle off (active low) - analogWrite(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_PWM_OFF); // Only write low byte + WRITE(SPINDLE_LASER_ENA_PIN, !SPINDLE_LASER_ACTIVE_HIGH); // Turn spindle off + analogWrite(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_PWM_OFF); // Only write low byte } #else WRITE(SPINDLE_LASER_ENA_PIN, (SPINDLE_LASER_ACTIVE_HIGH) ? enabled() : !enabled()); @@ -88,6 +93,10 @@ void SpindleLaser::apply_power(const cutter_power_t inpow) { #if ENABLED(SPINDLE_CHANGE_DIR) + // + // Set the spindle direction and apply immediately + // Stop on direction change if SPINDLE_STOP_ON_DIR_CHANGE is enabled + // void SpindleLaser::set_direction(const bool reverse) { const bool dir_state = (reverse == SPINDLE_INVERT_DIR); // Forward (M3) HIGH when not inverted #if ENABLED(SPINDLE_STOP_ON_DIR_CHANGE) diff --git a/Marlin/src/feature/spindle_laser.h b/Marlin/src/feature/spindle_laser.h index ea035299be3e..3d7ab6c360b4 100644 --- a/Marlin/src/feature/spindle_laser.h +++ b/Marlin/src/feature/spindle_laser.h @@ -28,55 +28,98 @@ #include "../inc/MarlinConfig.h" -#if ENABLED(SPINDLE_FEATURE) - #define _MSG_CUTTER(M) MSG_SPINDLE_##M -#else - #define _MSG_CUTTER(M) MSG_LASER_##M -#endif -#define MSG_CUTTER(M) _MSG_CUTTER(M) - -#if SPEED_POWER_MAX > 255 - typedef uint16_t cutter_power_t; - #define CUTTER_MENU_TYPE uint16_5 -#else - typedef uint8_t cutter_power_t; - #define CUTTER_MENU_TYPE uint8 +#include "spindle_laser_types.h" + +#if ENABLED(LASER_POWER_INLINE) + #include "../module/planner.h" #endif class SpindleLaser { public: + static bool isOn; // state to determine when to apply setPower to power static cutter_power_t power; - static inline uint8_t powerPercent(const uint8_t pp) { return ui8_to_percent(pp); } // for display - - static void init(); - - static inline bool enabled() { return !!power; } + static cutter_setPower_t setPower; // spindle/laser menu set power; in PWM, Percentage or RPM + #if ENABLED(MARLIN_DEV_MODE) + static cutter_frequency_t frequency; // set PWM frequency; range: 2K-50K + #endif - static inline void set_power(const cutter_power_t pwr) { power = pwr; } + static cutter_setPower_t interpret_power(const float pwr) { // convert speed/power to configured PWM, Percentage or RPM in relative or normal range + #if CUTTER_DISPLAY_IS(PERCENT) + return (pwr / SPEED_POWER_MAX) * 100; // to percent + #elif CUTTER_DISPLAY_IS(RPM) // to RPM is unaltered + return pwr; + #else // to PWM + #if ENABLED(CUTTER_POWER_RELATIVE) + return (pwr - SPEED_POWER_MIN) / (SPEED_POWER_MAX - SPEED_POWER_MIN) * 255; // using rpm range as relative percentage + #else + return (pwr / SPEED_POWER_MAX) * 255; + #endif + #endif + } + /** + * Translate speed/power --> percentage --> PWM value + **/ + static cutter_power_t translate_power(const float pwr) { + float pwrpc; + #if CUTTER_DISPLAY_IS(PERCENT) + pwrpc = pwr; + #elif CUTTER_DISPLAY_IS(RPM) // RPM to percent + #if ENABLED(CUTTER_POWER_RELATIVE) + pwrpc = (pwr - SPEED_POWER_MIN) / (SPEED_POWER_MAX - SPEED_POWER_MIN) * 100; + #else + pwrpc = pwr / SPEED_POWER_MAX * 100; + #endif + #else + return pwr; // PWM + #endif - static inline void refresh() { apply_power(power); } + #if ENABLED(SPINDLE_FEATURE) + #if ENABLED(CUTTER_POWER_RELATIVE) + constexpr float spmin = 0; + #else + constexpr float spmin = SPEED_POWER_MIN / SPEED_POWER_MAX * 100; // convert to percentage + #endif + constexpr float spmax = 100; + #else + constexpr float spmin = SPEED_POWER_MIN; + constexpr float spmax = SPEED_POWER_MAX; + #endif - static inline void set_enabled(const bool enable) { - const bool was = enabled(); - set_power(enable ? 255 : 0); - if (was != enable) power_delay(); + constexpr float inv_slope = RECIPROCAL(SPEED_POWER_SLOPE), + min_ocr = (spmin - (SPEED_POWER_INTERCEPT)) * inv_slope, // Minimum allowed + max_ocr = (spmax - (SPEED_POWER_INTERCEPT)) * inv_slope; // Maximum allowed + float ocr_val; + if (pwrpc < spmin) ocr_val = min_ocr; // Use minimum if set below + else if (pwrpc > spmax) ocr_val = max_ocr; // Use maximum if set above + else ocr_val = (pwrpc - (SPEED_POWER_INTERCEPT)) * inv_slope; // Use calculated OCR value + return ocr_val; // ...limited to Atmel PWM max } + static void init(); + + // Modifying this function should update everywhere + static inline bool enabled(const cutter_power_t pwr) { return pwr > 0; } + static inline bool enabled() { return enabled(power); } + #if ENABLED(MARLIN_DEV_MODE) + static inline void refresh_frequency() { set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), frequency); } + #endif static void apply_power(const cutter_power_t inpow); - //static bool active() { return READ(SPINDLE_LASER_ENA_PIN) == SPINDLE_LASER_ACTIVE_HIGH; } + FORCE_INLINE static void refresh() { apply_power(power); } + FORCE_INLINE static void set_power(const cutter_power_t pwr) { power = pwr; refresh(); } - static void update_output(); + static inline void set_enabled(const bool enable) { set_power(enable ? (power ?: interpret_power(SPEED_POWER_STARTUP)) : 0); } #if ENABLED(SPINDLE_LASER_PWM) static void set_ocr(const uint8_t ocr); - static inline void set_ocr_power(const cutter_power_t pwr) { power = pwr; set_ocr(pwr); } + static inline void set_ocr_power(const uint8_t pwr) { power = pwr; set_ocr(pwr); } + // static uint8_t translate_power(const cutter_power_t pwr); // Used by update output for power->OCR translation #endif // Wait for spindle to spin up or spin down - static inline void power_delay() { - #if SPINDLE_LASER_POWERUP_DELAY || SPINDLE_LASER_POWERDOWN_DELAY - safe_delay(enabled() ? SPINDLE_LASER_POWERUP_DELAY : SPINDLE_LASER_POWERDOWN_DELAY); + static inline void power_delay(const bool on) { + #if DISABLED(LASER_POWER_INLINE) + safe_delay(on ? SPINDLE_LASER_POWERUP_DELAY : SPINDLE_LASER_POWERDOWN_DELAY); #endif } @@ -86,10 +129,44 @@ class SpindleLaser { static inline void set_direction(const bool) {} #endif - static inline void disable() { set_enabled(false); } - static inline void enable_forward() { set_direction(false); set_enabled(true); } - static inline void enable_reverse() { set_direction(true); set_enabled(true); } + static inline void disable() { isOn = false; set_enabled(false); } + #if HAS_LCD_MENU + static inline void enable_forward() { isOn = true; setPower ? (power = setPower) : (setPower = interpret_power(SPEED_POWER_STARTUP)); set_direction(false); set_enabled(true); } + static inline void enable_reverse() { isOn = true; setPower ? (power = setPower) : (setPower = interpret_power(SPEED_POWER_STARTUP)); set_direction(true); set_enabled(true); } + #endif + #if ENABLED(LASER_POWER_INLINE) + // Force disengage planner power control + static inline void inline_disable() { planner.settings.laser.status = 0; planner.settings.laser.power = 0; isOn = false;} + + // Inline modes of all other functions; all enable planner inline power control + static inline void inline_enabled(const bool enable) { enable ? inline_power(SPEED_POWER_STARTUP) : inline_ocr_power(0); } + + static void inline_power(const cutter_power_t pwr) { + #if ENABLED(SPINDLE_LASER_PWM) + inline_ocr_power(translate_power(pwr)); + #else + planner.settings.laser.status = enabled(pwr) ? 0x03 : 0x01; + planner.settings.laser.power = pwr; + #endif + } + + static inline void inline_direction(const bool reverse) { UNUSED(reverse); } // TODO is this ever going to be needed + + #if ENABLED(SPINDLE_LASER_PWM) + static inline void inline_ocr_power(const uint8_t pwr) { + planner.settings.laser.status = pwr ? 0x03 : 0x01; + planner.settings.laser.power = pwr; + } + #endif + #endif + + static inline void kill() { + #if ENABLED(LASER_POWER_INLINE) + inline_disable(); + #endif + disable(); + } }; extern SpindleLaser cutter; diff --git a/Marlin/src/feature/spindle_laser_types.h b/Marlin/src/feature/spindle_laser_types.h new file mode 100644 index 000000000000..9e3f2bae48a8 --- /dev/null +++ b/Marlin/src/feature/spindle_laser_types.h @@ -0,0 +1,50 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * feature/spindle_laser_types.h + * Support for Laser Power or Spindle Power & Direction + */ + +#include "../inc/MarlinConfigPre.h" + +#if ENABLED(SPINDLE_FEATURE) + #define _MSG_CUTTER(M) MSG_SPINDLE_##M +#else + #define _MSG_CUTTER(M) MSG_LASER_##M +#endif +#define MSG_CUTTER(M) _MSG_CUTTER(M) +#if CUTTER_DISPLAY_IS(RPM) && SPEED_POWER_MAX > 255 + #define cutter_power_t uint16_t + #define cutter_setPower_t uint16_t + #define CUTTER_MENU_POWER_TYPE uint16_5 +#else + #define cutter_power_t uint8_t + #define cutter_setPower_t uint8_t + #define CUTTER_MENU_POWER_TYPE uint8 +#endif + +#if ENABLED(MARLIN_DEV_MODE) + #define cutter_frequency_t uint16_t + #define CUTTER_MENU_FREQUENCY_TYPE uint16_5 +#endif diff --git a/Marlin/src/gcode/control/M3-M5.cpp b/Marlin/src/gcode/control/M3-M5.cpp index 56e1e0e4ec9d..9c897abf01ae 100644 --- a/Marlin/src/gcode/control/M3-M5.cpp +++ b/Marlin/src/gcode/control/M3-M5.cpp @@ -28,6 +28,12 @@ #include "../../feature/spindle_laser.h" #include "../../module/stepper.h" +inline cutter_power_t get_s_power() { + return cutter_power_t( + parser.intval('S', cutter.interpret_power(SPEED_POWER_STARTUP)) + ); +} + /** * Laser: * @@ -71,29 +77,52 @@ */ void GcodeSuite::M3_M4(const bool is_M4) { - #if ENABLED(SPINDLE_FEATURE) - planner.synchronize(); // Wait for movement to complete before changing power + #if ENABLED(LASER_POWER_INLINE) + if (parser.seen('I') == DISABLED(LASER_POWER_INLINE_INVERT)) { + // Laser power in inline mode + cutter.inline_direction(is_M4); // Should always be unused + + #if ENABLED(SPINDLE_LASER_PWM) + if (parser.seen('O')) + cutter.inline_ocr_power(parser.value_byte()); // The OCR is a value from 0 to 255 (uint8_t) + else + cutter.inline_power(get_s_power()); + #else + cutter.inline_enabled(true); + #endif + return; + } + // Non-inline, standard case + cutter.inline_disable(); // Prevent future blocks re-setting the power #endif + planner.synchronize(); // Wait for previous movement commands (G0/G0/G2/G3) to complete before changing power + cutter.set_direction(is_M4); #if ENABLED(SPINDLE_LASER_PWM) if (parser.seenval('O')) cutter.set_ocr_power(parser.value_byte()); // The OCR is a value from 0 to 255 (uint8_t) else - cutter.set_power(parser.intval('S', 255)); + cutter.set_power(get_s_power()); #else cutter.set_enabled(true); #endif } /** - * M5 - Cutter OFF + * M5 - Cutter OFF (when moves are complete) */ void GcodeSuite::M5() { - #if ENABLED(SPINDLE_FEATURE) - planner.synchronize(); + #if ENABLED(LASER_POWER_INLINE) + if (parser.seen('I') == DISABLED(LASER_POWER_INLINE_INVERT)) { + cutter.inline_enabled(false); // Laser power in inline mode + return; + } + // Non-inline, standard case + cutter.inline_disable(); // Prevent future blocks re-setting the power #endif + planner.synchronize(); cutter.set_enabled(false); } diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index 1f9d710bb4c7..0937a86bd225 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -53,6 +53,10 @@ GcodeSuite gcode; #include "../feature/cancel_object.h" #endif +#if ENABLED(LASER_MOVE_POWER) + #include "../feature/spindle_laser.h" +#endif + #include "../MarlinCore.h" // for idle() millis_t GcodeSuite::previous_move_ms; @@ -172,6 +176,18 @@ void GcodeSuite::get_destination_from_command() { #if BOTH(MIXING_EXTRUDER, DIRECT_MIXING_IN_G1) M165(); #endif + + #if ENABLED(LASER_MOVE_POWER) + // Set the laser power in the planner to configure this move + if (parser.seen('S')) + cutter.inline_power(parser.value_int()); + else { + #if ENABLED(LASER_MOVE_G0_OFF) + if (parser.codenum == 0) // G0 + cutter.inline_enabled(false); + #endif + } + #endif } /** diff --git a/Marlin/src/gcode/motion/G0_G1.cpp b/Marlin/src/gcode/motion/G0_G1.cpp index 069d76fdad97..df0825a512d4 100644 --- a/Marlin/src/gcode/motion/G0_G1.cpp +++ b/Marlin/src/gcode/motion/G0_G1.cpp @@ -69,7 +69,7 @@ void GcodeSuite::G0_G1( #endif #endif - get_destination_from_command(); // Process X Y Z E F parameters + get_destination_from_command(); // Get X Y Z E F (and set cutter power) #ifdef G0_FEEDRATE if (fast_move) { diff --git a/Marlin/src/gcode/motion/G2_G3.cpp b/Marlin/src/gcode/motion/G2_G3.cpp index b0fb299ab26c..d6b18bdd9514 100644 --- a/Marlin/src/gcode/motion/G2_G3.cpp +++ b/Marlin/src/gcode/motion/G2_G3.cpp @@ -283,7 +283,7 @@ void GcodeSuite::G2_G3(const bool clockwise) { relative_mode = true; #endif - get_destination_from_command(); + get_destination_from_command(); // Get X Y Z E F (and set cutter power) #if ENABLED(SF_ARC_FIX) relative_mode = relative_mode_backup; diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h index a52ae1af2976..cda744d81b65 100644 --- a/Marlin/src/inc/Conditionals_adv.h +++ b/Marlin/src/inc/Conditionals_adv.h @@ -116,7 +116,23 @@ #define Z_STEPPER_ALIGN_AMP 1.0 #endif -#define HAS_CUTTER EITHER(SPINDLE_FEATURE, LASER_FEATURE) +// +// Spindle/Laser power display types +// Defined here so sanity checks can use them +// +#if EITHER(SPINDLE_FEATURE, LASER_FEATURE) + #define HAS_CUTTER 1 + #define _CUTTER_DISP_PWM 1 + #define _CUTTER_DISP_PERCENT 2 + #define _CUTTER_DISP_RPM 3 + #define _CUTTER_DISP(V) _CAT(_CUTTER_DISP_, V) + #define CUTTER_DISPLAY_IS(V) (_CUTTER_DISP(CUTTER_POWER_DISPLAY) == _CUTTER_DISP(V)) +#endif + +// Add features that need hardware PWM here +#if ANY(FAST_PWM_FAN, SPINDLE_LASER_PWM) + #define NEEDS_HARDWARE_PWM 1 +#endif #if !defined(__AVR__) || !defined(USBCON) // Define constants and variables for buffering serial data. @@ -290,3 +306,17 @@ #define MAXIMUM_STEPPER_RATE 250000 #endif #endif + +// +// SD Card connection methods +// Defined here so pins and sanity checks can use them +// +#if ENABLED(SDSUPPORT) + #define _SDCARD_LCD 1 + #define _SDCARD_ONBOARD 2 + #define _SDCARD_CUSTOM_CABLE 3 + #define _SDCARD_ID(V) _CAT(_SDCARD_, V) + #define SD_CONNECTION_IS(V) (_SDCARD_ID(SDCARD_CONNECTION) == _SDCARD_ID(V)) +#else + #define SD_CONNECTION_IS(...) 0 +#endif diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 20867b4fea08..b38aaa133206 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -324,17 +324,36 @@ /** * Override the SD_DETECT_STATE set in Configuration_adv.h + * and enable sharing of onboard SD host drives (all platforms but AGCM4) */ #if ENABLED(SDSUPPORT) - #if HAS_LCD_MENU && (SD_CONNECTION_IS(LCD) || !defined(SDCARD_CONNECTION)) - #undef SD_DETECT_STATE - #if ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) - #define SD_DETECT_STATE HIGH - #endif + + #if SD_CONNECTION_IS(ONBOARD) && DISABLED(NO_SD_HOST_DRIVE) && !defined(ARDUINO_GRAND_CENTRAL_M4) + // + // The external SD card is not used. Hardware SPI is used to access the card. + // When sharing the SD card with a PC we want the menu options to + // mount/unmount the card and refresh it. So we disable card detect. + // + #undef SD_DETECT_PIN + #define SHARED_SD_CARD + #endif + + #if DISABLED(SHARED_SD_CARD) + #define INIT_SDCARD_ON_BOOT 1 #endif - #ifndef SD_DETECT_STATE - #define SD_DETECT_STATE LOW + + #if PIN_EXISTS(SD_DETECT) + #if HAS_LCD_MENU && (SD_CONNECTION_IS(LCD) || !defined(SDCARD_CONNECTION)) + #undef SD_DETECT_STATE + #if ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) + #define SD_DETECT_STATE HIGH + #endif + #endif + #ifndef SD_DETECT_STATE + #define SD_DETECT_STATE LOW + #endif #endif + #endif /** @@ -2153,21 +2172,6 @@ #endif #endif -#if ENABLED(SDSUPPORT) - #if SD_CONNECTION_IS(ONBOARD) && DISABLED(NO_SD_HOST_DRIVE) && !defined(ARDUINO_GRAND_CENTRAL_M4) - // - // The external SD card is not used. Hardware SPI is used to access the card. - // When sharing the SD card with a PC we want the menu options to - // mount/unmount the card and refresh it. So we disable card detect. - // - #undef SD_DETECT_PIN - #define SHARED_SD_CARD - #endif - #if DISABLED(SHARED_SD_CARD) - #define INIT_SDCARD_ON_BOOT 1 - #endif -#endif - #if !NUM_SERIAL #undef BAUD_RATE_GCODE #endif diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 2fd61d4be10e..088ad098db92 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -1451,7 +1451,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS * Deploying the Allen Key probe uses big moves in z direction. Too dangerous for an unhomed z-axis. */ #if ENABLED(Z_PROBE_ALLEN_KEY) && (Z_HOME_DIR < 0) && ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) - #error "You can't home to a z min endstop with a Z_PROBE_ALLEN_KEY" + #error "You can't home to a z min endstop with a Z_PROBE_ALLEN_KEY." #endif /** @@ -2654,9 +2654,9 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #if ENABLED(BACKLASH_COMPENSATION) #ifndef BACKLASH_DISTANCE_MM - #error "BACKLASH_COMPENSATION requires BACKLASH_DISTANCE_MM" + #error "BACKLASH_COMPENSATION requires BACKLASH_DISTANCE_MM." #elif !defined(BACKLASH_CORRECTION) - #error "BACKLASH_COMPENSATION requires BACKLASH_CORRECTION" + #error "BACKLASH_COMPENSATION requires BACKLASH_CORRECTION." #elif IS_CORE constexpr float backlash_arr[] = BACKLASH_DISTANCE_MM; static_assert(!backlash_arr[CORE_AXIS_1] && !backlash_arr[CORE_AXIS_2], @@ -2736,6 +2736,45 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #endif #if HAS_CUTTER + #ifndef CUTTER_POWER_DISPLAY + #error "CUTTER_POWER_DISPLAY is required with a spindle or laser. Please update your Configuration_adv.h." + #elif !CUTTER_DISPLAY_IS(PWM) && !CUTTER_DISPLAY_IS(PERCENT) && !CUTTER_DISPLAY_IS(RPM) + #error "CUTTER_POWER_DISPLAY must be PWM, PERCENT, or RPM. Please update your Configuration_adv.h." + #endif + + #if ENABLED(LASER_POWER_INLINE) + #if ENABLED(SPINDLE_CHANGE_DIR) + #error "SPINDLE_CHANGE_DIR and LASER_POWER_INLINE are incompatible." + #elif ENABLED(LASER_MOVE_G0_OFF) && DISABLED(LASER_MOVE_POWER) + #error "LASER_MOVE_G0_OFF requires LASER_MOVE_POWER. Please update your Configuration_adv.h." + #endif + #if ENABLED(LASER_POWER_INLINE_TRAPEZOID) + #if DISABLED(SPINDLE_LASER_PWM) + #error "LASER_POWER_INLINE_TRAPEZOID requires SPINDLE_LASER_PWM to function." + #elif ENABLED(S_CURVE_ACCELERATION) + //#ifndef LASER_POWER_INLINE_S_CURVE_ACCELERATION_WARN + // #define LASER_POWER_INLINE_S_CURVE_ACCELERATION_WARN + // #warning "Combining LASER_POWER_INLINE_TRAPEZOID with S_CURVE_ACCELERATION may result in unintended behavior." + //#endif + #endif + #endif + #if ENABLED(LASER_POWER_INLINE_INVERT) + //#ifndef LASER_POWER_INLINE_INVERT_WARN + // #define LASER_POWER_INLINE_INVERT_WARN + // #warning "Enabling LASER_POWER_INLINE_INVERT means that `M5` won't kill the laser immediately; use `M5 I` instead." + //#endif + #endif + #else + #if SPINDLE_LASER_POWERUP_DELAY < 1 + #error "SPINDLE_LASER_POWERUP_DELAY must be greater than 0." + #elif SPINDLE_LASER_POWERDOWN_DELAY < 1 + #error "SPINDLE_LASER_POWERDOWN_DELAY must be greater than 0." + #elif ENABLED(LASER_MOVE_POWER) + #error "LASER_MOVE_POWER requires LASER_POWER_INLINE." + #elif ANY(LASER_POWER_INLINE_TRAPEZOID, LASER_POWER_INLINE_INVERT, LASER_MOVE_G0_OFF, LASER_MOVE_POWER) + #error "Enabled an inline laser feature without inline laser power being enabled." + #endif + #endif #define _PIN_CONFLICT(P) (PIN_EXISTS(P) && P##_PIN == SPINDLE_LASER_PWM_PIN) #if BOTH(SPINDLE_FEATURE, LASER_FEATURE) #error "Enable only one of SPINDLE_FEATURE or LASER_FEATURE." @@ -2748,13 +2787,9 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #error "SPINDLE_LASER_PWM_PIN is required for SPINDLE_LASER_PWM." #elif !PWM_PIN(SPINDLE_LASER_PWM_PIN) #error "SPINDLE_LASER_PWM_PIN not assigned to a PWM pin." - #elif SPINDLE_LASER_POWERUP_DELAY < 1 - #error "SPINDLE_LASER_POWERUP_DELAY must be greater than 0." - #elif SPINDLE_LASER_POWERDOWN_DELAY < 1 - #error "SPINDLE_LASER_POWERDOWN_DELAY must be greater than 0." #elif !defined(SPINDLE_LASER_PWM_INVERT) #error "SPINDLE_LASER_PWM_INVERT is required for (SPINDLE|LASER)_FEATURE." - #elif !defined(SPEED_POWER_SLOPE) || !defined(SPEED_POWER_INTERCEPT) || !defined(SPEED_POWER_MIN) || !defined(SPEED_POWER_MAX) + #elif !defined(SPEED_POWER_SLOPE) || !defined(SPEED_POWER_INTERCEPT) || !defined(SPEED_POWER_MIN) || !defined(SPEED_POWER_MAX) || !defined(SPEED_POWER_STARTUP) #error "SPINDLE_LASER_PWM equation constant(s) missing." #elif _PIN_CONFLICT(X_MIN) #error "SPINDLE_LASER_PWM pin conflicts with X_MIN_PIN." diff --git a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp index be414ab30372..b4bba3782ce8 100644 --- a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp +++ b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp @@ -570,8 +570,12 @@ void MarlinUI::draw_status_screen() { // Laser / Spindle #if DO_DRAW_CUTTER if (cutter.power && PAGE_CONTAINS(STATUS_CUTTER_TEXT_Y - INFO_FONT_ASCENT, STATUS_CUTTER_TEXT_Y - 1)) { - lcd_put_u8str(STATUS_CUTTER_TEXT_X, STATUS_CUTTER_TEXT_Y, i16tostr3rj(cutter.powerPercent(cutter.power))); - lcd_put_wchar('%'); + lcd_put_u8str(STATUS_CUTTER_TEXT_X, STATUS_CUTTER_TEXT_Y, i16tostr3rj(cutter.power)); + #if CUTTER_DISPLAY_IS(PERCENT) + lcd_put_wchar('%'); + #elif CUTTER_DISPLAY_IS(RPM) + lcd_put_wchar('K'); + #endif } #endif diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index 79a6f814b2ee..0aea571caabf 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -90,6 +90,7 @@ namespace Language_en { PROGMEM Language_Str MSG_PREHEAT_2_SETTINGS = _UxGT("Preheat ") PREHEAT_2_LABEL _UxGT(" Conf"); PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("Preheat Custom"); PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Cooldown"); + PROGMEM Language_Str MSG_CUTTER_FREQUENCY = _UxGT("Frequency"); PROGMEM Language_Str MSG_LASER_MENU = _UxGT("Laser Control"); PROGMEM Language_Str MSG_LASER_OFF = _UxGT("Laser Off"); PROGMEM Language_Str MSG_LASER_ON = _UxGT("Laser On"); @@ -603,7 +604,7 @@ namespace Language_en { PROGMEM Language_Str MSG_BACKLASH_C = LCD_STR_C; PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Correction"); PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Smoothing"); - + PROGMEM Language_Str MSG_LEVEL_X_AXIS = _UxGT("Level X Axis"); PROGMEM Language_Str MSG_AUTO_CALIBRATE = _UxGT("Auto Calibrate"); PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Heater Timeout"); diff --git a/Marlin/src/lcd/menu/menu_spindle_laser.cpp b/Marlin/src/lcd/menu/menu_spindle_laser.cpp index fd42522839eb..d8e680ec3c39 100644 --- a/Marlin/src/lcd/menu/menu_spindle_laser.cpp +++ b/Marlin/src/lcd/menu/menu_spindle_laser.cpp @@ -36,18 +36,29 @@ START_MENU(); BACK_ITEM(MSG_MAIN); - if (cutter.enabled()) { - #if ENABLED(SPINDLE_LASER_PWM) - EDIT_ITEM(CUTTER_MENU_TYPE, MSG_CUTTER(POWER), &cutter.power, SPEED_POWER_MIN, SPEED_POWER_MAX); - #endif + #if ENABLED(SPINDLE_LASER_PWM) + EDIT_ITEM_FAST(CUTTER_MENU_POWER_TYPE, MSG_CUTTER(POWER), &cutter.setPower, cutter.interpret_power(SPEED_POWER_MIN), cutter.interpret_power(SPEED_POWER_MAX), + []{ + if (cutter.isOn) { + cutter.power = cutter.setPower; + } + }); + #endif + + if (cutter.enabled() && cutter.isOn) ACTION_ITEM(MSG_CUTTER(OFF), cutter.disable); - } else { ACTION_ITEM(MSG_CUTTER(ON), cutter.enable_forward); #if ENABLED(SPINDLE_CHANGE_DIR) ACTION_ITEM(MSG_SPINDLE_REVERSE, cutter.enable_reverse); #endif } + + #if ENABLED(MARLIN_DEV_MODE) + #if ENABLED(HAL_CAN_SET_PWM_FREQ) && defined(SPINDLE_LASER_FREQUENCY) + EDIT_ITEM_FAST(CUTTER_MENU_FREQUENCY_TYPE, MSG_CUTTER_FREQUENCY, &cutter.frequency, 2000, 50000,[]{ cutter.refresh_frequency();}); + #endif + #endif END_MENU(); } diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index e1a050a45924..2de46373b26f 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -815,11 +815,10 @@ void Planner::calculate_trapezoid_for_block(block_t* const block, const float &e #if ENABLED(S_CURVE_ACCELERATION) // Jerk controlled speed requires to express speed versus time, NOT steps uint32_t acceleration_time = ((float)(cruise_rate - initial_rate) / accel) * (STEPPER_TIMER_RATE), - deceleration_time = ((float)(cruise_rate - final_rate) / accel) * (STEPPER_TIMER_RATE); - + deceleration_time = ((float)(cruise_rate - final_rate) / accel) * (STEPPER_TIMER_RATE), // And to offload calculations from the ISR, we also calculate the inverse of those times here - uint32_t acceleration_time_inverse = get_period_inverse(acceleration_time); - uint32_t deceleration_time_inverse = get_period_inverse(deceleration_time); + acceleration_time_inverse = get_period_inverse(acceleration_time), + deceleration_time_inverse = get_period_inverse(deceleration_time); #endif // Store new block parameters @@ -834,6 +833,47 @@ void Planner::calculate_trapezoid_for_block(block_t* const block, const float &e block->cruise_rate = cruise_rate; #endif block->final_rate = final_rate; + + /** + * Laser trapezoid calculations + * + * Approximate the trapezoid with the laser, incrementing the power every `entry_per` while accelerating + * and decrementing it every `exit_power_per` while decelerating, thus ensuring power is related to feedrate. + * + * LASER_POWER_INLINE_TRAPEZOID_CONT doesn't need this as it continuously approximates + * + * Note this may behave unreliably when running with S_CURVE_ACCELERATION + */ + #if ENABLED(LASER_POWER_INLINE_TRAPEZOID) + if (block->laser.power > 0) { // No need to care if power == 0 + const uint8_t entry_power = block->laser.power * entry_factor; // Power on block entry + #if DISABLED(LASER_POWER_INLINE_TRAPEZOID_CONT) + // Speedup power + const uint8_t entry_power_diff = block->laser.power - entry_power; + if (entry_power_diff) { + block->laser.entry_per = accelerate_steps / entry_power_diff; + block->laser.power_entry = entry_power; + } + else { + block->laser.entry_per = 0; + block->laser.power_entry = block->laser.power; + } + // Slowdown power + const uint8_t exit_power = block->laser.power * exit_factor, // Power on block entry + exit_power_diff = block->laser.power - exit_power; + if (exit_power_diff) { + block->laser.exit_per = (block->step_event_count - block->decelerate_after) / exit_power_diff; + block->laser.power_exit = exit_power; + } + else { + block->laser.exit_per = 0; + block->laser.power_exit = block->laser.power; + } + #else + block->laser.power_entry = entry_power; + #endif + } + #endif } /* PLANNER SPEED DEFINITION @@ -1813,6 +1853,12 @@ bool Planner::_populate_block(block_t * const block, bool split_move, // Set direction bits block->direction_bits = dm; + // Update block laser power + #if ENABLED(LASER_POWER_INLINE) + block->laser.status = settings.laser.status; + block->laser.power = settings.laser.power; + #endif + // Number of steps for each axis // See http://www.corexy.com/theory.html #if CORE_IS_XY diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index 24c02c01c5c6..a42c84c1faf9 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -52,7 +52,7 @@ #endif #if HAS_CUTTER - #include "../feature/spindle_laser.h" + #include "../feature/spindle_laser_types.h" #endif // Feedrate for manual moves @@ -88,6 +88,23 @@ enum BlockFlag : char { BLOCK_FLAG_SYNC_POSITION = _BV(BLOCK_BIT_SYNC_POSITION) }; +#if ENABLED(LASER_POWER_INLINE) + + typedef struct { + uint8_t status, // See planner settings for meaning + power; // Ditto; When in trapezoid mode this is nominal power + #if ENABLED(LASER_POWER_INLINE_TRAPEZOID) + uint8_t power_entry; // Entry power for the laser + #if DISABLED(LASER_POWER_INLINE_TRAPEZOID_CONT) + uint8_t power_exit; // Exit power for the laser + uint32_t entry_per, // Steps per power increment (to avoid floats in stepper calcs) + exit_per; // Steps per power decrement + #endif + #endif + } block_laser_t; + +#endif + /** * struct block_t * @@ -174,12 +191,36 @@ typedef struct block_t { uint32_t sdpos; #endif + #if ENABLED(LASER_POWER_INLINE) + block_laser_t laser; + #endif + } block_t; #define HAS_POSITION_FLOAT ANY(LIN_ADVANCE, SCARA_FEEDRATE_SCALING, GRADIENT_MIX, LCD_SHOW_E_TOTAL) #define BLOCK_MOD(n) ((n)&(BLOCK_BUFFER_SIZE-1)) +#if ENABLED(LASER_POWER_INLINE) + typedef struct { + /** + * Laser status bitmask; most bits are unused; + * 0: Planner buffer enable + * 1: Laser enable + * 2: Reserved for direction + */ + uint8_t status; + /** + * Laser power: 0 or 255 in case of PWM-less laser, + * or the OCR value; + * + * Using OCR instead of raw power, + * as it avoids floating points during move loop + */ + uint8_t power; + } settings_laser_t; +#endif + typedef struct { uint32_t max_acceleration_mm_per_s2[XYZE_N], // (mm/s^2) M201 XYZE min_segment_time_us; // (µs) M205 B @@ -190,6 +231,9 @@ typedef struct { travel_acceleration; // (mm/s^2) M204 T - Travel acceleration. DEFAULT ACCELERATION for all NON printing moves. feedRate_t min_feedrate_mm_s, // (mm/s) M205 S - Minimum linear feedrate min_travel_feedrate_mm_s; // (mm/s) M205 T - Minimum travel feedrate + #if ENABLED(LASER_POWER_INLINE) + settings_laser_t laser; + #endif } planner_settings_t; #if DISABLED(SKEW_CORRECTION) diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index ed48b83d5a6c..f77a596b08c0 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -133,6 +133,10 @@ Stepper stepper; // Singleton #include "../feature/powerloss.h" #endif +#if HAS_CUTTER + #include "../feature/spindle_laser.h" +#endif + // public: #if HAS_EXTRA_ENDSTOPS || ENABLED(Z_STEPPER_AUTO_ALIGN) @@ -236,6 +240,20 @@ xyz_long_t Stepper::endstops_trigsteps; xyze_long_t Stepper::count_position{0}; xyze_int8_t Stepper::count_direction{0}; +#if ENABLED(LASER_POWER_INLINE_TRAPEZOID) + Stepper::stepper_laser_t Stepper::laser = { + .trap_en = false, + .cur_power = 0, + .cruise_set = false, + #if DISABLED(LASER_POWER_INLINE_TRAPEZOID_CONT) + .last_step_count = 0, + .acc_step_count = 0 + #else + .till_update = 0 + #endif + }; +#endif + #define DUAL_ENDSTOP_APPLY_STEP(A,V) \ if (separate_multi_axis) { \ if (A##_HOME_DIR < 0) { \ @@ -1674,10 +1692,9 @@ uint32_t Stepper::block_phase_isr() { #if ENABLED(S_CURVE_ACCELERATION) // Get the next speed to use (Jerk limited!) - uint32_t acc_step_rate = - acceleration_time < current_block->acceleration_time - ? _eval_bezier_curve(acceleration_time) - : current_block->cruise_rate; + uint32_t acc_step_rate = acceleration_time < current_block->acceleration_time + ? _eval_bezier_curve(acceleration_time) + : current_block->cruise_rate; #else acc_step_rate = STEP_MULTIPLY(acceleration_time, current_block->acceleration_rate) + current_block->initial_rate; NOMORE(acc_step_rate, current_block->nominal_rate); @@ -1690,9 +1707,40 @@ uint32_t Stepper::block_phase_isr() { acceleration_time += interval; #if ENABLED(LIN_ADVANCE) - // Fire ISR if final adv_rate is reached - if (LA_steps && (!LA_use_advance_lead || LA_isr_rate != current_block->advance_speed)) - initiateLA(); + if (LA_use_advance_lead) { + // Fire ISR if final adv_rate is reached + if (LA_steps && LA_isr_rate != current_block->advance_speed) nextAdvanceISR = 0; + } + else if (LA_steps) nextAdvanceISR = 0; + #endif + + // Update laser - Accelerating + #if ENABLED(LASER_POWER_INLINE_TRAPEZOID) + if (laser.trap_en) { + #if DISABLED(LASER_POWER_INLINE_TRAPEZOID_CONT) + if (current_block->laser.entry_per) { + laser.acc_step_count -= step_events_completed - laser.last_step_count; + laser.last_step_count = step_events_completed; + + // Should be faster than a divide, since this should trip just once + if (laser.acc_step_count < 0) { + while (laser.acc_step_count < 0) { + laser.acc_step_count += current_block->laser.entry_per; + if (laser.cur_power < current_block->laser.power) laser.cur_power++; + } + cutter.set_ocr_power(laser.cur_power); + } + } + #else + if (laser.till_update) + laser.till_update--; + else { + laser.till_update = LASER_POWER_INLINE_TRAPEZOID_CONT_PER; + laser.cur_power = (current_block->laser.power * acc_step_rate) / current_block->nominal_rate; + cutter.set_ocr_power(laser.cur_power); // Cycle efficiency is irrelevant it the last line was many cycles + } + #endif + } #endif } // Are we in Deceleration phase ? @@ -1740,10 +1788,39 @@ uint32_t Stepper::block_phase_isr() { LA_isr_rate = current_block->advance_speed; } } - else if (LA_steps) initiateLA(); + else if (LA_steps) nextAdvanceISR = 0; + #endif // LIN_ADVANCE + + // Update laser - Decelerating + #if ENABLED(LASER_POWER_INLINE_TRAPEZOID) + if (laser.trap_en) { + #if DISABLED(LASER_POWER_INLINE_TRAPEZOID_CONT) + if (current_block->laser.exit_per) { + laser.acc_step_count -= step_events_completed - laser.last_step_count; + laser.last_step_count = step_events_completed; + + // Should be faster than a divide, since this should trip just once + if (laser.acc_step_count < 0) { + while (laser.acc_step_count < 0) { + laser.acc_step_count += current_block->laser.exit_per; + if (laser.cur_power > current_block->laser.power_exit) laser.cur_power--; + } + cutter.set_ocr_power(laser.cur_power); + } + } + #else + if (laser.till_update) + laser.till_update--; + else { + laser.till_update = LASER_POWER_INLINE_TRAPEZOID_CONT_PER; + laser.cur_power = (current_block->laser.power * step_rate) / current_block->nominal_rate; + cutter.set_ocr_power(laser.cur_power); // Cycle efficiency isn't relevant when the last line was many cycles + } + #endif + } #endif } - // We must be in cruise phase otherwise + // Must be in cruise phase otherwise else { #if ENABLED(LIN_ADVANCE) @@ -1759,6 +1836,22 @@ uint32_t Stepper::block_phase_isr() { // The timer interval is just the nominal value for the nominal speed interval = ticks_nominal; + + // Update laser - Cruising + #if ENABLED(LASER_POWER_INLINE_TRAPEZOID) + if (laser.trap_en) { + if (!laser.cruise_set) { + laser.cur_power = current_block->laser.power; + cutter.set_ocr_power(laser.cur_power); + laser.cruise_set = true; + } + #if ENABLED(LASER_POWER_INLINE_TRAPEZOID_CONT) + laser.till_update = LASER_POWER_INLINE_TRAPEZOID_CONT_PER; + #else + laser.last_step_count = step_events_completed; + #endif + } + #endif } } } @@ -1805,11 +1898,11 @@ uint32_t Stepper::block_phase_isr() { * If DeltaA == DeltaB, the movement is only in the 1st axis (X) */ #if EITHER(COREXY, COREXZ) - #define X_CMP == + #define X_CMP(A,B) ((A)==(B)) #else - #define X_CMP != + #define X_CMP(A,B) ((A)!=(B)) #endif - #define X_MOVE_TEST ( S_(1) != S_(2) || (S_(1) > 0 && D_(1) X_CMP D_(2)) ) + #define X_MOVE_TEST ( S_(1) != S_(2) || (S_(1) > 0 && X_CMP(D_(1),D_(2))) ) #else #define X_MOVE_TEST !!current_block->steps.a #endif @@ -1823,11 +1916,11 @@ uint32_t Stepper::block_phase_isr() { * If DeltaA == -DeltaB, the movement is only in the 2nd axis (Y or Z) */ #if EITHER(COREYX, COREYZ) - #define Y_CMP == + #define Y_CMP(A,B) ((A)==(B)) #else - #define Y_CMP != + #define Y_CMP(A,B) ((A)!=(B)) #endif - #define Y_MOVE_TEST ( S_(1) != S_(2) || (S_(1) > 0 && D_(1) Y_CMP D_(2)) ) + #define Y_MOVE_TEST ( S_(1) != S_(2) || (S_(1) > 0 && Y_CMP(D_(1),D_(2))) ) #else #define Y_MOVE_TEST !!current_block->steps.b #endif @@ -1841,11 +1934,11 @@ uint32_t Stepper::block_phase_isr() { * If DeltaA == -DeltaB, the movement is only in the 2nd axis (Z) */ #if EITHER(COREZX, COREZY) - #define Z_CMP == + #define Z_CMP(A,B) ((A)==(B)) #else - #define Z_CMP != + #define Z_CMP(A,B) ((A)!=(B)) #endif - #define Z_MOVE_TEST ( S_(1) != S_(2) || (S_(1) > 0 && D_(1) Z_CMP D_(2)) ) + #define Z_MOVE_TEST ( S_(1) != S_(2) || (S_(1) > 0 && Z_CMP(D_(1),D_(2))) ) #else #define Z_MOVE_TEST !!current_block->steps.c #endif @@ -1938,6 +2031,39 @@ uint32_t Stepper::block_phase_isr() { set_directions(); } + #if ENABLED(LASER_POWER_INLINE) + const uint8_t stat = current_block->laser.status; + #if ENABLED(LASER_POWER_INLINE_TRAPEZOID) + laser.trap_en = (stat & 0x03) == 0x03; + laser.cur_power = current_block->laser.power_entry; // RESET STATE + laser.cruise_set = false; + #if DISABLED(LASER_POWER_INLINE_TRAPEZOID_CONT) + laser.last_step_count = 0; + laser.acc_step_count = current_block->laser.entry_per / 2; + #else + laser.till_update = 0; + #endif + // Always have PWM in this case + if (TEST(stat, 0)) { // Planner controls the laser + if (TEST(stat, 1)) // Laser is on + cutter.set_ocr_power(laser.cur_power); + else + cutter.set_power(0); + } + #else + if (TEST(stat, 0)) { // Planner controls the laser + #if ENABLED(SPINDLE_LASER_PWM) + if (TEST(stat, 1)) // Laser is on + cutter.set_ocr_power(current_block->laser.power); + else + cutter.set_power(0); + #else + cutter.set_enabled(TEST(stat, 1)); + #endif + } + #endif + #endif // LASER_POWER_INLINE + // At this point, we must ensure the movement about to execute isn't // trying to force the head against a limit switch. If using interrupt- // driven change detection, and already against a limit then no call to @@ -1957,21 +2083,35 @@ uint32_t Stepper::block_phase_isr() { // Mark the time_nominal as not calculated yet ticks_nominal = -1; - #if DISABLED(S_CURVE_ACCELERATION) - // Set as deceleration point the initial rate of the block - acc_step_rate = current_block->initial_rate; - #endif - #if ENABLED(S_CURVE_ACCELERATION) // Initialize the Bézier speed curve _calc_bezier_curve_coeffs(current_block->initial_rate, current_block->cruise_rate, current_block->acceleration_time_inverse); // We haven't started the 2nd half of the trapezoid bezier_2nd_half = false; + #else + // Set as deceleration point the initial rate of the block + acc_step_rate = current_block->initial_rate; #endif // Calculate the initial timer interval interval = calc_timer_interval(current_block->initial_rate, &steps_per_isr); } + #if ENABLED(LASER_POWER_INLINE_CONTINUOUS) + else { // No new block found; so apply inline laser parameters + // This should mean ending file with 'M5 I' will stop the laser; thus the inline flag isn't needed + const uint8_t stat = planner.settings.laser.status; + if (TEST(stat, 0)) { // Planner controls the laser + #if ENABLED(SPINDLE_LASER_PWM) + if (TEST(stat, 1)) // Laser is on + cutter.set_ocr_power(planner.settings.laser.power); + else + cutter.set_power(0); + #else + cutter.set_enabled(TEST(stat, 1)); + #endif + } + } + #endif } // Return the interval to wait diff --git a/Marlin/src/module/stepper.h b/Marlin/src/module/stepper.h index 46c6c1c16a78..3876980ad064 100644 --- a/Marlin/src/module/stepper.h +++ b/Marlin/src/module/stepper.h @@ -339,23 +339,35 @@ class Stepper { static uint32_t acc_step_rate; // needed for deceleration start point #endif - // // Exact steps at which an endstop was triggered - // static xyz_long_t endstops_trigsteps; - // // Positions of stepper motors, in step units - // static xyze_long_t count_position; - // - // Current direction of stepper motors (+1 or -1) - // + // Current stepper motor directions (+1 or -1) static xyze_int8_t count_direction; - public: + #if ENABLED(LASER_POWER_INLINE_TRAPEZOID) + + typedef struct { + bool trap_en; // Trapezoid needed flag (i.e., laser on, planner in control) + uint8_t cur_power; // Current laser power + bool cruise_set; // Power set up for cruising? + + #if DISABLED(LASER_POWER_INLINE_TRAPEZOID_CONT) + uint32_t last_step_count, // Step count from the last update + acc_step_count; // Bresenham counter for laser accel/decel + #else + uint16_t till_update; // Countdown to the next update + #endif + } stepper_laser_t; + static stepper_laser_t laser; + + #endif + + public: // Initialize stepper hardware static void init(); From ed0799d65341f0efc30fadfc0246aba62e4e67a3 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 4 Apr 2020 00:03:24 +0000 Subject: [PATCH 23/37] [cron] Bump distribution date (2020-04-04) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index fce0c46b5c8a..74c38628c456 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-04-03" + #define STRING_DISTRIBUTION_DATE "2020-04-04" #endif /** From bc01d8d023e1dc95d4cbff50fc22edde5a6ff3f4 Mon Sep 17 00:00:00 2001 From: InsanityAutomation <38436470+InsanityAutomation@users.noreply.github.com> Date: Fri, 3 Apr 2020 20:17:05 -0400 Subject: [PATCH 24/37] Toolchange touchup (#17395) Co-authored-by: Scott Lahteine --- Marlin/src/module/tool_change.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/module/tool_change.cpp b/Marlin/src/module/tool_change.cpp index 2471581c8c68..658671fb7ef5 100644 --- a/Marlin/src/module/tool_change.cpp +++ b/Marlin/src/module/tool_change.cpp @@ -821,7 +821,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { if (new_tool >= EXTRUDERS) return invalid_extruder_error(new_tool); - if (!no_move && !all_axes_homed()) { + if (!no_move && !homing_needed()) { no_move = true; if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("No move (not homed)"); } @@ -1073,7 +1073,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { #endif #ifdef EVENT_GCODE_AFTER_TOOLCHANGE - if (!no_move) + if (!no_move && TERN1(DUAL_X_CARRIAGE, dual_x_carriage_mode == DXC_AUTO_PARK_MODE)) gcode.process_subcommands_now_P(PSTR(EVENT_GCODE_AFTER_TOOLCHANGE)); #endif From 65f6a373b0a77da23f0758d5d1520e404436cec0 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 4 Apr 2020 00:08:25 -0500 Subject: [PATCH 25/37] Refactor SD detect handler (#17380) Co-Authored-By: Eric Ptak --- Marlin/src/MarlinCore.cpp | 95 +++++++++++++++----------- Marlin/src/lcd/extui/ui_api.cpp | 23 +------ Marlin/src/lcd/ultralcd.cpp | 114 +++++++++++++++----------------- Marlin/src/lcd/ultralcd.h | 4 ++ Marlin/src/sd/cardreader.cpp | 36 ++++++++++ Marlin/src/sd/cardreader.h | 3 + 6 files changed, 156 insertions(+), 119 deletions(-) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 5073c339cd1a..da3c6cbaa2ec 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -443,7 +443,6 @@ void startOrResumeJob() { /** * Minimal management of Marlin's core activities: - * - Check for Filament Runout * - Keep the command buffer full * - Check for maximum inactive time between commands * - Check for maximum inactive time between stepper commands @@ -454,13 +453,8 @@ void startOrResumeJob() { * - Check if an idle but hot extruder needs filament extruded (EXTRUDER_RUNOUT_PREVENT) * - Pulse FET_SAFETY_PIN if it exists */ - inline void manage_inactivity(const bool ignore_stepper_queue=false) { - #if HAS_FILAMENT_SENSOR - runout.run(); - #endif - if (queue.length < BUFSIZE) queue.get_available_commands(); const millis_t ms = millis(); @@ -644,9 +638,53 @@ inline void manage_inactivity(const bool ignore_stepper_queue=false) { } /** - * Standard idle routine keeps the machine alive + * Standard idle routine keeps the machine alive: + * - Core Marlin activities + * - Manage heaters (and Watchdog) + * - Max7219 heartbeat, animation, etc. + * + * Only after setup() is complete: + * - Handle filament runout sensors + * - Run HAL idle tasks + * - Handle Power-Loss Recovery + * - Run StallGuard endstop checks + * - Handle SD Card insert / remove + * - Handle USB Flash Drive insert / remove + * - Announce Host Keepalive state (if any) + * - Update the Print Job Timer state + * - Update the Beeper queue + * - Read Buttons and Update the LCD + * - Run i2c Position Encoders + * - Auto-report Temperatures / SD Status + * - Update the Prusa MMU2 + * - Handle Joystick jogging */ void idle(TERN_(ADVANCED_PAUSE_FEATURE, bool no_stepper_sleep/*=false*/)) { + + // Core Marlin activities + manage_inactivity(TERN_(ADVANCED_PAUSE_FEATURE, no_stepper_sleep)); + + // Manage Heaters (and Watchdog) + thermalManager.manage_heater(); + + // Max7219 heartbeat, animation, etc + #if ENABLED(MAX7219_DEBUG) + max7219.idle_tasks(); + #endif + + // Return if setup() isn't completed + if (marlin_state == MF_INITIALIZING) return; + + // Handle filament runout sensors + #if HAS_FILAMENT_SENSOR + runout.run(); + #endif + + // Run HAL idle tasks + #ifdef HAL_IDLETASK + HAL_idletask(); + #endif + // Handle Power-Loss Recovery #if ENABLED(POWER_LOSS_RECOVERY) && PIN_EXISTS(POWER_LOSS) recovery.outage(); @@ -660,29 +698,21 @@ void idle(TERN_(ADVANCED_PAUSE_FEATURE, bool no_stepper_sleep/*=false*/)) { if (endstops.tmc_spi_homing_check()) break; #endif - // Max7219 heartbeat, animation, etc. - #if ENABLED(MAX7219_DEBUG) - max7219.idle_tasks(); + // Handle SD Card insert / remove + #if ENABLED(SDSUPPORT) + card.manage_media(); #endif - // Read Buttons and Update the LCD - ui.update(); + // Handle USB Flash Drive insert / remove + #if ENABLED(USB_FLASH_DRIVE_SUPPORT) + Sd2Card::idle(); + #endif // Announce Host Keepalive state (if any) #if ENABLED(HOST_KEEPALIVE_FEATURE) gcode.host_keepalive(); #endif - // Core Marlin activities - manage_inactivity( - #if ENABLED(ADVANCED_PAUSE_FEATURE) - no_stepper_sleep - #endif - ); - - // Manage heaters (and Watchdog) - thermalManager.manage_heater(); - // Update the Print Job Timer state #if ENABLED(PRINTCOUNTER) print_job_timer.tick(); @@ -693,6 +723,9 @@ void idle(TERN_(ADVANCED_PAUSE_FEATURE, bool no_stepper_sleep/*=false*/)) { buzzer.tick(); #endif + // Read Buttons and Update the LCD + ui.update(); + // Run i2c Position Encoders #if ENABLED(I2C_POSITION_ENCODERS) static millis_t i2cpem_next_update_ms; @@ -705,11 +738,6 @@ void idle(TERN_(ADVANCED_PAUSE_FEATURE, bool no_stepper_sleep/*=false*/)) { } #endif - // Run HAL idle tasks - #ifdef HAL_IDLETASK - HAL_idletask(); - #endif - // Auto-report Temperatures / SD Status #if HAS_AUTO_REPORTING if (!gcode.autoreport_paused) { @@ -722,11 +750,6 @@ void idle(TERN_(ADVANCED_PAUSE_FEATURE, bool no_stepper_sleep/*=false*/)) { } #endif - // Handle USB Flash Drive insert / remove - #if ENABLED(USB_FLASH_DRIVE_SUPPORT) - Sd2Card::idle(); - #endif - // Update the Prusa MMU2 #if ENABLED(PRUSA_MMU2) mmu2.mmu_loop(); @@ -983,8 +1006,8 @@ void setup() { SETUP_RUN(ui.show_bootscreen()); #endif - #if ENABLED(SDSUPPORT) && defined(SDCARD_CONNECTION) && !SD_CONNECTION_IS(LCD) - SETUP_RUN(card.mount()); // Mount onboard / custom SD card before settings.first_load + #if BOTH(SDSUPPORT, SDCARD_EEPROM_EMULATION) + SETUP_RUN(card.mount()); // Mount media with settings before first_load #endif SETUP_RUN(settings.first_load()); // Load data from EEPROM if available (or use defaults) @@ -1151,10 +1174,6 @@ void setup() { queue.inject_P(PSTR(STARTUP_COMMANDS)); #endif - #if ENABLED(INIT_SDCARD_ON_BOOT) && !HAS_SPI_LCD - SETUP_RUN(card.beginautostart()); - #endif - #if ENABLED(HOST_PROMPT_SUPPORT) SETUP_RUN(host_action_prompt_end()); #endif diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index a5b1460c90af..d57adadfefed 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -1149,28 +1149,7 @@ void MarlinUI::init() { ExtUI::onStartup(); } -void MarlinUI::update() { - #if ENABLED(SDSUPPORT) - static bool last_sd_status; - const bool sd_status = IS_SD_INSERTED(); - if (sd_status != last_sd_status) { - last_sd_status = sd_status; - if (sd_status) { - card.mount(); - if (card.isMounted()) - ExtUI::onMediaInserted(); - else - ExtUI::onMediaError(); - } - else { - const bool ok = card.isMounted(); - card.release(); - if (ok) ExtUI::onMediaRemoved(); - } - } - #endif // SDSUPPORT - ExtUI::onIdle(); -} +void MarlinUI::update() { ExtUI::onIdle(); } void MarlinUI::kill_screen(PGM_P const error, PGM_P const component) { using namespace ExtUI; diff --git a/Marlin/src/lcd/ultralcd.cpp b/Marlin/src/lcd/ultralcd.cpp index ff0331eb2072..10a717b6fe2e 100644 --- a/Marlin/src/lcd/ultralcd.cpp +++ b/Marlin/src/lcd/ultralcd.cpp @@ -121,10 +121,6 @@ MarlinUI ui; #endif #endif -#if ENABLED(INIT_SDCARD_ON_BOOT) - uint8_t lcd_sd_status; -#endif - #if HAS_LCD_MENU && LCD_TIMEOUT_TO_STATUS bool MarlinUI::defer_return_to_status; #endif @@ -342,13 +338,8 @@ void MarlinUI::init() { #endif // HAS_SHIFT_ENCODER - #if ENABLED(SDSUPPORT) - #if PIN_EXISTS(SD_DETECT) - SET_INPUT_PULLUP(SD_DETECT_PIN); - #endif - #if ENABLED(INIT_SDCARD_ON_BOOT) - lcd_sd_status = 2; // UNKNOWN - #endif + #if ENABLED(SDSUPPORT) && PIN_EXISTS(SD_DETECT) + SET_INPUT_PULLUP(SD_DETECT_PIN); #endif #if HAS_ENCODER_ACTION && HAS_SLOW_BUTTONS @@ -744,11 +735,11 @@ void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) { */ LCDViewAction MarlinUI::lcdDrawUpdate = LCDVIEW_CLEAR_CALL_REDRAW; +millis_t next_lcd_update_ms; void MarlinUI::update() { static uint16_t max_display_update_time = 0; - static millis_t next_lcd_update_ms; millis_t ms = millis(); #if HAS_LCD_MENU && LCD_TIMEOUT_TO_STATUS @@ -824,53 +815,6 @@ void MarlinUI::update() { #endif // HAS_LCD_MENU - #if ENABLED(INIT_SDCARD_ON_BOOT) - // - // SPI SD Card detection (and first card init when the LCD is present) - // - const uint8_t sd_status = (uint8_t)IS_SD_INSERTED(); - if (sd_status != lcd_sd_status && detected()) { - - uint8_t old_sd_status = lcd_sd_status; // prevent re-entry to this block! - lcd_sd_status = sd_status; - - if (sd_status) { - safe_delay(500); // Some boards need a delay to get settled - card.mount(); - if (old_sd_status == 2) - card.beginautostart(); // Initial boot - else - set_status_P(GET_TEXT(MSG_MEDIA_INSERTED)); - } - #if PIN_EXISTS(SD_DETECT) - else { - card.release(); - if (old_sd_status != 2) { - set_status_P(GET_TEXT(MSG_MEDIA_REMOVED)); - #if HAS_LCD_MENU - return_to_status(); - #endif - } - } - - #if DISABLED(NO_LCD_REINIT) - init_lcd(); // May revive the LCD if static electricity killed it - #endif - - #endif - - refresh(); - - ms = millis(); - next_lcd_update_ms = ms + LCD_UPDATE_INTERVAL; // delay LCD update until after SD activity completes - - #ifdef LED_BACKLIGHT_TIMEOUT - leds.reset_timeout(ms); - #endif - } - - #endif // INIT_SDCARD_ON_BOOT - if (ELAPSED(ms, next_lcd_update_ms) #if HAS_GRAPHICAL_LCD || drawing_screen @@ -1595,3 +1539,55 @@ void MarlinUI::update() { } #endif // !HAS_DISPLAY + +#if ENABLED(SDSUPPORT) + + void MarlinUI::media_changed(const uint8_t old_status, const uint8_t status) { + if (old_status == status) { + #if ENABLED(EXTENSIBLE_UI) + ExtUI::onMediaError(); // Failed to mount/unmount + #endif + return; + } + + if (status) { + #if ENABLED(EXTENSIBLE_UI) + ExtUI::onMediaInserted(); // ExtUI response + #endif + if (old_status < 2) + set_status_P(GET_TEXT(MSG_MEDIA_INSERTED)); + } + else { + #if ENABLED(EXTENSIBLE_UI) + ExtUI::onMediaRemoved(); // ExtUI response + #endif + if (old_status < 2) { + #if PIN_EXISTS(SD_DETECT) + set_status_P(GET_TEXT(MSG_MEDIA_REMOVED)); + #if HAS_LCD_MENU + return_to_status(); + #endif + #endif + } + } + + #if PIN_EXISTS(SD_DETECT) && DISABLED(NO_LCD_REINIT) + init_lcd(); // Revive a noisy shared SPI LCD + #endif + + refresh(); + + #if HAS_SPI_LCD || defined(LED_BACKLIGHT_TIMEOUT) + const millis_t ms = millis(); + #endif + + #if HAS_SPI_LCD + next_lcd_update_ms = ms + LCD_UPDATE_INTERVAL; // Delay LCD update for SD activity + #endif + + #ifdef LED_BACKLIGHT_TIMEOUT + leds.reset_timeout(ms); + #endif + } + +#endif // SDSUPPORT diff --git a/Marlin/src/lcd/ultralcd.h b/Marlin/src/lcd/ultralcd.h index 2737a1a64883..0be82ff1f687 100644 --- a/Marlin/src/lcd/ultralcd.h +++ b/Marlin/src/lcd/ultralcd.h @@ -274,6 +274,10 @@ class MarlinUI { // LCD implementations static void clear_lcd(); + #if ENABLED(SDSUPPORT) + static void media_changed(const uint8_t old_stat, const uint8_t stat); + #endif + #if HAS_SPI_LCD static bool detected(); static void init_lcd(); diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index 80e94b88b580..63607f7bbd89 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -378,6 +378,42 @@ void CardReader::mount() { ui.refresh(); } +/** + * Handle SD card events + */ +#if MB(FYSETC_CHEETAH) + #include "../module/stepper.h" +#endif + +void CardReader::manage_media() { + static uint8_t prev_stat = TERN(INIT_SDCARD_ON_BOOT, 2, 0); + uint8_t stat = uint8_t(IS_SD_INSERTED()); + if (stat != prev_stat && ui.detected()) { + + uint8_t old_stat = prev_stat; + prev_stat = stat; // Change now to prevent re-entry + + if (stat) { // Media Inserted + safe_delay(500); // Some boards need a delay to get settled + mount(); // Try to mount the media + #if MB(FYSETC_CHEETAH) + reset_stepper_drivers(); // Workaround for Cheetah bug + #endif + if (!isMounted()) stat = 0; // Not mounted? + } + else { + #if PIN_EXISTS(SD_DETECT) + release(); // Card is released + #endif + } + + ui.media_changed(old_stat, stat); // Update the UI + + if (stat && old_stat == 2) // First mount? + beginautostart(); // Look for autostart files soon + } +} + void CardReader::release() { endFilePrint(); flag.mounted = false; diff --git a/Marlin/src/sd/cardreader.h b/Marlin/src/sd/cardreader.h index 955a8b69b39e..1fee807495f5 100644 --- a/Marlin/src/sd/cardreader.h +++ b/Marlin/src/sd/cardreader.h @@ -73,6 +73,9 @@ class CardReader { static inline bool isMounted() { return flag.mounted; } static void ls(); + // Handle media insert/remove + static void manage_media(); + // SD Card Logging static void openLogFile(char * const path); static void write_command(char * const buf); From 723d4d6f610e922dbdc56e7f4f69e4a15ebb0fc8 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 4 Apr 2020 02:18:01 -0500 Subject: [PATCH 26/37] Fix Archim 2 build for PIO --- Marlin/Makefile | 2 +- Marlin/src/pins/pins.h | 2 +- platformio.ini | 19 +++++++++++++++++++ 3 files changed, 21 insertions(+), 2 deletions(-) diff --git a/Marlin/Makefile b/Marlin/Makefile index 0a9b3a45d708..33a787fb6403 100644 --- a/Marlin/Makefile +++ b/Marlin/Makefile @@ -686,7 +686,7 @@ ifeq ($(HARDWARE_VARIANT), Teensy) else ifeq ($(HARDWARE_VARIANT), archim) CDEFS += -DARDUINO_SAM_ARCHIM -DARDUINO_ARCH_SAM -D__SAM3X8E__ -DUSB_VID=0x27b1 -DUSB_PID=0x0001 -DUSBCON '-DUSB_MANUFACTURER="UltiMachine"' '-DUSB_PRODUCT="Archim"' - LIB_CXXSRC += variant.cpp IPAddress.cpp Reset.cpp RingBuffer.cpp Stream.cpp UARTClass.cpp USARTClass.cpp abi.cpp new.cpp watchdog.cpp CDC.cpp PluggableUSB.cpp USBCore.cpp + LIB_CXXSRC += variant.cpp IPAddress.cpp Reset.cpp RingBuffer.cpp Stream.cpp UARTClass.cpp USARTClass.cpp abi.cpp new.cpp watchdog.cpp CDC.cpp PluggableUSB.cpp USBCore.cpp LIB_SRC += cortex_handlers.c iar_calls_sam3.c syscalls_sam3.c dtostrf.c itoa.c ifeq ($(U8GLIB), 1) diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 5de75a1f0e64..a1095e23e221 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -454,7 +454,7 @@ #elif MB(ARCHIM1) #include "sam/pins_ARCHIM1.h" // SAM3X8E env:DUE env:DUE_debug #elif MB(ARCHIM2) - #include "sam/pins_ARCHIM2.h" // SAM3X8E env:DUE env:DUE_debug + #include "sam/pins_ARCHIM2.h" // SAM3X8E env:DUE_archim env:DUE_archim_debug #elif MB(ALLIGATOR) #include "sam/pins_ALLIGATOR_R2.h" // SAM3X8E env:DUE env:DUE_debug #elif MB(ADSK) diff --git a/platformio.ini b/platformio.ini index 4e801713a029..bf3dea01bc20 100644 --- a/platformio.ini +++ b/platformio.ini @@ -206,6 +206,25 @@ build_flags = ${common.build_flags} -funwind-tables -mpoke-function-name +# +# Archim SAM +# +[env:DUE_archim] +platform = atmelsam +board = due +src_filter = ${common.default_src_filter} + +build_flags = ${common.build_flags} + -DARDUINO_SAM_ARCHIM -DARDUINO_ARCH_SAM -D__SAM3X8E__ -DUSBCON + +[env:DUE_archim_debug] +# Used when WATCHDOG_RESET_MANUAL is enabled +platform = atmelsam +board = due +src_filter = ${common.default_src_filter} + +build_flags = ${common.build_flags} + -DARDUINO_SAM_ARCHIM -DARDUINO_ARCH_SAM -D__SAM3X8E__ -DUSBCON + -funwind-tables -mpoke-function-name + # # NXP LPC176x ARM Cortex-M3 # From 0e06aaa2bc5c58e018fcdd466ae8836ac0c38e13 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 3 Apr 2020 19:49:45 -0500 Subject: [PATCH 27/37] Add millis helper macros --- Marlin/src/MarlinCore.cpp | 4 ++-- Marlin/src/core/millis_t.h | 4 ++++ Marlin/src/feature/controllerfan.cpp | 2 +- Marlin/src/feature/pause.cpp | 4 ++-- Marlin/src/feature/power.cpp | 2 +- Marlin/src/gcode/calibrate/G76_M871.cpp | 2 +- Marlin/src/gcode/gcode.cpp | 2 +- Marlin/src/libs/stopwatch.cpp | 3 +-- Marlin/src/module/temperature.cpp | 24 ++++++++++++------------ Marlin/src/module/temperature.h | 2 +- 10 files changed, 26 insertions(+), 23 deletions(-) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index da3c6cbaa2ec..d05c9c601453 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -227,7 +227,7 @@ bool wait_for_heatup = true; // Inactivity shutdown millis_t max_inactive_time, // = 0 - stepper_inactive_time = (DEFAULT_STEPPER_DEACTIVE_TIME) * 1000UL; + stepper_inactive_time = SEC_TO_MS(DEFAULT_STEPPER_DEACTIVE_TIME); #if PIN_EXISTS(CHDK) extern millis_t chdk_timeout; @@ -543,7 +543,7 @@ inline void manage_inactivity(const bool ignore_stepper_queue=false) { #if ENABLED(EXTRUDER_RUNOUT_PREVENT) if (thermalManager.degHotend(active_extruder) > EXTRUDER_RUNOUT_MINTEMP - && ELAPSED(ms, gcode.previous_move_ms + (EXTRUDER_RUNOUT_SECONDS) * 1000UL) + && ELAPSED(ms, gcode.previous_move_ms + SEC_TO_MS(EXTRUDER_RUNOUT_SECONDS)) && !planner.has_blocks_queued() ) { #if ENABLED(SWITCHING_EXTRUDER) diff --git a/Marlin/src/core/millis_t.h b/Marlin/src/core/millis_t.h index 39ea17b9f0c8..bf0b0bb30899 100644 --- a/Marlin/src/core/millis_t.h +++ b/Marlin/src/core/millis_t.h @@ -25,5 +25,9 @@ typedef uint32_t millis_t; +#define SEC_TO_MS(N) millis_t((N)*1000UL) +#define MIN_TO_MS(N) SEC_TO_MS((N)*60UL) +#define MS_TO_SEC(N) millis_t((N)/1000UL) + #define PENDING(NOW,SOON) ((int32_t)(NOW-(SOON))<0) #define ELAPSED(NOW,SOON) (!PENDING(NOW,SOON)) diff --git a/Marlin/src/feature/controllerfan.cpp b/Marlin/src/feature/controllerfan.cpp index 074670040781..debfdea1f910 100644 --- a/Marlin/src/feature/controllerfan.cpp +++ b/Marlin/src/feature/controllerfan.cpp @@ -91,7 +91,7 @@ void ControllerFan::update() { // - If AutoMode is on and steppers have been enabled for CONTROLLERFAN_IDLE_TIME seconds. // - If System is on idle and idle fan speed settings is activated. set_fan_speed( - settings.auto_mode && lastMotorOn && PENDING(ms, lastMotorOn + settings.duration * 1000UL) + settings.auto_mode && lastMotorOn && PENDING(ms, lastMotorOn + SEC_TO_MS(settings.duration)) ? settings.active_speed : settings.idle_speed ); diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index 23fa2fee0187..259b13082227 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -485,7 +485,7 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep #endif // Start the heater idle timers - const millis_t nozzle_timeout = (millis_t)(PAUSE_PARK_NOZZLE_TIMEOUT) * 1000UL; + const millis_t nozzle_timeout = SEC_TO_MS(PAUSE_PARK_NOZZLE_TIMEOUT); HOTEND_LOOP() thermalManager.hotend_idle[e].start(nozzle_timeout); @@ -549,7 +549,7 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep show_continue_prompt(is_reload); // Start the heater idle timers - const millis_t nozzle_timeout = (millis_t)(PAUSE_PARK_NOZZLE_TIMEOUT) * 1000UL; + const millis_t nozzle_timeout = SEC_TO_MS(PAUSE_PARK_NOZZLE_TIMEOUT); HOTEND_LOOP() thermalManager.hotend_idle[e].start(nozzle_timeout); #if ENABLED(HOST_PROMPT_SUPPORT) diff --git a/Marlin/src/feature/power.cpp b/Marlin/src/feature/power.cpp index 1fa751811e61..510747d20801 100644 --- a/Marlin/src/feature/power.cpp +++ b/Marlin/src/feature/power.cpp @@ -98,7 +98,7 @@ void Power::check() { nextPowerCheck = ms + 2500UL; if (is_power_needed()) power_on(); - else if (!lastPowerOn || ELAPSED(ms, lastPowerOn + (POWER_TIMEOUT) * 1000UL)) + else if (!lastPowerOn || ELAPSED(ms, lastPowerOn + SEC_TO_MS(POWER_TIMEOUT))) power_off(); } } diff --git a/Marlin/src/gcode/calibrate/G76_M871.cpp b/Marlin/src/gcode/calibrate/G76_M871.cpp index c878f83a17f2..4bc27b82f5f9 100644 --- a/Marlin/src/gcode/calibrate/G76_M871.cpp +++ b/Marlin/src/gcode/calibrate/G76_M871.cpp @@ -182,7 +182,7 @@ void GcodeSuite::G76() { do_blocking_move_to(parkpos); // Wait for heatbed to reach target temp and probe to cool below target temp - if (wait_for_temps(target_bed, target_probe, next_temp_report, millis() + 900UL * 1000UL)) { + if (wait_for_temps(target_bed, target_probe, next_temp_report, millis() + MIN_TO_MS(15))) { SERIAL_ECHOLNPGM("!Bed heating timeout."); break; } diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index 0937a86bd225..57abc37b0df9 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -988,7 +988,7 @@ void GcodeSuite::process_subcommands_now(char * gcode) { break; } } - next_busy_signal_ms = ms + host_keepalive_interval * 1000UL; + next_busy_signal_ms = ms + SEC_TO_MS(host_keepalive_interval); } #endif // HOST_KEEPALIVE_FEATURE diff --git a/Marlin/src/libs/stopwatch.cpp b/Marlin/src/libs/stopwatch.cpp index 6b01158cb9a9..c75eb2da09ad 100644 --- a/Marlin/src/libs/stopwatch.cpp +++ b/Marlin/src/libs/stopwatch.cpp @@ -106,8 +106,7 @@ void Stopwatch::reset() { } millis_t Stopwatch::duration() { - return ((isRunning() ? millis() : stopTimestamp) - - startTimestamp) / 1000UL + accumulator; + return accumulator + MS_TO_SEC((isRunning() ? millis() : stopTimestamp) - startTimestamp); } #if ENABLED(DEBUG_STOPWATCH) diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index af2f1a10e8dd..f9f311635ef5 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -399,7 +399,7 @@ volatile bool Temperature::raw_temps_ready = false; const uint16_t watch_temp_period = GTV(WATCH_BED_TEMP_PERIOD, WATCH_TEMP_PERIOD); const uint8_t watch_temp_increase = GTV(WATCH_BED_TEMP_INCREASE, WATCH_TEMP_INCREASE); const float watch_temp_target = target - float(watch_temp_increase + GTV(TEMP_BED_HYSTERESIS, TEMP_HYSTERESIS) + 1); - millis_t temp_change_ms = next_temp_ms + watch_temp_period * 1000UL; + millis_t temp_change_ms = next_temp_ms + SEC_TO_MS(watch_temp_period); float next_watch_temp = 0.0; bool heated = false; #endif @@ -546,7 +546,7 @@ volatile bool Temperature::raw_temps_ready = false; if (!heated) { // If not yet reached target... if (current_temp > next_watch_temp) { // Over the watch temp? next_watch_temp = current_temp + watch_temp_increase; // - set the next temp to watch for - temp_change_ms = ms + watch_temp_period * 1000UL; // - move the expiration timer up + temp_change_ms = ms + SEC_TO_MS(watch_temp_period); // - move the expiration timer up if (current_temp > watch_temp_target) heated = true; // - Flag if target temperature reached } else if (ELAPSED(ms, temp_change_ms)) // Watch timer expired @@ -2051,7 +2051,7 @@ void Temperature::init() { #endif if (current >= tr_target_temperature[heater_index] - hysteresis_degc) { - sm.timer = millis() + period_seconds * 1000UL; + sm.timer = millis() + SEC_TO_MS(period_seconds); break; } else if (PENDING(millis(), sm.timer)) break; @@ -3124,7 +3124,7 @@ void Temperature::tick() { millis_t residency_start_ms = 0; bool first_loop = true; // Loop until the temperature has stabilized - #define TEMP_CONDITIONS (!residency_start_ms || PENDING(now, residency_start_ms + (TEMP_RESIDENCY_TIME) * 1000UL)) + #define TEMP_CONDITIONS (!residency_start_ms || PENDING(now, residency_start_ms + SEC_TO_MS(TEMP_RESIDENCY_TIME))) #else // Loop until the temperature is very close target #define TEMP_CONDITIONS (wants_to_cool ? isCoolingHotend(target_extruder) : isHeatingHotend(target_extruder)) @@ -3160,7 +3160,7 @@ void Temperature::tick() { #if TEMP_RESIDENCY_TIME > 0 SERIAL_ECHOPGM(" W:"); if (residency_start_ms) - SERIAL_ECHO(long((((TEMP_RESIDENCY_TIME) * 1000UL) - (now - residency_start_ms)) / 1000UL)); + SERIAL_ECHO(long((SEC_TO_MS(TEMP_RESIDENCY_TIME) - (now - residency_start_ms)) / 1000UL)); else SERIAL_CHAR('?'); #endif @@ -3185,7 +3185,7 @@ void Temperature::tick() { // Start the TEMP_RESIDENCY_TIME timer when we reach target temp for the first time. if (temp_diff < TEMP_WINDOW) { residency_start_ms = now; - if (first_loop) residency_start_ms += (TEMP_RESIDENCY_TIME) * 1000UL; + if (first_loop) residency_start_ms += SEC_TO_MS(TEMP_RESIDENCY_TIME); } } else if (temp_diff > TEMP_HYSTERESIS) { @@ -3247,7 +3247,7 @@ void Temperature::tick() { millis_t residency_start_ms = 0; bool first_loop = true; // Loop until the temperature has stabilized - #define TEMP_BED_CONDITIONS (!residency_start_ms || PENDING(now, residency_start_ms + (TEMP_BED_RESIDENCY_TIME) * 1000UL)) + #define TEMP_BED_CONDITIONS (!residency_start_ms || PENDING(now, residency_start_ms + SEC_TO_MS(TEMP_BED_RESIDENCY_TIME))) #else // Loop until the temperature is very close target #define TEMP_BED_CONDITIONS (wants_to_cool ? isCoolingBed() : isHeatingBed()) @@ -3284,7 +3284,7 @@ void Temperature::tick() { #if TEMP_BED_RESIDENCY_TIME > 0 SERIAL_ECHOPGM(" W:"); if (residency_start_ms) - SERIAL_ECHO(long((((TEMP_BED_RESIDENCY_TIME) * 1000UL) - (now - residency_start_ms)) / 1000UL)); + SERIAL_ECHO(long((SEC_TO_MS(TEMP_BED_RESIDENCY_TIME) - (now - residency_start_ms)) / 1000UL)); else SERIAL_CHAR('?'); #endif @@ -3309,7 +3309,7 @@ void Temperature::tick() { // Start the TEMP_BED_RESIDENCY_TIME timer when we reach target temp for the first time. if (temp_diff < TEMP_BED_WINDOW) { residency_start_ms = now; - if (first_loop) residency_start_ms += (TEMP_BED_RESIDENCY_TIME) * 1000UL; + if (first_loop) residency_start_ms += SEC_TO_MS(TEMP_BED_RESIDENCY_TIME); } } else if (temp_diff > TEMP_BED_HYSTERESIS) { @@ -3373,7 +3373,7 @@ void Temperature::tick() { millis_t residency_start_ms = 0; bool first_loop = true; // Loop until the temperature has stabilized - #define TEMP_CHAMBER_CONDITIONS (!residency_start_ms || PENDING(now, residency_start_ms + (TEMP_CHAMBER_RESIDENCY_TIME) * 1000UL)) + #define TEMP_CHAMBER_CONDITIONS (!residency_start_ms || PENDING(now, residency_start_ms + SEC_TO_MS(TEMP_CHAMBER_RESIDENCY_TIME))) #else // Loop until the temperature is very close target #define TEMP_CHAMBER_CONDITIONS (wants_to_cool ? isCoolingChamber() : isHeatingChamber()) @@ -3405,7 +3405,7 @@ void Temperature::tick() { #if TEMP_CHAMBER_RESIDENCY_TIME > 0 SERIAL_ECHOPGM(" W:"); if (residency_start_ms) - SERIAL_ECHO(long((((TEMP_CHAMBER_RESIDENCY_TIME) * 1000UL) - (now - residency_start_ms)) / 1000UL)); + SERIAL_ECHO(long((SEC_TO_MS(TEMP_CHAMBER_RESIDENCY_TIME) - (now - residency_start_ms)) / 1000UL)); else SERIAL_CHAR('?'); #endif @@ -3425,7 +3425,7 @@ void Temperature::tick() { // Start the TEMP_CHAMBER_RESIDENCY_TIME timer when we reach target temp for the first time. if (temp_diff < TEMP_CHAMBER_WINDOW) { residency_start_ms = now; - if (first_loop) residency_start_ms += (TEMP_CHAMBER_RESIDENCY_TIME) * 1000UL; + if (first_loop) residency_start_ms += SEC_TO_MS(TEMP_CHAMBER_RESIDENCY_TIME); } } else if (temp_diff > TEMP_CHAMBER_HYSTERESIS) { diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index 24e005449667..cba1642afdbe 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -241,7 +241,7 @@ struct HeaterWatch { const int16_t newtarget = curr + INCREASE; if (newtarget < tgt - HYSTERESIS - 1) { target = newtarget; - next_ms = millis() + PERIOD * 1000UL; + next_ms = millis() + SEC_TO_MS(PERIOD); return; } } From da0f63cd1c854cf9018720ebaa3518e751f7a37f Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 5 Apr 2020 00:02:50 +0000 Subject: [PATCH 28/37] [cron] Bump distribution date (2020-04-05) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 74c38628c456..d24a9dbefaae 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-04-04" + #define STRING_DISTRIBUTION_DATE "2020-04-05" #endif /** From 8dd9afe4f9837df50d905b25197847928cefa087 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 2 Apr 2020 12:54:46 -0500 Subject: [PATCH 29/37] Better push in 'mfpub' --- buildroot/share/git/mfpub | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/buildroot/share/git/mfpub b/buildroot/share/git/mfpub index 8ec28ad489a1..53911d6d4e45 100755 --- a/buildroot/share/git/mfpub +++ b/buildroot/share/git/mfpub @@ -67,11 +67,11 @@ if [[ $BRANCH == $TARG ]]; then # Allow working directly with the main fork echo echo -n "Pushing to origin/$TARG... " - git push -f origin + git push origin HEAD:$TARG echo echo -n "Pushing to upstream/$TARG... " - git push -f upstream + git push upstream HEAD:$TARG else From 86a3efda6f1363ada61f3a6c1f469af18bc8576e Mon Sep 17 00:00:00 2001 From: Giuliano Zaro <3684609+GMagician@users.noreply.github.com> Date: Sun, 5 Apr 2020 03:51:05 +0200 Subject: [PATCH 30/37] Update Italian language (#17407) --- Marlin/src/lcd/language/language_it.h | 15 ++++++++++++--- 1 file changed, 12 insertions(+), 3 deletions(-) diff --git a/Marlin/src/lcd/language/language_it.h b/Marlin/src/lcd/language/language_it.h index 8d8112d523f1..c7f0585df523 100644 --- a/Marlin/src/lcd/language/language_it.h +++ b/Marlin/src/lcd/language/language_it.h @@ -88,6 +88,7 @@ namespace Language_it { PROGMEM Language_Str MSG_PREHEAT_2_SETTINGS = _UxGT("Preris.") PREHEAT_2_LABEL _UxGT(" conf"); PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("Prerisc.personal."); PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Raffredda"); + PROGMEM Language_Str MSG_CUTTER_FREQUENCY = _UxGT("Frequenza"); PROGMEM Language_Str MSG_LASER_MENU = _UxGT("Controllo laser"); PROGMEM Language_Str MSG_LASER_OFF = _UxGT("Laser Off"); PROGMEM Language_Str MSG_LASER_ON = _UxGT("Laser On"); @@ -349,7 +350,8 @@ namespace Language_it { PROGMEM Language_Str MSG_USERWAIT = _UxGT("Premi tasto.."); PROGMEM Language_Str MSG_PRINT_PAUSED = _UxGT("Stampa sospesa"); PROGMEM Language_Str MSG_PRINTING = _UxGT("Stampa..."); - PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("Stampa annullata"); + PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("Stampa Annullata"); + PROGMEM Language_Str MSG_PRINT_DONE = _UxGT("Stampa Eseguita"); PROGMEM Language_Str MSG_NO_MOVE = _UxGT("Nessun Movimento"); PROGMEM Language_Str MSG_KILLED = _UxGT("UCCISO. "); PROGMEM Language_Str MSG_STOPPED = _UxGT("ARRESTATO. "); @@ -368,6 +370,7 @@ namespace Language_it { PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Risalita Z"); PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPD = _UxGT("Velocità innesco"); PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPD = _UxGT("Velocità retrazione"); + PROGMEM Language_Str MSG_NOZZLE_PARKED = _UxGT("Ugello Parcheggiato"); PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Standby ugello"); PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Cambia filamento"); PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Cambia filamento *"); @@ -581,7 +584,7 @@ namespace Language_it { PROGMEM Language_Str MSG_TMC_DRIVERS = _UxGT("Drivers TMC"); PROGMEM Language_Str MSG_TMC_CURRENT = _UxGT("Driver in uso"); PROGMEM Language_Str MSG_TMC_HYBRID_THRS = _UxGT("Soglia modo ibrido"); - PROGMEM Language_Str MSG_TMC_HOMING_THRS = _UxGT("Azzer. sensorless"); + PROGMEM Language_Str MSG_TMC_HOMING_THRS = _UxGT("Azzer. senza sens."); PROGMEM Language_Str MSG_TMC_STEPPING_MODE = _UxGT("Modo stepping"); PROGMEM Language_Str MSG_TMC_STEALTH_ENABLED = _UxGT("StealthChop abil."); @@ -593,5 +596,11 @@ namespace Language_it { PROGMEM Language_Str MSG_BACKLASH_B = LCD_STR_B; PROGMEM Language_Str MSG_BACKLASH_C = LCD_STR_C; PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Correzione"); - PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Smoothing"); + PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Appianamento"); + + PROGMEM Language_Str MSG_LEVEL_X_AXIS = _UxGT("Livello asse X"); + PROGMEM Language_Str MSG_AUTO_CALIBRATE = _UxGT("Auto Calibra"); + PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Timeout riscaldatore"); + PROGMEM Language_Str MSG_REHEAT = _UxGT("Riscalda"); + PROGMEM Language_Str MSG_REHEATING = _UxGT("Riscaldando..."); } From 07b3f38269c605fb79eab53516ddaef33155fb05 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 4 Apr 2020 23:51:11 -0500 Subject: [PATCH 31/37] First SD status change is silent --- Marlin/src/lcd/ultralcd.cpp | 15 ++++++++------- 1 file changed, 8 insertions(+), 7 deletions(-) diff --git a/Marlin/src/lcd/ultralcd.cpp b/Marlin/src/lcd/ultralcd.cpp index 10a717b6fe2e..08597451a0ba 100644 --- a/Marlin/src/lcd/ultralcd.cpp +++ b/Marlin/src/lcd/ultralcd.cpp @@ -1551,17 +1551,18 @@ void MarlinUI::update() { } if (status) { - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMediaInserted(); // ExtUI response - #endif - if (old_status < 2) + if (old_status < 2) { + #if ENABLED(EXTENSIBLE_UI) + ExtUI::onMediaInserted(); // ExtUI response + #endif set_status_P(GET_TEXT(MSG_MEDIA_INSERTED)); + } } else { - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMediaRemoved(); // ExtUI response - #endif if (old_status < 2) { + #if ENABLED(EXTENSIBLE_UI) + ExtUI::onMediaRemoved(); // ExtUI response + #endif #if PIN_EXISTS(SD_DETECT) set_status_P(GET_TEXT(MSG_MEDIA_REMOVED)); #if HAS_LCD_MENU From fad9235cd80f2acdf1c0658d9633857fad94edea Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 5 Apr 2020 18:24:50 -0500 Subject: [PATCH 32/37] Move MSG_x_LINE to multi_language.h --- Marlin/src/core/multi_language.h | 4 ++++ Marlin/src/lcd/language/language_en.h | 4 ---- Marlin/src/lcd/language/language_pl.h | 4 ---- Marlin/src/lcd/language/language_tr.h | 4 ---- Marlin/src/lcd/language/language_zh_TW.h | 4 ---- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h | 6 ++++-- 6 files changed, 8 insertions(+), 18 deletions(-) diff --git a/Marlin/src/core/multi_language.h b/Marlin/src/core/multi_language.h index 98020b1e8d9c..ce8ce94fdc46 100644 --- a/Marlin/src/core/multi_language.h +++ b/Marlin/src/core/multi_language.h @@ -77,3 +77,7 @@ typedef const char Language_Str[]; #define GET_TEXT_F(MSG) (const __FlashStringHelper*)GET_TEXT(MSG) #define MSG_CONCAT(A,B) pgm_p_pair_t(GET_TEXT(A),GET_TEXT(B)) + +#define MSG_1_LINE(A) A "\0" "\0" +#define MSG_2_LINE(A,B) A "\0" B "\0" +#define MSG_3_LINE(A,B,C) A "\0" B "\0" C diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index 0aea571caabf..2037d0c928d9 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -557,10 +557,6 @@ namespace Language_en { PROGMEM Language_Str MSG_SNAKE = _UxGT("Sn4k3"); PROGMEM Language_Str MSG_MAZE = _UxGT("Maze"); - #define MSG_1_LINE(A) A "\0" "\0" - #define MSG_2_LINE(A,B) A "\0" B "\0" - #define MSG_3_LINE(A,B,C) A "\0" B "\0" C - // // Filament Change screens show up to 3 lines on a 4-line display // ...or up to 2 lines on a 3-line display diff --git a/Marlin/src/lcd/language/language_pl.h b/Marlin/src/lcd/language/language_pl.h index 113c58629f10..9fefeb6ee0f2 100644 --- a/Marlin/src/lcd/language/language_pl.h +++ b/Marlin/src/lcd/language/language_pl.h @@ -523,10 +523,6 @@ namespace Language_pl { PROGMEM Language_Str MSG_SNAKE = _UxGT("Sn4k3"); PROGMEM Language_Str MSG_MAZE = _UxGT("Maze"); - #define MSG_1_LINE(A) A "\0" "\0" - #define MSG_2_LINE(A,B) A "\0" B "\0" - #define MSG_3_LINE(A,B,C) A "\0" B "\0" C - // // Filament Change screens show up to 3 lines on a 4-line display // ...or up to 2 lines on a 3-line display diff --git a/Marlin/src/lcd/language/language_tr.h b/Marlin/src/lcd/language/language_tr.h index 096fef254cf2..515f4d0037f5 100644 --- a/Marlin/src/lcd/language/language_tr.h +++ b/Marlin/src/lcd/language/language_tr.h @@ -549,10 +549,6 @@ namespace Language_tr { PROGMEM Language_Str MSG_SNAKE = _UxGT("Sn4k3"); PROGMEM Language_Str MSG_MAZE = _UxGT("Maze"); - #define MSG_1_LINE(A) A "\0" "\0" - #define MSG_2_LINE(A,B) A "\0" B "\0" - #define MSG_3_LINE(A,B,C) A "\0" B "\0" C - // // Filament Değişim ekranları 4 satırlı ekranda 3 satıra kadar gösterilir // ...veya 3 satırlı ekranda 2 satıra kadar diff --git a/Marlin/src/lcd/language/language_zh_TW.h b/Marlin/src/lcd/language/language_zh_TW.h index 06b19440f281..053a90d5860b 100644 --- a/Marlin/src/lcd/language/language_zh_TW.h +++ b/Marlin/src/lcd/language/language_zh_TW.h @@ -546,10 +546,6 @@ namespace Language_zh_TW { PROGMEM Language_Str MSG_SNAKE = _UxGT("Sn4k3"); PROGMEM Language_Str MSG_MAZE = _UxGT("Maze"); - #define MSG_1_LINE(A) A "\0" "\0" - #define MSG_2_LINE(A,B) A "\0" B "\0" - #define MSG_3_LINE(A,B,C) A "\0" B "\0" C - // // Filament Change screens show up to 3 lines on a 4-line display // ...or up to 2 lines on a 3-line display diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h index 1d1ad60f2474..c4226001e67a 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h @@ -26,8 +26,10 @@ // // EEPROM // -#define FLASH_EEPROM_EMULATION -//#define SDCARD_EEPROM_EMULATION +#if NONE(FLASH_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) + #define FLASH_EEPROM_EMULATION + //#define SDCARD_EEPROM_EMULATION +#endif /** * Trinamic Stallguard pins From c47feb1cfe95c10b7166ef12d94c7e5b1b615846 Mon Sep 17 00:00:00 2001 From: Brais Fortes Date: Mon, 6 Apr 2020 01:36:27 +0200 Subject: [PATCH 33/37] Update Galician language (#17418) --- Marlin/src/core/language.h | 2 +- Marlin/src/lcd/language/language_gl.h | 518 ++++++++++++++++++++++---- 2 files changed, 455 insertions(+), 65 deletions(-) diff --git a/Marlin/src/core/language.h b/Marlin/src/core/language.h index f58ace77091b..a166de59cae6 100644 --- a/Marlin/src/core/language.h +++ b/Marlin/src/core/language.h @@ -185,7 +185,7 @@ #define STR_INVALID_POS_SLOT "Invalid slot. Total: " #define STR_SD_CANT_OPEN_SUBDIR "Cannot open subdir " -#define STR_SD_INIT_FAIL "SD init fail" +#define STR_SD_INIT_FAIL "No SD card" #define STR_SD_VOL_INIT_FAIL "volume.init failed" #define STR_SD_OPENROOT_FAIL "openRoot failed" #define STR_SD_CARD_OK "SD card ok" diff --git a/Marlin/src/lcd/language/language_gl.h b/Marlin/src/lcd/language/language_gl.h index 6a8f166ff19c..c40c0c1f7d52 100644 --- a/Marlin/src/lcd/language/language_gl.h +++ b/Marlin/src/lcd/language/language_gl.h @@ -39,22 +39,39 @@ namespace Language_gl { PROGMEM Language_Str LANGUAGE = _UxGT("Galician"); PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT(" lista."); + PROGMEM Language_Str MSG_MARLIN = _UxGT("Marlin"); + PROGMEM Language_Str MSG_YES = _UxGT("SI"); + PROGMEM Language_Str MSG_NO = _UxGT("NON"); + PROGMEM Language_Str MSG_BACK = _UxGT("Atrás"); + PROGMEM Language_Str MSG_MEDIA_ABORTING = _UxGT("Cancelando..."); PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("Tarxeta inserida"); PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Tarxeta retirada"); + PROGMEM Language_Str MSG_MEDIA_RELEASED = _UxGT("SD/USB lanzado"); + PROGMEM Language_Str MSG_MEDIA_WAITING = _UxGT("Agardando ao SD/USB"); + PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("Erro lectura SD/USB"); + PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("Disp. USB retirado"); + PROGMEM Language_Str MSG_MEDIA_USB_FAILED = _UxGT("Inicio USB fallido"); PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("FinCarro"); - PROGMEM Language_Str MSG_MAIN = _UxGT("Menu principal"); + PROGMEM Language_Str MSG_LCD_SOFT_ENDSTOPS = _UxGT("FinCarro SW"); + PROGMEM Language_Str MSG_MAIN = _UxGT("Menú principal"); + PROGMEM Language_Str MSG_ADVANCED_SETTINGS = _UxGT("Axustes avanzados"); + PROGMEM Language_Str MSG_CONFIGURATION = _UxGT("Configuración"); PROGMEM Language_Str MSG_AUTOSTART = _UxGT("Autoarranque"); PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Apagar motores"); + PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Menú depuración"); + PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Test barra progreso"); PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("Ir a orixe"); PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Ir orixe X"); PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Ir orixe Y"); PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Ir orixe Z"); + PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Autoaliñar Z"); PROGMEM Language_Str MSG_LEVEL_BED_HOMING = _UxGT("Ir orixes XYZ"); PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("Prema pulsador"); PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("Seguinte punto"); - PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("Nivelado feito"); - PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Offsets na orixe"); - PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Offsets fixados"); + PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("Fin Nivelación!"); + PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("Compensación Altura"); + PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Axustar Desfases"); + PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Desfases aplicados"); PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Fixar orixe"); PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Prequentar ") PREHEAT_1_LABEL; PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Prequentar ") PREHEAT_1_LABEL " ~"; @@ -70,19 +87,151 @@ namespace Language_gl { PROGMEM Language_Str MSG_PREHEAT_2_ALL = _UxGT("Preque. ") PREHEAT_2_LABEL _UxGT(" Todo"); PROGMEM Language_Str MSG_PREHEAT_2_BEDONLY = _UxGT("Preque. ") PREHEAT_2_LABEL _UxGT(" Cama"); PROGMEM Language_Str MSG_PREHEAT_2_SETTINGS = _UxGT("Preque. ") PREHEAT_2_LABEL _UxGT(" conf"); + PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("Preque. Personali."); PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Arrefriar"); + PROGMEM Language_Str MSG_CUTTER_FREQUENCY = _UxGT("Frecuencia"); + PROGMEM Language_Str MSG_LASER_MENU = _UxGT("Control Láser"); + PROGMEM Language_Str MSG_LASER_OFF = _UxGT("Láser Apagado"); + PROGMEM Language_Str MSG_LASER_ON = _UxGT("Láser Aceso"); + PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Potencia Láser"); + PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Control Fuso"); + PROGMEM Language_Str MSG_SPINDLE_OFF = _UxGT("Fuso Apagado"); + PROGMEM Language_Str MSG_SPINDLE_ON = _UxGT("Fuso Aceso"); + PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Potencia Fuso"); + PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("Inverter xiro"); PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Acender"); PROGMEM Language_Str MSG_SWITCH_PS_OFF = _UxGT("Apagar"); - PROGMEM Language_Str MSG_EXTRUDE = _UxGT("Extrudir"); + PROGMEM Language_Str MSG_EXTRUDE = _UxGT("Extruír"); PROGMEM Language_Str MSG_RETRACT = _UxGT("Retraer"); PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Mover eixe"); - PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Nivelar cama"); - PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Nivelar cama"); + PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Nivelando Cama"); + PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Nivelar Cama"); + PROGMEM Language_Str MSG_LEVEL_CORNERS = _UxGT("Nivelar Cantos"); + PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Seguinte Canto"); + PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Editor Mallado"); + PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Editar Mallado"); + PROGMEM Language_Str MSG_EDITING_STOPPED = _UxGT("Ed. Mallado Detida"); + PROGMEM Language_Str MSG_PROBING_MESH = _UxGT("Punto de Proba"); + PROGMEM Language_Str MSG_MESH_X = _UxGT("Índice X"); + PROGMEM Language_Str MSG_MESH_Y = _UxGT("Índice Y"); + PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Valor Z"); + PROGMEM Language_Str MSG_USER_MENU = _UxGT("Comandos Personaliz."); + PROGMEM Language_Str MSG_M48_TEST = _UxGT("M48 Probar Sonda"); + PROGMEM Language_Str MSG_M48_POINT = _UxGT("M48 Punto"); + PROGMEM Language_Str MSG_M48_DEVIATION = _UxGT("Desviación"); + PROGMEM Language_Str MSG_IDEX_MENU = _UxGT("Modo IDEX"); + PROGMEM Language_Str MSG_OFFSETS_MENU = _UxGT("Ferramentas Compens"); + PROGMEM Language_Str MSG_IDEX_MODE_AUTOPARK = _UxGT("Auto-Estacionar"); + PROGMEM Language_Str MSG_IDEX_MODE_DUPLICATE = _UxGT("Duplicación"); + PROGMEM Language_Str MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Copia Espello"); + PROGMEM Language_Str MSG_IDEX_MODE_FULL_CTRL = _UxGT("Control Total"); + PROGMEM Language_Str MSG_HOTEND_OFFSET_X = _UxGT("2º Bico X"); + PROGMEM Language_Str MSG_HOTEND_OFFSET_Y = _UxGT("2º Bico Y"); + PROGMEM Language_Str MSG_HOTEND_OFFSET_Z = _UxGT("2º Bico Z"); + PROGMEM Language_Str MSG_UBL_DOING_G29 = _UxGT("Executando G29"); + PROGMEM Language_Str MSG_UBL_TOOLS = _UxGT("Ferramentas UBL"); + PROGMEM Language_Str MSG_UBL_LEVEL_BED = _UxGT("Unified Bed Leveling"); + PROGMEM Language_Str MSG_LCD_TILTING_MESH = _UxGT("Punto de inclinación"); + PROGMEM Language_Str MSG_UBL_MANUAL_MESH = _UxGT("Facer Malla Manual"); + PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Colocar Calzo e Medir"); + PROGMEM Language_Str MSG_UBL_BC_INSERT2 = _UxGT("Medir"); + PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Quitar e Medir Cama"); + PROGMEM Language_Str MSG_UBL_MOVING_TO_NEXT = _UxGT("Mover ao Seguinte"); + PROGMEM Language_Str MSG_UBL_ACTIVATE_MESH = _UxGT("Activar UBL"); + PROGMEM Language_Str MSG_UBL_DEACTIVATE_MESH = _UxGT("Desactivar UBL"); + PROGMEM Language_Str MSG_UBL_SET_TEMP_BED = _UxGT("Temp Cama"); + PROGMEM Language_Str MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Temp Cama"); + PROGMEM Language_Str MSG_UBL_SET_TEMP_HOTEND = _UxGT("Temp Bico"); + PROGMEM Language_Str MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Temp Bico"); + PROGMEM Language_Str MSG_UBL_MESH_EDIT = _UxGT("Editar Malla"); + PROGMEM Language_Str MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Edit. Malla Person."); + PROGMEM Language_Str MSG_UBL_FINE_TUNE_MESH = _UxGT("Axuste Fino da Malla"); + PROGMEM Language_Str MSG_UBL_DONE_EDITING_MESH = _UxGT("Fin Edición da Malla"); + PROGMEM Language_Str MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Crear Malla Person."); + PROGMEM Language_Str MSG_UBL_BUILD_MESH_MENU = _UxGT("Crear Malla"); + PROGMEM Language_Str MSG_UBL_BUILD_MESH_M1 = _UxGT("Crear Malla (") PREHEAT_1_LABEL _UxGT(")"); + PROGMEM Language_Str MSG_UBL_BUILD_MESH_M2 = _UxGT("Crear Malla (") PREHEAT_2_LABEL _UxGT(")"); + PROGMEM Language_Str MSG_UBL_BUILD_COLD_MESH = _UxGT("Crear Malla Fría"); + PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Axustar Altura Malla"); + PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Altura"); + PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Validar Malla"); + PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M1 = _UxGT("Validar Malla (") PREHEAT_1_LABEL _UxGT(")"); + PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M2 = _UxGT("Validar Malla (") PREHEAT_2_LABEL _UxGT(")"); + PROGMEM Language_Str MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Validar Malla perso."); + PROGMEM Language_Str MSG_G26_HEATING_BED = _UxGT("G26 Quentando Cama"); + PROGMEM Language_Str MSG_G26_HEATING_NOZZLE = _UxGT("G26 Quentando Bico"); + PROGMEM Language_Str MSG_G26_MANUAL_PRIME = _UxGT("Traballo manual..."); + PROGMEM Language_Str MSG_G26_FIXED_LENGTH = _UxGT("Traballo Lonxit Fixa"); + PROGMEM Language_Str MSG_G26_PRIME_DONE = _UxGT("Fin Traballo"); + PROGMEM Language_Str MSG_G26_CANCELED = _UxGT("G26 Cancelado"); + PROGMEM Language_Str MSG_G26_LEAVING = _UxGT("Saíndo de G26"); + PROGMEM Language_Str MSG_UBL_CONTINUE_MESH = _UxGT("Continuar Malla"); + PROGMEM Language_Str MSG_UBL_MESH_LEVELING = _UxGT("Nivelación Malla"); + PROGMEM Language_Str MSG_UBL_3POINT_MESH_LEVELING = _UxGT("Nivelación 3Puntos"); + PROGMEM Language_Str MSG_UBL_GRID_MESH_LEVELING = _UxGT("Nivelación Grid"); + PROGMEM Language_Str MSG_UBL_MESH_LEVEL = _UxGT("Nivelar Malla"); + PROGMEM Language_Str MSG_UBL_SIDE_POINTS = _UxGT("Puntos Laterais"); + PROGMEM Language_Str MSG_UBL_MAP_TYPE = _UxGT("Tipo de Mapa "); + PROGMEM Language_Str MSG_UBL_OUTPUT_MAP = _UxGT("Gardar Mapa"); + PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_HOST = _UxGT("Enviar ao Host"); + PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_CSV = _UxGT("Gardar en CSV"); + PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Backup Externo"); + PROGMEM Language_Str MSG_UBL_INFO_UBL = _UxGT("Info do UBL"); + PROGMEM Language_Str MSG_UBL_FILLIN_AMOUNT = _UxGT("Cantidade de Recheo"); + PROGMEM Language_Str MSG_UBL_MANUAL_FILLIN = _UxGT("Recheo Manual"); + PROGMEM Language_Str MSG_UBL_SMART_FILLIN = _UxGT("Recheo Intelixente"); + PROGMEM Language_Str MSG_UBL_FILLIN_MESH = _UxGT("Recheo da Malla"); + PROGMEM Language_Str MSG_UBL_INVALIDATE_ALL = _UxGT("Invalidar todo"); + PROGMEM Language_Str MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Invalidar cercanos"); + PROGMEM Language_Str MSG_UBL_FINE_TUNE_ALL = _UxGT("Axustar Fino Todo"); + PROGMEM Language_Str MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Axustar Fino Cerc"); + PROGMEM Language_Str MSG_UBL_STORAGE_MESH_MENU = _UxGT("Almacenamento Malla"); + PROGMEM Language_Str MSG_UBL_STORAGE_SLOT = _UxGT("Rañura Memoria"); + PROGMEM Language_Str MSG_UBL_LOAD_MESH = _UxGT("Cargar Malla Cama"); + PROGMEM Language_Str MSG_UBL_SAVE_MESH = _UxGT("Gardar Malla Cama"); + PROGMEM Language_Str MSG_MESH_LOADED = _UxGT("M117 Malla %i Cargada"); + PROGMEM Language_Str MSG_MESH_SAVED = _UxGT("M117 Malla %i Gardada"); + PROGMEM Language_Str MSG_UBL_NO_STORAGE = _UxGT("Sen Gardar"); + PROGMEM Language_Str MSG_UBL_SAVE_ERROR = _UxGT("Erro: Gardadado UBL"); + PROGMEM Language_Str MSG_UBL_RESTORE_ERROR = _UxGT("Erro: Recuperación UBL"); + PROGMEM Language_Str MSG_UBL_Z_OFFSET = _UxGT("Desfase de Z: "); + PROGMEM Language_Str MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Desfase de Z Detido"); + PROGMEM Language_Str MSG_UBL_STEP_BY_STEP_MENU = _UxGT("UBL Paso a Paso"); + PROGMEM Language_Str MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1. Crear Malla Fría"); + PROGMEM Language_Str MSG_UBL_2_SMART_FILLIN = _UxGT("2. Recheo Intelixente"); + PROGMEM Language_Str MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3. Validar Malla"); + PROGMEM Language_Str MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4. Axustar Fino Todo"); + PROGMEM Language_Str MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5. Validar Malla"); + PROGMEM Language_Str MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6. Axustar Fino Todo"); + PROGMEM Language_Str MSG_UBL_7_SAVE_MESH = _UxGT("7. Gardar Malla Cama"); + + PROGMEM Language_Str MSG_LED_CONTROL = _UxGT("Control LED"); + PROGMEM Language_Str MSG_LEDS = _UxGT("Luces"); + PROGMEM Language_Str MSG_LED_PRESETS = _UxGT("Axustes Luz"); + PROGMEM Language_Str MSG_SET_LEDS_RED = _UxGT("Vermello"); + PROGMEM Language_Str MSG_SET_LEDS_ORANGE = _UxGT("Laranxa"); + PROGMEM Language_Str MSG_SET_LEDS_YELLOW = _UxGT("Amarelo"); + PROGMEM Language_Str MSG_SET_LEDS_GREEN = _UxGT("Verde"); + PROGMEM Language_Str MSG_SET_LEDS_BLUE = _UxGT("Azul"); + PROGMEM Language_Str MSG_SET_LEDS_INDIGO = _UxGT("Índigo"); + PROGMEM Language_Str MSG_SET_LEDS_VIOLET = _UxGT("Violeta"); + PROGMEM Language_Str MSG_SET_LEDS_WHITE = _UxGT("Branco"); + PROGMEM Language_Str MSG_SET_LEDS_DEFAULT = _UxGT("Por defecto"); + PROGMEM Language_Str MSG_CUSTOM_LEDS = _UxGT("Luces personalizadas"); + PROGMEM Language_Str MSG_INTENSITY_R = _UxGT("Intensidade Vermello"); + PROGMEM Language_Str MSG_INTENSITY_G = _UxGT("Intensidade Verde"); + PROGMEM Language_Str MSG_INTENSITY_B = _UxGT("Intensidade Azul"); + PROGMEM Language_Str MSG_INTENSITY_W = _UxGT("Intensidade Branco"); + PROGMEM Language_Str MSG_LED_BRIGHTNESS = _UxGT("Brillo"); + + PROGMEM Language_Str MSG_MOVING = _UxGT("Movendo..."); + PROGMEM Language_Str MSG_FREE_XY = _UxGT("Libre XY"); PROGMEM Language_Str MSG_MOVE_X = _UxGT("Mover X"); PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Mover Y"); PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Mover Z"); PROGMEM Language_Str MSG_MOVE_E = _UxGT("Extrusor"); PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Extrusor *"); + PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Bico moi frío"); PROGMEM Language_Str MSG_MOVE_Z_DIST = _UxGT("Mover %smm"); PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Mover 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Mover 1mm"); @@ -91,17 +240,66 @@ namespace Language_gl { PROGMEM Language_Str MSG_BED_Z = _UxGT("Cama Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Bico"); PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Bico ~"); + PROGMEM Language_Str MSG_NOZZLE_PARKED = _UxGT("Bico Estacionado"); + PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Bico Standby"); PROGMEM Language_Str MSG_BED = _UxGT("Cama"); - PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Velocidade vent."); - PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Velocidade vent. ~"); + PROGMEM Language_Str MSG_CHAMBER = _UxGT("Cámara"); + PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Vel. Ventilador"); + PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Vel. Ventilador ~"); + PROGMEM Language_Str MSG_STORED_FAN_N = _UxGT("Ventilador Mem. ~"); + PROGMEM Language_Str MSG_EXTRA_FAN_SPEED = _UxGT("Vel. Vent. Extra"); + PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("Vel. Vent. Extra ~"); + PROGMEM Language_Str MSG_CONTROLLER_FAN = _UxGT("Controlador Vent."); + PROGMEM Language_Str MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("Velocidade Repouso"); + PROGMEM Language_Str MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Modo Auto"); + PROGMEM Language_Str MSG_CONTROLLER_FAN_SPEED = _UxGT("Velocidade Activa"); + PROGMEM Language_Str MSG_CONTROLLER_FAN_DURATION = _UxGT("Tempo Repouso"); PROGMEM Language_Str MSG_FLOW = _UxGT("Fluxo"); PROGMEM Language_Str MSG_FLOW_N = _UxGT("Fluxo ~"); + PROGMEM Language_Str MSG_CONTROL = _UxGT("Control"); PROGMEM Language_Str MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min"); PROGMEM Language_Str MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Max"); PROGMEM Language_Str MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Fact"); + PROGMEM Language_Str MSG_AUTOTEMP = _UxGT("Temperatura Auto."); + PROGMEM Language_Str MSG_LCD_ON = _UxGT("Acender"); + PROGMEM Language_Str MSG_LCD_OFF = _UxGT("Apagar"); + PROGMEM Language_Str MSG_PID_AUTOTUNE = _UxGT("Auto-Sint. PID"); + PROGMEM Language_Str MSG_PID_AUTOTUNE_E = _UxGT("Auto-Sint. PID *"); + PROGMEM Language_Str MSG_PID_P = _UxGT("PID-P"); + PROGMEM Language_Str MSG_PID_P_E = _UxGT("PID-P *"); + PROGMEM Language_Str MSG_PID_I = _UxGT("PID-I"); + PROGMEM Language_Str MSG_PID_I_E = _UxGT("PID-I *"); + PROGMEM Language_Str MSG_PID_D = _UxGT("PID-D"); + PROGMEM Language_Str MSG_PID_D_E = _UxGT("PID-D *"); + PROGMEM Language_Str MSG_PID_C = _UxGT("PID-C"); + PROGMEM Language_Str MSG_PID_C_E = _UxGT("PID-C *"); + PROGMEM Language_Str MSG_PID_F = _UxGT("PID-F"); + PROGMEM Language_Str MSG_PID_F_E = _UxGT("PID-F *"); PROGMEM Language_Str MSG_SELECT = _UxGT("Escolla"); PROGMEM Language_Str MSG_SELECT_E = _UxGT("Escolla *"); PROGMEM Language_Str MSG_ACC = _UxGT("Acel"); + PROGMEM Language_Str MSG_JERK = _UxGT("Jerk"); + PROGMEM Language_Str MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-Jerk"); + PROGMEM Language_Str MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-Jerk"); + PROGMEM Language_Str MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-Jerk"); + PROGMEM Language_Str MSG_VE_JERK = _UxGT("Ve-Jerk"); + PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Desvío Unión"); + PROGMEM Language_Str MSG_VELOCITY = _UxGT("Velocidade"); + PROGMEM Language_Str MSG_VMAX_A = _UxGT("Vmax ") LCD_STR_A; + PROGMEM Language_Str MSG_VMAX_B = _UxGT("Vmax ") LCD_STR_B; + PROGMEM Language_Str MSG_VMAX_C = _UxGT("Vmax ") LCD_STR_C; + PROGMEM Language_Str MSG_VMAX_E = _UxGT("Vmax ") LCD_STR_E; + PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Vmax *"); + PROGMEM Language_Str MSG_VMIN = _UxGT("Vmin"); + PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("V-viaxe min"); + PROGMEM Language_Str MSG_ACCELERATION = _UxGT("Aceleración"); + PROGMEM Language_Str MSG_AMAX_A = _UxGT("Amax") LCD_STR_A; + PROGMEM Language_Str MSG_AMAX_B = _UxGT("Amax") LCD_STR_B; + PROGMEM Language_Str MSG_AMAX_C = _UxGT("Amax") LCD_STR_C; + PROGMEM Language_Str MSG_AMAX_E = _UxGT("Amax") LCD_STR_E; + PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Amax *"); + PROGMEM Language_Str MSG_A_RETRACT = _UxGT("A-retrac."); + PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("A-viaxe"); PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("Pasos/mm"); PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" pasos/mm"); PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" pasos/mm"); @@ -114,102 +312,294 @@ namespace Language_gl { PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E en mm³"); PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Diam. fil."); PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Diam. fil. *"); + PROGMEM Language_Str MSG_FILAMENT_UNLOAD = _UxGT("Descarga mm"); + PROGMEM Language_Str MSG_FILAMENT_LOAD = _UxGT("Carga mm"); + PROGMEM Language_Str MSG_ADVANCE_K = _UxGT("Avance K"); + PROGMEM Language_Str MSG_ADVANCE_K_E = _UxGT("Avance K *"); PROGMEM Language_Str MSG_CONTRAST = _UxGT("Constraste LCD"); - PROGMEM Language_Str MSG_STORE_EEPROM = _UxGT("Gardar en memo."); - PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Cargar de memo."); - PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("Cargar de firm."); - PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT("Volver a cargar"); - PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("Monitorizacion"); + PROGMEM Language_Str MSG_STORE_EEPROM = _UxGT("Gardar Configuración"); + PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Cargar Configuración"); + PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("Rest. Defecto"); + PROGMEM Language_Str MSG_INIT_EEPROM = _UxGT("Inicializar EEPROM"); + PROGMEM Language_Str MSG_ERR_EEPROM_CRC = _UxGT("Erro: CRC EEPROM"); + PROGMEM Language_Str MSG_ERR_EEPROM_INDEX = _UxGT("Erro: Índice EEPROM"); + PROGMEM Language_Str MSG_ERR_EEPROM_VERSION = _UxGT("Erro: Versión EEPROM"); + PROGMEM Language_Str MSG_MEDIA_UPDATE = _UxGT("Actualizar SD/USB"); + PROGMEM Language_Str MSG_RESET_PRINTER = _UxGT("Reiniciar Impresora"); + PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT("Recargar"); + PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("Información"); PROGMEM Language_Str MSG_PREPARE = _UxGT("Preparar"); PROGMEM Language_Str MSG_TUNE = _UxGT("Axustar"); - PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Pausar impres."); - PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Seguir impres."); - PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("Deter impres."); + PROGMEM Language_Str MSG_START_PRINT = _UxGT("Comezar impresión"); + PROGMEM Language_Str MSG_BUTTON_NEXT = _UxGT("Seguinte"); + PROGMEM Language_Str MSG_BUTTON_INIT = _UxGT("Comezar"); + PROGMEM Language_Str MSG_BUTTON_STOP = _UxGT("Deter"); + PROGMEM Language_Str MSG_BUTTON_PRINT = _UxGT("Imprimir"); + PROGMEM Language_Str MSG_BUTTON_RESET = _UxGT("Reiniciar"); + PROGMEM Language_Str MSG_BUTTON_CANCEL = _UxGT("Cancelar"); + PROGMEM Language_Str MSG_BUTTON_DONE = _UxGT("Listo"); + PROGMEM Language_Str MSG_BUTTON_BACK = _UxGT("Atrás"); + PROGMEM Language_Str MSG_BUTTON_PROCEED = _UxGT("Proceder"); + PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Pausar impresión"); + PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Retomar impresión"); + PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("Deter impresión"); + PROGMEM Language_Str MSG_PRINTING_OBJECT = _UxGT("Imprimindo Obxecto"); + PROGMEM Language_Str MSG_CANCEL_OBJECT = _UxGT("Cancelar Obxecto"); + PROGMEM Language_Str MSG_CANCEL_OBJECT_N = _UxGT("Cancelar Obxecto ="); + PROGMEM Language_Str MSG_OUTAGE_RECOVERY = _UxGT("Recuperar Impresión"); PROGMEM Language_Str MSG_MEDIA_MENU = _UxGT("Tarxeta SD"); PROGMEM Language_Str MSG_NO_MEDIA = _UxGT("Sen tarxeta SD"); PROGMEM Language_Str MSG_DWELL = _UxGT("En repouso..."); PROGMEM Language_Str MSG_USERWAIT = _UxGT("A espera..."); - PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("Impre. cancelada"); + PROGMEM Language_Str MSG_PRINT_PAUSED = _UxGT("Prema para Retomar"); + PROGMEM Language_Str MSG_PRINTING = _UxGT("Imprimindo..."); + PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("Impresión Cancelada"); + PROGMEM Language_Str MSG_PRINT_DONE = _UxGT("Fin Impresión"); PROGMEM Language_Str MSG_NO_MOVE = _UxGT("Sen movemento."); - PROGMEM Language_Str MSG_KILLED = _UxGT("PROGRAMA MORTO"); - PROGMEM Language_Str MSG_STOPPED = _UxGT("PROGRAMA PARADO"); - PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("Retraccion mm"); + PROGMEM Language_Str MSG_KILLED = _UxGT("MORTO."); + PROGMEM Language_Str MSG_STOPPED = _UxGT("DETIDO."); + PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("Retraer mm"); PROGMEM Language_Str MSG_CONTROL_RETRACT_SWAP = _UxGT("Cambio retra. mm"); - PROGMEM Language_Str MSG_CONTROL_RETRACTF = _UxGT("Retraccion V"); + PROGMEM Language_Str MSG_CONTROL_RETRACTF = _UxGT("Retraer V"); PROGMEM Language_Str MSG_CONTROL_RETRACT_ZHOP = _UxGT("Alzar Z mm"); PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER = _UxGT("Recup. retra. mm"); PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Cambio recup. mm"); PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Recuperacion V"); - PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("Retraccion auto."); - PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Cambiar filamen."); - PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Cambiar filamen. *"); - PROGMEM Language_Str MSG_ATTACH_MEDIA = _UxGT("Iniciando SD"); - PROGMEM Language_Str MSG_CHANGE_MEDIA = _UxGT("Cambiar SD"); - PROGMEM Language_Str MSG_ZPROBE_OUT = _UxGT("Sonda-Z sen cama"); - PROGMEM Language_Str MSG_BLTOUCH_SELFTEST = _UxGT("Comprobar BLTouch"); - PROGMEM Language_Str MSG_BLTOUCH_RESET = _UxGT("Iniciar BLTouch"); - PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Offset Z"); + PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("S UnRet V"); + PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("Auto-Retracción"); + PROGMEM Language_Str MSG_FILAMENT_SWAP_LENGTH = _UxGT("Lonxitude Retracción"); + PROGMEM Language_Str MSG_FILAMENT_PURGE_LENGTH = _UxGT("Lonxitude de Purga"); + PROGMEM Language_Str MSG_TOOL_CHANGE = _UxGT("Cambiar Ferramenta"); + PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Levantar Z"); + PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPD = _UxGT("Velocidade prim."); + PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPD = _UxGT("Vel. de Retracción"); + PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Cambiar Filamento"); + PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Cambiar Filamento *"); + PROGMEM Language_Str MSG_FILAMENTLOAD = _UxGT("Cargar Filamento"); + PROGMEM Language_Str MSG_FILAMENTLOAD_E = _UxGT("Cargar Filamento *"); + PROGMEM Language_Str MSG_FILAMENTUNLOAD = _UxGT("Descargar Filamento"); + PROGMEM Language_Str MSG_FILAMENTUNLOAD_E = _UxGT("Descargar Filamento *"); + PROGMEM Language_Str MSG_FILAMENTUNLOAD_ALL = _UxGT("Descargar Todo"); + PROGMEM Language_Str MSG_ATTACH_MEDIA = _UxGT("Iniciar SD/USB"); + PROGMEM Language_Str MSG_CHANGE_MEDIA = _UxGT("Cambiar SD/USB"); + PROGMEM Language_Str MSG_RELEASE_MEDIA = _UxGT("Lanzar SD/USB"); + PROGMEM Language_Str MSG_ZPROBE_OUT = _UxGT("Sonda-Z fóra Cama"); + PROGMEM Language_Str MSG_SKEW_FACTOR = _UxGT("Factor de Desviación"); + PROGMEM Language_Str MSG_BLTOUCH = _UxGT("BLTouch"); + PROGMEM Language_Str MSG_BLTOUCH_SELFTEST = _UxGT("Cmd: Auto-Test"); + PROGMEM Language_Str MSG_BLTOUCH_RESET = _UxGT("Cmd: Reiniciar"); + PROGMEM Language_Str MSG_BLTOUCH_STOW = _UxGT("Cmd: Recoller"); + PROGMEM Language_Str MSG_BLTOUCH_DEPLOY = _UxGT("Cmd: Estender"); + PROGMEM Language_Str MSG_BLTOUCH_SW_MODE = _UxGT("Cmd: Modo Software"); + PROGMEM Language_Str MSG_BLTOUCH_5V_MODE = _UxGT("Cmd: Modo 5V"); + PROGMEM Language_Str MSG_BLTOUCH_OD_MODE = _UxGT("Cmd: Modo OD"); + PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE = _UxGT("Cmd: Modo Almacenar"); + PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_5V = _UxGT("Axustar BLTouch a 5V"); + PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_OD = _UxGT("Axustar BLTouch a OD"); + PROGMEM Language_Str MSG_BLTOUCH_MODE_ECHO = _UxGT("Modo de Informe"); + PROGMEM Language_Str MSG_BLTOUCH_MODE_CHANGE = _UxGT("PERIGO: Unha mala configuración pode producir daños! Proceder igualmente?"); + PROGMEM Language_Str MSG_TOUCHMI_PROBE = _UxGT("TouchMI"); + PROGMEM Language_Str MSG_TOUCHMI_INIT = _UxGT("Iniciar TouchMI"); + PROGMEM Language_Str MSG_TOUCHMI_ZTEST = _UxGT("Test de Desfase Z"); + PROGMEM Language_Str MSG_TOUCHMI_SAVE = _UxGT("Gardar"); + PROGMEM Language_Str MSG_MANUAL_DEPLOY_TOUCHMI = _UxGT("Estender TouchMI"); + PROGMEM Language_Str MSG_MANUAL_DEPLOY = _UxGT("Estender Sonda Z"); + PROGMEM Language_Str MSG_MANUAL_STOW = _UxGT("Recoller Sonda Z"); + PROGMEM Language_Str MSG_HOME_FIRST = _UxGT("Orixe %s%s%s Primeiro"); + PROGMEM Language_Str MSG_ZPROBE_OFFSETS = _UxGT("Desfases Sonda"); + PROGMEM Language_Str MSG_ZPROBE_XOFFSET = _UxGT("Desfase Sonda X"); + PROGMEM Language_Str MSG_ZPROBE_YOFFSET = _UxGT("Desfase Sonda Y"); + PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Desfase Z"); PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Micropaso X"); PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Micropaso Y"); PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Micropaso Z"); - PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Erro fin carro"); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Fallo quentando"); - PROGMEM Language_Str MSG_ERR_REDUNDANT_TEMP = _UxGT("Erro temperatura"); - PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("Temp. excesiva"); - PROGMEM Language_Str MSG_HALTED = _UxGT("SISTEMA MORTO"); + PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Total"); + PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Erro FinCarro"); + PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Fallo Quentando"); + PROGMEM Language_Str MSG_HEATING_FAILED_LCD_BED = _UxGT("Fallo Quent. Cama"); + PROGMEM Language_Str MSG_HEATING_FAILED_LCD_CHAMBER = _UxGT("Fallo Quent. Cámara"); + PROGMEM Language_Str MSG_ERR_REDUNDANT_TEMP = _UxGT("Erro:Temp Redundante"); + PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("FUGA TÉRMICA"); + PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("FUGA TÉRMICA CAMA"); + PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("FUGA TÉRMICA CÁMARA"); + PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Erro:TEMP MÁX"); + PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Erro:TEMP MÍN"); + PROGMEM Language_Str MSG_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_ERR_Z_HOMING = _UxGT("Orixe XY Primeiro"); + PROGMEM Language_Str MSG_HALTED = _UxGT("IMPRESORA DETIDA"); PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Debe reiniciar!"); + PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("d"); // One character only + PROGMEM Language_Str MSG_SHORT_HOUR = _UxGT("h"); // One character only + PROGMEM Language_Str MSG_SHORT_MINUTE = _UxGT("m"); // One character only PROGMEM Language_Str MSG_HEATING = _UxGT("Quentando..."); + PROGMEM Language_Str MSG_COOLING = _UxGT("Arrefriando..."); PROGMEM Language_Str MSG_BED_HEATING = _UxGT("Quentando cama..."); + PROGMEM Language_Str MSG_BED_COOLING = _UxGT("Enfriando Cama..."); + PROGMEM Language_Str MSG_CHAMBER_HEATING = _UxGT("Quentando Cámara..."); + PROGMEM Language_Str MSG_CHAMBER_COOLING = _UxGT("Arrefriando Cámara..."); PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Calibracion Delta"); PROGMEM Language_Str MSG_DELTA_CALIBRATE_X = _UxGT("Calibrar X"); PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("Calibrar Y"); PROGMEM Language_Str MSG_DELTA_CALIBRATE_Z = _UxGT("Calibrar Z"); PROGMEM Language_Str MSG_DELTA_CALIBRATE_CENTER = _UxGT("Calibrar Centro"); + PROGMEM Language_Str MSG_DELTA_SETTINGS = _UxGT("Configuración Delta"); + PROGMEM Language_Str MSG_DELTA_AUTO_CALIBRATE = _UxGT("Auto Calibración"); + PROGMEM Language_Str MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Ax. Altura Delta"); + PROGMEM Language_Str MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Axustar Sonda Z"); + PROGMEM Language_Str MSG_DELTA_DIAG_ROD = _UxGT("Barra Diagonal"); + PROGMEM Language_Str MSG_DELTA_HEIGHT = _UxGT("Altura"); + PROGMEM Language_Str MSG_DELTA_RADIUS = _UxGT("Radio"); PROGMEM Language_Str MSG_INFO_MENU = _UxGT("Acerca de..."); - PROGMEM Language_Str MSG_INFO_PRINTER_MENU = _UxGT("Informacion"); - PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Estadisticas"); + PROGMEM Language_Str MSG_INFO_PRINTER_MENU = _UxGT("Información"); + PROGMEM Language_Str MSG_3POINT_LEVELING = _UxGT("Nivelación 3puntos"); + PROGMEM Language_Str MSG_LINEAR_LEVELING = _UxGT("Nivelación Lineal"); + PROGMEM Language_Str MSG_BILINEAR_LEVELING = _UxGT("Nivelación Bilineal"); + PROGMEM Language_Str MSG_UBL_LEVELING = _UxGT("Nivelación UBL"); + PROGMEM Language_Str MSG_MESH_LEVELING = _UxGT("Nivelación en Malla"); + PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Estatísticas"); PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("Placa nai"); PROGMEM Language_Str MSG_INFO_THERMISTOR_MENU = _UxGT("Termistores"); PROGMEM Language_Str MSG_INFO_EXTRUDERS = _UxGT("Extrusores"); PROGMEM Language_Str MSG_INFO_BAUDRATE = _UxGT("Baudios"); PROGMEM Language_Str MSG_INFO_PROTOCOL = _UxGT("Protocolo"); - PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Luz"); + PROGMEM Language_Str MSG_INFO_RUNAWAY_OFF = _UxGT("Reloxo Traballo: OFF"); + PROGMEM Language_Str MSG_INFO_RUNAWAY_ON = _UxGT("Reloxo Traballo: ON"); + + PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Luz da Caixa"); + PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Brillo Luces"); + PROGMEM Language_Str MSG_EXPECTED_PRINTER = _UxGT("IMPRESORA INCORRECTA"); + #if LCD_WIDTH >= 20 - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Total traballos"); - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Total completos"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Tempo impresion"); - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Traballo +longo"); - PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Total extruido"); + PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Total Impresións"); + PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Completadas"); + PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Tempo Total Imp."); + PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Impresión máis longa"); + PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Total Extruído"); #else - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Traballos"); - PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Completos"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Tempo"); - PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("O +longo"); + PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Impresións"); + PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Completadas"); + PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Total"); + PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Máis Longa"); PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Extruido"); #endif - PROGMEM Language_Str MSG_INFO_MIN_TEMP = _UxGT("Min Temp"); - PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Max Temp"); - PROGMEM Language_Str MSG_INFO_PSU = _UxGT("Fonte alime."); - PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Potencia motor"); - PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("Garda DAC EEPROM"); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Segue traballo"); + PROGMEM Language_Str MSG_INFO_MIN_TEMP = _UxGT("Temp Mín"); + PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Temp Máx"); + PROGMEM Language_Str MSG_INFO_PSU = _UxGT("Fonte Alimentación"); + PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Forza do Motor"); + PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("X Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Y Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Z Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E Driver %"); + PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("ERRO CONEX. TMC"); + PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("Escribe DAC EEPROM"); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER = _UxGT("CAMBIAR FILAMENTO"); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("IMPRESIÓN PAUSADA"); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_LOAD = _UxGT("CARGAR FILAMENTO"); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER_UNLOAD = _UxGT("DESCARGAR FILAMENTO"); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("OPCIÓN DE RETOMAR:"); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Purgar máis"); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Retomar traballo"); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Bico: "); + PROGMEM Language_Str MSG_RUNOUT_SENSOR = _UxGT("Sensor Filamento"); + PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("Dist mm Sensor Fil"); + PROGMEM Language_Str MSG_LCD_HOMING_FAILED = _UxGT("Fallo ao ir á Orixe"); + PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Fallo ao Sondar"); + PROGMEM Language_Str MSG_M600_TOO_COLD = _UxGT("M600: Moi Frío"); - PROGMEM Language_Str MSG_EXPECTED_PRINTER = _UxGT("Impresora incorrecta"); + PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("ESCOLLE FILAMENTO"); + PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); + PROGMEM Language_Str MSG_MMU2_WRONG_FIRMWARE = _UxGT("Actualizar FW MMU!"); + PROGMEM Language_Str MSG_MMU2_NOT_RESPONDING = _UxGT("MMU Precisa Atención."); + PROGMEM Language_Str MSG_MMU2_RESUME = _UxGT("Retomar impr."); + PROGMEM Language_Str MSG_MMU2_RESUMING = _UxGT("Retomando..."); + PROGMEM Language_Str MSG_MMU2_LOAD_FILAMENT = _UxGT("Cargar Filamento"); + PROGMEM Language_Str MSG_MMU2_LOAD_ALL = _UxGT("Cargar Todo"); + PROGMEM Language_Str MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("Cargar até bico"); + PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT = _UxGT("Expulsar Filamento"); + PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT_N = _UxGT("Expulsar Filamento ~"); + PROGMEM Language_Str MSG_MMU2_UNLOAD_FILAMENT = _UxGT("Descargar Filamento"); + PROGMEM Language_Str MSG_MMU2_LOADING_FILAMENT = _UxGT("Cargando Fil. %i..."); + PROGMEM Language_Str MSG_MMU2_EJECTING_FILAMENT = _UxGT("Expulsando Fil. ..."); + PROGMEM Language_Str MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Descargando Fil..."); + PROGMEM Language_Str MSG_MMU2_ALL = _UxGT("Todo"); + PROGMEM Language_Str MSG_MMU2_FILAMENT_N = _UxGT("Filamento ~"); + PROGMEM Language_Str MSG_MMU2_RESET = _UxGT("Reiniciar MMU"); + PROGMEM Language_Str MSG_MMU2_RESETTING = _UxGT("Reiniciando MMU..."); + PROGMEM Language_Str MSG_MMU2_EJECT_RECOVER = _UxGT("Expulsar, premer"); + + PROGMEM Language_Str MSG_MIX = _UxGT("Mestura"); + PROGMEM Language_Str MSG_MIX_COMPONENT_N = _UxGT("Compoñente ="); + PROGMEM Language_Str MSG_MIXER = _UxGT("Mesturadora"); + PROGMEM Language_Str MSG_GRADIENT = _UxGT("Degradado"); + PROGMEM Language_Str MSG_FULL_GRADIENT = _UxGT("Degradado Total"); + PROGMEM Language_Str MSG_TOGGLE_MIX = _UxGT("Mestura Conmutada"); + PROGMEM Language_Str MSG_CYCLE_MIX = _UxGT("Mestura Cíclica"); + PROGMEM Language_Str MSG_GRADIENT_MIX = _UxGT("Mestura de Degradado"); + PROGMEM Language_Str MSG_REVERSE_GRADIENT = _UxGT("Degradado Inverso"); + PROGMEM Language_Str MSG_ACTIVE_VTOOL = _UxGT("Activar Ferr-V"); + PROGMEM Language_Str MSG_START_VTOOL = _UxGT("Inicio Ferr-V"); + PROGMEM Language_Str MSG_END_VTOOL = _UxGT(" Fin Ferr-V"); + PROGMEM Language_Str MSG_GRADIENT_ALIAS = _UxGT("Alias Ferr-V"); + PROGMEM Language_Str MSG_RESET_VTOOLS = _UxGT("Reiniciar Ferr-V"); + PROGMEM Language_Str MSG_COMMIT_VTOOL = _UxGT("Commit mest. Ferr-V"); + PROGMEM Language_Str MSG_VTOOLS_RESET = _UxGT("Ferr-V reiniciadas"); + PROGMEM Language_Str MSG_START_Z = _UxGT("Inicio Z:"); + PROGMEM Language_Str MSG_END_Z = _UxGT(" Fin Z:"); + + PROGMEM Language_Str MSG_GAMES = _UxGT("Xogos"); + PROGMEM Language_Str MSG_BRICKOUT = _UxGT("Brickout"); + PROGMEM Language_Str MSG_INVADERS = _UxGT("Invaders"); + PROGMEM Language_Str MSG_SNAKE = _UxGT("Sn4k3"); + PROGMEM Language_Str MSG_MAZE = _UxGT("Labirinto"); #if LCD_HEIGHT >= 4 - // Up to 3 lines allowed - PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Agarde para", "iniciar troco", "de filamento")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_3_LINE("Agarde pola", "descarga do", "filamento")); + PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_2_LINE("Preme o botón para", "continuar impresión")); + PROGMEM Language_Str MSG_PAUSE_PRINT_INIT = _UxGT(MSG_1_LINE("Estacionando...")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Agarde para", "comezar cambio", "de filamento")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Introduza o", "filamento e", "faga click")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Prema o botón para", "quentar o bico")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_2_LINE("Quentando bico", "Agarde, por favor...")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_3_LINE("Agarde pola", "descarga do", "filamento")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_3_LINE("Agarde pola", "carga do", "filamento")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_3_LINE("Agarde para", "seguir co", "traballo")); - #else // LCD_HEIGHT < 4 - // Up to 2 lines allowed + PROGMEM Language_Str MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_2_LINE("Agarde para", "purgar o filamento")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_2_LINE("Prema para finalizar", "a purga do filamen.")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_3_LINE("Agarde a que", "se retome", "a impresión")); + #else + PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("Premer para continuar")); + PROGMEM Language_Str MSG_PAUSE_PRINT_INIT = _UxGT(MSG_1_LINE("Estacionando...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("Agarde...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("Descargando...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Introduza e click")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("Prema para quentar")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("Quentando...")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("Descargando...")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("Cargando...")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Seguindo...")); - #endif // LCD_HEIGHT < 4 + PROGMEM Language_Str MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_1_LINE("Purgando...")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("Prema para finalizar")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Retomando...")); + #endif + + PROGMEM Language_Str MSG_TMC_DRIVERS = _UxGT("Controladores TMC"); + PROGMEM Language_Str MSG_TMC_CURRENT = _UxGT("Controlador Actual"); + PROGMEM Language_Str MSG_TMC_HYBRID_THRS = _UxGT("Limiar Hibrido"); + PROGMEM Language_Str MSG_TMC_HOMING_THRS = _UxGT("Orixe sen Sensores"); + PROGMEM Language_Str MSG_TMC_STEPPING_MODE = _UxGT("Modo de pasos"); + PROGMEM Language_Str MSG_TMC_STEALTH_ENABLED = _UxGT("StealthChop Habilit."); + PROGMEM Language_Str MSG_SERVICE_RESET = _UxGT("Reiniciar"); + PROGMEM Language_Str MSG_SERVICE_IN = _UxGT(" dentro:"); + PROGMEM Language_Str MSG_BACKLASH = _UxGT("Reacción"); + PROGMEM Language_Str MSG_BACKLASH_A = LCD_STR_A; + PROGMEM Language_Str MSG_BACKLASH_B = LCD_STR_B; + PROGMEM Language_Str MSG_BACKLASH_C = LCD_STR_C; + PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Corrección"); + PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Suavizado"); + + PROGMEM Language_Str MSG_LEVEL_X_AXIS = _UxGT("Nivel Eixe X"); + PROGMEM Language_Str MSG_AUTO_CALIBRATE = _UxGT("Auto Calibrar"); + PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Tempo exc. Quent."); + PROGMEM Language_Str MSG_REHEAT = _UxGT("Requentar"); + PROGMEM Language_Str MSG_REHEATING = _UxGT("Requentando..."); } From 1d81bb7a2b7692dff37d2a35dd547e6a8a25c49f Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 6 Apr 2020 00:02:56 +0000 Subject: [PATCH 34/37] [cron] Bump distribution date (2020-04-06) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index d24a9dbefaae..cdeaeffd5ebd 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-04-05" + #define STRING_DISTRIBUTION_DATE "2020-04-06" #endif /** From d6f39a69af1d5dbab09deeb8a35bcdc050488b83 Mon Sep 17 00:00:00 2001 From: Tor-p <63096807+Tor-p@users.noreply.github.com> Date: Mon, 6 Apr 2020 22:32:06 +0200 Subject: [PATCH 35/37] Fix G76 probe height / position (#17392) --- Marlin/Configuration_adv.h | 11 +---- Marlin/src/feature/probe_temp_comp.cpp | 10 ++-- Marlin/src/feature/probe_temp_comp.h | 34 +++++++------- Marlin/src/gcode/calibrate/G76_M871.cpp | 61 ++++++++++++------------- Marlin/src/inc/SanityCheck.h | 15 ++++++ buildroot/share/tests/rambo-tests | 2 +- 6 files changed, 67 insertions(+), 66 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 7d1547c0d027..c715fe333298 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1600,18 +1600,11 @@ // Add additional compensation depending on hotend temperature // Note: this values cannot be calibrated and have to be set manually #if ENABLED(PROBE_TEMP_COMPENSATION) - // Max temperature that can be reached by heated bed. - // This is required only for the calibration process. - #define PTC_MAX_BED_TEMP BED_MAXTEMP - // Park position to wait for probe cooldown - #define PTC_PARK_POS_X 0.0F - #define PTC_PARK_POS_Y 0.0F - #define PTC_PARK_POS_Z 100.0F + #define PTC_PARK_POS { 0, 0, 100 } // Probe position to probe and wait for probe to reach target temperature - #define PTC_PROBE_POS_X 90.0F - #define PTC_PROBE_POS_Y 100.0F + #define PTC_PROBE_POS { 90, 100 } // Enable additional compensation using hotend temperature // Note: this values cannot be calibrated automatically but have to be set manually diff --git a/Marlin/src/feature/probe_temp_comp.cpp b/Marlin/src/feature/probe_temp_comp.cpp index 6b787f420a33..b773536a5d54 100644 --- a/Marlin/src/feature/probe_temp_comp.cpp +++ b/Marlin/src/feature/probe_temp_comp.cpp @@ -29,11 +29,11 @@ ProbeTempComp temp_comp; -int16_t ProbeTempComp::z_offsets_probe[ProbeTempComp::cali_info_init[TSI_PROBE].measurements], // = {0} - ProbeTempComp::z_offsets_bed[ProbeTempComp::cali_info_init[TSI_BED].measurements]; // = {0} +int16_t ProbeTempComp::z_offsets_probe[cali_info_init[TSI_PROBE].measurements], // = {0} + ProbeTempComp::z_offsets_bed[cali_info_init[TSI_BED].measurements]; // = {0} #if ENABLED(USE_TEMP_EXT_COMPENSATION) - int16_t ProbeTempComp::z_offsets_ext[ProbeTempComp::cali_info_init[TSI_EXT].measurements]; // = {0} + int16_t ProbeTempComp::z_offsets_ext[cali_info_init[TSI_EXT].measurements]; // = {0} #endif int16_t *ProbeTempComp::sensor_z_offsets[TSI_COUNT] = { @@ -44,9 +44,9 @@ int16_t *ProbeTempComp::sensor_z_offsets[TSI_COUNT] = { }; const temp_calib_t ProbeTempComp::cali_info[TSI_COUNT] = { - ProbeTempComp::cali_info_init[TSI_PROBE], ProbeTempComp::cali_info_init[TSI_BED] + cali_info_init[TSI_PROBE], cali_info_init[TSI_BED] #if ENABLED(USE_TEMP_EXT_COMPENSATION) - , ProbeTempComp::cali_info_init[TSI_EXT] + , cali_info_init[TSI_EXT] #endif }; diff --git a/Marlin/src/feature/probe_temp_comp.h b/Marlin/src/feature/probe_temp_comp.h index 2ed10eeb990a..dff21b92ad6a 100644 --- a/Marlin/src/feature/probe_temp_comp.h +++ b/Marlin/src/feature/probe_temp_comp.h @@ -44,30 +44,28 @@ typedef struct { * Z-probes like the P.I.N.D.A V2 allow for compensation of * measurement errors/shifts due to changed temperature. */ + +static constexpr temp_calib_t cali_info_init[TSI_COUNT] = { + { 10, 5, 30, 30 + 10 * 5 }, // Probe + { 10, 5, 60, 60 + 10 * 5 }, // Bed + #if ENABLED(USE_TEMP_EXT_COMPENSATION) + { 20, 5, 180, 180 + 5 * 20 } // Extruder + #endif +}; + class ProbeTempComp { public: - static constexpr temp_calib_t cali_info_init[TSI_COUNT] = { - { 10, 5, 30, 30 + 10 * 5 }, // Probe - { 10, 5, 60, 60 + 10 * 5 }, // Bed - #if ENABLED(USE_TEMP_EXT_COMPENSATION) - { 20, 5, 180, 180 + 5 * 20 } // Extruder - #endif - }; static const temp_calib_t cali_info[TSI_COUNT]; // Where to park nozzle to wait for probe cooldown - static constexpr float park_point_x = PTC_PARK_POS_X, - park_point_y = PTC_PARK_POS_Y, - park_point_z = PTC_PARK_POS_Z, - // XY coordinates of nozzle for probing the bed - measure_point_x = PTC_PROBE_POS_X, // Coordinates to probe - measure_point_y = PTC_PROBE_POS_Y; - //measure_point_x = 12.0f, // Coordinates to probe on MK52 magnetic heatbed - //measure_point_y = 7.3f; - - static constexpr int max_bed_temp = PTC_MAX_BED_TEMP, // Max temperature to avoid heating errors - probe_calib_bed_temp = max_bed_temp, // Bed temperature while calibrating probe + static constexpr xyz_pos_t park_point = PTC_PARK_POS; + + // XY coordinates of nozzle for probing the bed + static constexpr xy_pos_t measure_point = PTC_PROBE_POS; // Coordinates to probe + //measure_point = { 12.0f, 7.3f }; // Coordinates for the MK52 magnetic heatbed + + static constexpr int probe_calib_bed_temp = BED_MAXTEMP - 10, // Bed temperature while calibrating probe bed_calib_probe_temp = 30; // Probe temperature while calibrating bed static int16_t *sensor_z_offsets[TSI_COUNT], diff --git a/Marlin/src/gcode/calibrate/G76_M871.cpp b/Marlin/src/gcode/calibrate/G76_M871.cpp index 4bc27b82f5f9..50b099bd1c7c 100644 --- a/Marlin/src/gcode/calibrate/G76_M871.cpp +++ b/Marlin/src/gcode/calibrate/G76_M871.cpp @@ -103,13 +103,19 @@ void GcodeSuite::G76() { return false; }; - auto g76_probe = [](const xy_pos_t &xypos) { + auto g76_probe = [](const TempSensorID sid, uint16_t &targ, const xy_pos_t &nozpos) { do_blocking_move_to_z(5.0); // Raise nozzle before probing - const float measured_z = probe.probe_at_point(xypos, PROBE_PT_NONE, 0, false); // verbose=0, probe_relative=false + const float measured_z = probe.probe_at_point(nozpos, PROBE_PT_NONE, 0, false); // verbose=0, probe_relative=false if (isnan(measured_z)) SERIAL_ECHOLNPGM("!Received NAN. Aborting."); - else + else { SERIAL_ECHOLNPAIR_F("Measured: ", measured_z); + if (targ == cali_info_init[sid].start_temp) + temp_comp.prepare_new_calibration(measured_z); + else + temp_comp.push_back_new_measurement(sid, measured_z); + targ += cali_info_init[sid].temp_res; + } return measured_z; }; @@ -125,8 +131,9 @@ void GcodeSuite::G76() { // Synchronize with planner planner.synchronize(); - const xyz_pos_t parkpos = { temp_comp.park_point_x, temp_comp.park_point_y, temp_comp.park_point_z }; - const xy_pos_t ppos = { temp_comp.measure_point_x, temp_comp.measure_point_y }; + const xyz_pos_t parkpos = temp_comp.park_point, + probe_pos_xyz = temp_comp.measure_point + xyz_pos_t({ 0.0f, 0.0f, 0.5f }), + noz_pos_xyz = probe_pos_xyz - probe.offset_xy; // Nozzle position based on probe position if (do_bed_cal || do_probe_cal) { // Ensure park position is reachable @@ -135,7 +142,7 @@ void GcodeSuite::G76() { SERIAL_ECHOLNPGM("!Park"); else { // Ensure probe position is reachable - reachable = probe.can_reach(ppos); + reachable = probe.can_reach(probe_pos_xyz); if (!reachable) SERIAL_ECHOLNPGM("!Probe"); } @@ -149,8 +156,6 @@ void GcodeSuite::G76() { remember_feedrate_scaling_off(); - // Nozzle position based on probe position - const xy_pos_t noz_pos = ppos - probe.offset_xy; /****************************************** * Calibrate bed temperature offsets @@ -159,9 +164,13 @@ void GcodeSuite::G76() { // Report temperatures every second and handle heating timeouts millis_t next_temp_report = millis() + 1000; + auto report_targets = [&](const uint16_t tb, const uint16_t tp) { + SERIAL_ECHOLNPAIR("Target Bed:", tb, " Probe:", tp); + }; + if (do_bed_cal) { - uint16_t target_bed = temp_comp.cali_info_init[TSI_BED].start_temp, + uint16_t target_bed = cali_info_init[TSI_BED].start_temp, target_probe = temp_comp.bed_calib_probe_temp; SERIAL_ECHOLNPGM("Waiting for cooling."); @@ -176,7 +185,7 @@ void GcodeSuite::G76() { for (;;) { thermalManager.setTargetBed(target_bed); - SERIAL_ECHOLNPAIR("Target Bed:", target_bed, " Probe:", target_probe); + report_targets(target_bed, target_probe); // Park nozzle do_blocking_move_to(parkpos); @@ -188,21 +197,13 @@ void GcodeSuite::G76() { } // Move the nozzle to the probing point and wait for the probe to reach target temp - do_blocking_move_to_xy(noz_pos); + do_blocking_move_to(noz_pos_xyz); SERIAL_ECHOLNPGM("Waiting for probe heating."); while (thermalManager.degProbe() < target_probe) report_temps(next_temp_report); - const float measured_z = g76_probe(noz_pos); - if (isnan(measured_z)) break; - - if (target_bed == temp_comp.cali_info_init[TSI_BED].start_temp) - temp_comp.prepare_new_calibration(measured_z); - else - temp_comp.push_back_new_measurement(TSI_BED, measured_z); - - target_bed += temp_comp.cali_info_init[TSI_BED].temp_res; - if (target_bed > temp_comp.max_bed_temp) break; + const float measured_z = g76_probe(TSI_BED, target_bed, noz_pos_xyz); + if (isnan(measured_z) || target_bed > BED_MAXTEMP - 10) break; } SERIAL_ECHOLNPAIR("Retrieved measurements: ", temp_comp.get_index()); @@ -231,7 +232,9 @@ void GcodeSuite::G76() { const uint16_t target_bed = temp_comp.probe_calib_bed_temp; thermalManager.setTargetBed(target_bed); - uint16_t target_probe = temp_comp.cali_info_init[TSI_PROBE].start_temp; + uint16_t target_probe = cali_info_init[TSI_PROBE].start_temp; + + report_targets(target_bed, target_probe); // Wait for heatbed to reach target temp and probe to cool below target temp wait_for_temps(target_bed, target_probe, next_temp_report); @@ -244,7 +247,7 @@ void GcodeSuite::G76() { bool timeout = false; for (;;) { // Move probe to probing point and wait for it to reach target temperature - do_blocking_move_to_xy(noz_pos); + do_blocking_move_to(noz_pos_xyz); SERIAL_ECHOLNPAIR("Waiting for probe heating. Bed:", target_bed, " Probe:", target_probe); const millis_t probe_timeout_ms = millis() + 900UL * 1000UL; @@ -257,16 +260,8 @@ void GcodeSuite::G76() { } if (timeout) break; - const float measured_z = g76_probe(noz_pos); - if (isnan(measured_z)) break; - - if (target_probe == temp_comp.cali_info_init[TSI_PROBE].start_temp) - temp_comp.prepare_new_calibration(measured_z); - else - temp_comp.push_back_new_measurement(TSI_PROBE, measured_z); - - target_probe += temp_comp.cali_info_init[TSI_PROBE].temp_res; - if (target_probe > temp_comp.cali_info_init[TSI_PROBE].end_temp) break; + const float measured_z = g76_probe(TSI_PROBE, target_probe, noz_pos_xyz); + if (isnan(measured_z) || target_probe > cali_info_init[TSI_PROBE].end_temp) break; } SERIAL_ECHOLNPAIR("Retrieved measurements: ", temp_comp.get_index()); diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 088ad098db92..185f5c0b4dce 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -491,6 +491,21 @@ #error "DUGS_UI_MOVE_DIS_OPTION is spelled DGUS_UI_MOVE_DIS_OPTION. Please update Configuration_adv.h." #endif +/** + * Probe temp compensation requirements + */ +#if ENABLED(PROBE_TEMP_COMPENSATION) + #if defined(PTC_PARK_POS_X) || defined(PTC_PARK_POS_Y) || defined(PTC_PARK_POS_Z) + #error "PTC_PARK_POS_[XYZ] is now PTC_PARK_POS (array). Please update Configuration_adv.h." + #elif !defined(PTC_PARK_POS) + #error "PROBE_TEMP_COMPENSATION requires PTC_PARK_POS." + #elif defined(PTC_PROBE_POS_X) || defined(PTC_PROBE_POS_Y) + #error "PTC_PROBE_POS_[XY] is now PTC_PROBE_POS (array). Please update Configuration_adv.h." + #elif !defined(PTC_PROBE_POS) + #error "PROBE_TEMP_COMPENSATION requires PTC_PROBE_POS." + #endif +#endif + /** * Marlin release, version and default string */ diff --git a/buildroot/share/tests/rambo-tests b/buildroot/share/tests/rambo-tests index 8092059627ea..57c363c3a467 100644 --- a/buildroot/share/tests/rambo-tests +++ b/buildroot/share/tests/rambo-tests @@ -50,7 +50,7 @@ opt_set GRID_MAX_POINTS_X 16 opt_set FANMUX0_PIN 53 opt_disable USE_WATCHDOG opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER LCD_PROGRESS_BAR LCD_PROGRESS_BAR_TEST \ - FIX_MOUNTED_PROBE Z_SAFE_HOMING CODEPENDENT_XY_HOMING PIDTEMPBED \ + FIX_MOUNTED_PROBE Z_SAFE_HOMING CODEPENDENT_XY_HOMING PIDTEMPBED PROBE_TEMP_COMPENSATION \ PROBING_HEATERS_OFF PROBING_FANS_OFF PROBING_STEPPERS_OFF WAIT_FOR_BED_HEATER \ EEPROM_SETTINGS SDSUPPORT SD_REPRINT_LAST_SELECTED_FILE BINARY_FILE_TRANSFER \ BLINKM PCA9632 RGB_LED RGB_LED_R_PIN RGB_LED_G_PIN RGB_LED_B_PIN LED_CONTROL_MENU \ From 966e0e4a77f6f62a173a2b08de73c25512b40072 Mon Sep 17 00:00:00 2001 From: thisiskeithb <13375512+thisiskeithb@users.noreply.github.com> Date: Mon, 6 Apr 2020 13:51:09 -0700 Subject: [PATCH 36/37] BTT002 release V1 uses STM32F407VGT6 (#17387) --- Marlin/src/core/boards.h | 2 +- buildroot/share/PlatformIO/boards/BigTree_Btt002.json | 10 +++++----- buildroot/share/tests/BIGTREE_BTT002-tests | 2 +- platformio.ini | 4 ++-- 4 files changed, 9 insertions(+), 9 deletions(-) diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index 30c2d3eb87a3..c650d7ec75f2 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -319,7 +319,7 @@ #define BOARD_BLACK_STM32F407ZE 4206 // BLACK_STM32F407ZE #define BOARD_STEVAL_3DP001V1 4207 // STEVAL-3DP001V1 3D PRINTER BOARD #define BOARD_BTT_SKR_PRO_V1_1 4208 // BigTreeTech SKR Pro v1.1 (STM32F407ZG) -#define BOARD_BTT_BTT002_V1_0 4209 // BigTreeTech BTT002 v1.0 (STM32F407VE) +#define BOARD_BTT_BTT002_V1_0 4209 // BigTreeTech BTT002 v1.0 (STM32F407VG) #define BOARD_BTT_GTR_V1_0 4210 // BigTreeTech GTR v1.0 (STM32F407IGT) #define BOARD_LERDGE_K 4211 // Lerdge K (STM32F407ZG) #define BOARD_LERDGE_X 4212 // Lerdge X (STM32F407VE) diff --git a/buildroot/share/PlatformIO/boards/BigTree_Btt002.json b/buildroot/share/PlatformIO/boards/BigTree_Btt002.json index 2fbf5ae8ac38..8ef3b77ea81f 100644 --- a/buildroot/share/PlatformIO/boards/BigTree_Btt002.json +++ b/buildroot/share/PlatformIO/boards/BigTree_Btt002.json @@ -15,22 +15,22 @@ ] ], "ldscript": "stm32f407xg.ld", - "mcu": "stm32f407vet6", + "mcu": "stm32f407vgt6", "variant": "BIGTREE_BTT002" }, "debug": { - "jlink_device": "STM32F407VE", + "jlink_device": "STM32F407VG", "openocd_target": "stm32f4x", "svd_path": "STM32F40x.svd" }, "frameworks": [ "arduino" ], - "name": "STM32F407VE (192k RAM. 512k Flash)", + "name": "STM32F407VG (192k RAM. 1024k Flash)", "upload": { "disable_flushing": false, "maximum_ram_size": 131072, - "maximum_size": 524288, + "maximum_size": 1048576, "protocol": "stlink", "protocols": [ "stlink", @@ -41,6 +41,6 @@ "use_1200bps_touch": false, "wait_for_upload_port": false }, - "url": "http://www.st.com/en/microcontrollers/stm32f407ve.html", + "url": "http://www.st.com/en/microcontrollers/stm32f407vg.html", "vendor": "Generic" } diff --git a/buildroot/share/tests/BIGTREE_BTT002-tests b/buildroot/share/tests/BIGTREE_BTT002-tests index 858957154def..1ab40123b5dd 100644 --- a/buildroot/share/tests/BIGTREE_BTT002-tests +++ b/buildroot/share/tests/BIGTREE_BTT002-tests @@ -1,6 +1,6 @@ #!/usr/bin/env bash # -# Build tests for STM32F407VET6 BigTreeTech BTT002 +# Build tests for STM32F407VGT6 BigTreeTech BTT002 V1.0 # # exit on first failure diff --git a/platformio.ini b/platformio.ini index bf3dea01bc20..f7fb31ec2ef9 100644 --- a/platformio.ini +++ b/platformio.ini @@ -727,14 +727,14 @@ src_filter = ${common.default_src_filter} + monitor_speed = 250000 # -# BigTreeTech BTT002 (STM32F407VET6 ARM Cortex-M4) +# BigTreeTech BTT002 V1.0 (STM32F407VGT6 ARM Cortex-M4) # [env:BIGTREE_BTT002] platform = ststm32@5.6.0 board = BigTree_Btt002 platform_packages = framework-arduinoststm32@>=3.107,<4 build_flags = ${common.build_flags} - -DUSBCON -DUSBD_USE_CDC -DUSBD_VID=0x0483 -DUSB_PRODUCT=\"STM32F407VE\" + -DUSBCON -DUSBD_USE_CDC -DUSBD_VID=0x0483 -DUSB_PRODUCT=\"STM32F407VG\" -DTARGET_STM32F4 -DSTM32F407_5VX -DVECT_TAB_OFFSET=0x8000 -DHAVE_HWSERIAL2 -DHAVE_HWSERIAL3 From e1fc6f7e2508a73a760f8c1294f9aef405194880 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 7 Apr 2020 00:03:10 +0000 Subject: [PATCH 37/37] [cron] Bump distribution date (2020-04-07) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index cdeaeffd5ebd..4d457a57dfd1 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-04-06" + #define STRING_DISTRIBUTION_DATE "2020-04-07" #endif /**