diff --git a/LICENSE b/LICENSE index 4ad6d9b1e2..6c0e10f3b8 100644 --- a/LICENSE +++ b/LICENSE @@ -3,7 +3,7 @@ GNU GENERAL PUBLIC LICENSE Version 3, 29 June 2007 - Copyright (c) 2007 Free Software Foundation, Inc. + Copyright (c) 2007 Free Software Foundation, Inc. Everyone is permitted to copy and distribute verbatim copies of this license document, but changing it is not allowed. @@ -673,5 +673,4 @@ into proprietary programs. If your program is a subroutine library, you may consider it more useful to permit linking proprietary applications with the library. If this is what you want to do, use the GNU Lesser General Public License instead of this License. But first, please read -. - +. diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index ff07c4eed0..23f142ebac 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -34,9 +34,8 @@ * - Extra features * * Advanced settings can be found in Configuration_adv.h - * */ -#define CONFIGURATION_H_VERSION 020006 +#define CONFIGURATION_H_VERSION 020007 //=========================================================================== //============================= Getting Started ============================= @@ -111,7 +110,6 @@ * :[-1, 0, 1, 2, 3, 4, 5, 6, 7] */ #define SERIAL_PORT_2 1 -#define NUM_SERIAL 2 /** * This setting determines the communication speed of the printer. @@ -391,6 +389,7 @@ * 21 : Pt100 with circuit in the Ultimainboard V2.x with 3.3v excitation (STM32 \ LPC176x....) * 22 : 100k (hotend) with 4.7k pullup to 3.3V and 220R to analog input (as in GTM32 Pro vB) * 23 : 100k (bed) with 4.7k pullup to 3.3v and 220R to analog input (as in GTM32 Pro vB) + * 30 : Kis3d Silicone heating mat 200W/300W with 6mm precision cast plate (EN AW 5083) NTC100K / B3950 (4.7k pullup) * 201 : Pt100 with circuit in Overlord, similar to Ultimainboard V2.x * 60 : 100k Maker's Tool Works Kapton Bed Thermistor beta=3950 * 61 : 100k Formbot / Vivedino 3950 350C thermistor 4.7k pullup @@ -487,29 +486,17 @@ #define PID_AUTOTUNE_MENU // Add PID auto-tuning to the "Advanced Settings" menu. (~250 bytes of PROGMEM) //#define PID_PARAMS_PER_HOTEND // Uses separate PID parameters for each extruder (useful for mismatched extruders) // Set/get with gcode: M301 E[extruder number, 0-2] - - // If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it - - // Ultimaker - //#define DEFAULT_Kp 22.2 - //#define DEFAULT_Ki 1.08 - //#define DEFAULT_Kd 114 - - // MakerGear - //#define DEFAULT_Kp 7.0 - //#define DEFAULT_Ki 0.1 - //#define DEFAULT_Kd 12 - - // Mendel Parts V9 on 12V - //#define DEFAULT_Kp 63.0 - //#define DEFAULT_Ki 2.25 - //#define DEFAULT_Kd 440 - - //FB4S - #define DEFAULT_Kp 17.04 - #define DEFAULT_Ki 1.31 - #define DEFAULT_Kd 55.34 - + #if ENABLED(PID_PARAMS_PER_HOTEND) + // Specify between 1 and HOTENDS values per array. + // If fewer than EXTRUDER values are provided, the last element will be repeated. + #define DEFAULT_Kp_LIST { 22.20, 20.0 } + #define DEFAULT_Ki_LIST { 1.08, 1.0 } + #define DEFAULT_Kd_LIST { 114.00, 112.0 } + #else + #define DEFAULT_Kp 17.04 + #define DEFAULT_Ki 1.31 + #define DEFAULT_Kd 55.34 + #endif #endif // PIDTEMP //=========================================================================== @@ -551,11 +538,6 @@ //#define DEFAULT_bedKi .023 //#define DEFAULT_bedKd 305.4 - //120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+) - //from pidautotune - //#define DEFAULT_bedKp 97.1 - //#define DEFAULT_bedKi 1.41 - //#define DEFAULT_bedKd 1675.16 //FB4S #define DEFAULT_bedKp 40.68 @@ -620,7 +602,7 @@ // @section machine -// Uncomment one of these options to enable CoreXY, CoreXZ, or CoreYZ kinematics +// Enable one of the options below for CoreXY, CoreXZ, or CoreYZ kinematics, // either in the usual order or reversed //#define COREXY //#define COREXZ @@ -628,6 +610,7 @@ //#define COREYX //#define COREZX //#define COREZY +//#define MARKFORGED_XY // MarkForged. See https://reprap.org/forum/read.php?152,504042 //=========================================================================== //============================== Endstop Settings =========================== @@ -879,7 +862,6 @@ * - For simple switches connect... * - normally-closed switches to GND and D32. * - normally-open switches to 5V and D32. - * */ #define Z_MIN_PROBE_PIN BL_TOUCH_Z_PIN // Pin 32 is the RAMPS default @@ -1580,14 +1562,14 @@ EEPROM_W25Q // @section temperature // Preheat Constants -#define PREHEAT_1_LABEL "ABS" -#define PREHEAT_1_TEMP_HOTEND 250 -#define PREHEAT_1_TEMP_BED 100 +#define PREHEAT_1_LABEL "PETG" +#define PREHEAT_1_TEMP_HOTEND 235 +#define PREHEAT_1_TEMP_BED 80 #define PREHEAT_1_FAN_SPEED 0 // Value from 0 to 255 -#define PREHEAT_2_LABEL "PETG" -#define PREHEAT_2_TEMP_HOTEND 235 -#define PREHEAT_2_TEMP_BED 80 +#define PREHEAT_2_LABEL "ABS" +#define PREHEAT_2_TEMP_HOTEND 250 +#define PREHEAT_2_TEMP_BED 100 #define PREHEAT_2_FAN_SPEED 0 // Value from 0 to 255 /** @@ -1649,7 +1631,6 @@ EEPROM_W25Q * * Caveats: The ending Z should be the same as starting Z. * Attention: EXPERIMENTAL. G-code arguments may change. - * */ //#define NOZZLE_CLEAN_FEATURE @@ -1802,7 +1783,6 @@ EEPROM_W25Q * * SD Card support is disabled by default. If your controller has an SD slot, * you must uncomment the following option or it won't work. - * */ #define SDSUPPORT @@ -2039,6 +2019,14 @@ EEPROM_W25Q // //#define FF_INTERFACEBOARD +// +// TFT GLCD Panel with Marlin UI +// Panel connected to main board by SPI or I2C interface. +// See https://github.com/Serhiy-K/TFTGLCDAdapter +// +//#define TFTGLCD_PANEL_SPI +//#define TFTGLCD_PANEL_I2C + //============================================================================= //======================= LCD / Controller Selection ======================= //========================= (Graphical LCDs) ======================== @@ -2242,6 +2230,9 @@ EEPROM_W25Q // Touch-screen LCD for Malyan M200/M300 printers // //#define MALYAN_LCD +#if ENABLED(MALYAN_LCD) + #define LCD_SERIAL_PORT 1 // Default is 1 for Malyan M200 +#endif // // Touch UI for FTDI EVE (FT800/FT810) displays @@ -2255,7 +2246,7 @@ EEPROM_W25Q //#define ANYCUBIC_LCD_I3MEGA //#define ANYCUBIC_LCD_CHIRON #if EITHER(ANYCUBIC_LCD_I3MEGA, ANYCUBIC_LCD_CHIRON) - #define ANYCUBIC_LCD_SERIAL_PORT 3 + #define LCD_SERIAL_PORT 3 // Default is 3 for Anycubic //#define ANYCUBIC_LCD_DEBUG #endif @@ -2412,7 +2403,6 @@ EEPROM_W25Q * *** CAUTION *** * * LED Type. Enable only one of the following two options. - * */ //#define RGB_LED //#define RGBW_LED diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index b27932bb8e..6816524389 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -29,9 +29,8 @@ * Some of these settings can damage your printer if improperly set! * * Basic settings can be found in Configuration.h - * */ -#define CONFIGURATION_ADV_H_VERSION 020006 +#define CONFIGURATION_ADV_H_VERSION 020007 // @section temperature @@ -738,7 +737,6 @@ * | 4 3 | 1 4 | 2 1 | 3 2 | * | | | | | * | 1 2 | 2 3 | 3 4 | 4 1 | - * */ #ifndef Z_STEPPER_ALIGN_XY //#define Z_STEPPERS_ORIENTATION 0 @@ -771,9 +769,8 @@ // // Add the G35 command to read bed corners to help adjust screws. Requires a bed probe. // -//#define ASSISTED_TRAMMING +#define ASSISTED_TRAMMING #if ENABLED(ASSISTED_TRAMMING) - // Define positions for probing points, use the hotend as reference not the sensor. #define TRAMMING_POINT_XY { { 20, 20 }, { 200, 20 }, { 200, 200 }, { 20, 200 } } @@ -786,6 +783,9 @@ // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G35 + // Add a menu item for Assisted Tramming + //#define ASSISTED_TRAMMING_MENU_ITEM + /** * Screw thread: * M3: 30 = Clockwise, 31 = Counter-Clockwise @@ -793,7 +793,6 @@ * M5: 50 = Clockwise, 51 = Counter-Clockwise */ #define TRAMMING_SCREW_THREAD 30 - #endif // @section motion @@ -1025,7 +1024,7 @@ // @section lcd #if EITHER(ULTIPANEL, EXTENSIBLE_UI) - #define MANUAL_FEEDRATE { 50*60, 50*60, 4*60, 60 } // (mm/min) Feedrates for manual moves along X, Y, Z, E from panel + #define MANUAL_FEEDRATE { 50*60, 50*60, 4*60, 2*60 } // (mm/min) Feedrates for manual moves along X, Y, Z, E from panel #define SHORT_MANUAL_Z_MOVE 0.025 // (mm) Smallest manual Z move (< 0.1mm) #if ENABLED(ULTIPANEL) #define MANUAL_E_MOVES_RELATIVE // Display extruder move distance rather than "position" @@ -1036,8 +1035,8 @@ // Change values more rapidly when the encoder is rotated faster #define ENCODER_RATE_MULTIPLIER #if ENABLED(ENCODER_RATE_MULTIPLIER) - #define ENCODER_10X_STEPS_PER_SEC 50 // (steps/s) Encoder rate for 10x speed - #define ENCODER_100X_STEPS_PER_SEC 200 // (steps/s) Encoder rate for 100x speed + #define ENCODER_10X_STEPS_PER_SEC 30 // (steps/s) Encoder rate for 10x speed + #define ENCODER_100X_STEPS_PER_SEC 80 // (steps/s) Encoder rate for 100x speed #endif // Play a beep when the feedrate is changed from the Status Screen @@ -1105,23 +1104,26 @@ #define BOOTSCREEN_TIMEOUT 200 // (ms) Total Duration to display the boot screen(s) #endif -#if HAS_GRAPHICAL_LCD && EITHER(SDSUPPORT, LCD_SET_PROGRESS_MANUALLY) - //#define PRINT_PROGRESS_SHOW_DECIMALS // Show progress with decimal digits - //#define SHOW_REMAINING_TIME // Display estimated time to completion +#if EITHER(SDSUPPORT, LCD_SET_PROGRESS_MANUALLY) && ANY(HAS_MARLINUI_U8GLIB, HAS_MARLINUI_HD44780, IS_TFTGLCD_PANEL) + //#define SHOW_REMAINING_TIME // Display estimated time to completion #if ENABLED(SHOW_REMAINING_TIME) - //#define USE_M73_REMAINING_TIME // Use remaining time from M73 command instead of estimation - //#define ROTATE_PROGRESS_DISPLAY // Display (P)rogress, (E)lapsed, and (R)emaining time + //#define USE_M73_REMAINING_TIME // Use remaining time from M73 command instead of estimation + //#define ROTATE_PROGRESS_DISPLAY // Display (P)rogress, (E)lapsed, and (R)emaining time #endif -#endif -#if HAS_CHARACTER_LCD && EITHER(SDSUPPORT, LCD_SET_PROGRESS_MANUALLY) - //#define LCD_PROGRESS_BAR // Show a progress bar on HD44780 LCDs for SD printing - #if ENABLED(LCD_PROGRESS_BAR) - #define PROGRESS_BAR_BAR_TIME 2000 // (ms) Amount of time to show the bar - #define PROGRESS_BAR_MSG_TIME 3000 // (ms) Amount of time to show the status message - #define PROGRESS_MSG_EXPIRE 0 // (ms) Amount of time to retain the status message (0=forever) - //#define PROGRESS_MSG_ONCE // Show the message for MSG_TIME then clear it - //#define LCD_PROGRESS_BAR_TEST // Add a menu item to test the progress bar + #if HAS_MARLINUI_U8GLIB + //#define PRINT_PROGRESS_SHOW_DECIMALS // Show progress with decimal digits + #endif + + #if EITHER(HAS_MARLINUI_HD44780, IS_TFTGLCD_PANEL) + //#define LCD_PROGRESS_BAR // Show a progress bar on HD44780 LCDs for SD printing + #if ENABLED(LCD_PROGRESS_BAR) + #define PROGRESS_BAR_BAR_TIME 2000 // (ms) Amount of time to show the bar + #define PROGRESS_BAR_MSG_TIME 3000 // (ms) Amount of time to show the status message + #define PROGRESS_MSG_EXPIRE 0 // (ms) Amount of time to retain the status message (0=forever) + //#define PROGRESS_MSG_ONCE // Show the message for MSG_TIME then clear it + //#define LCD_PROGRESS_BAR_TEST // Add a menu item to test the progress bar + #endif #endif #endif @@ -1164,6 +1166,7 @@ #if ENABLED(POWER_LOSS_RECOVERY) #define PLR_ENABLED_DEFAULT false // Power Loss Recovery enabled by default. (Set with 'M413 Sn' & M500) //#define BACKUP_POWER_SUPPLY // Backup power / UPS to move the steppers on power loss + //#define POWER_LOSS_RECOVER_ZHOME // Z homing is needed for proper recovery. 99.9% of the time this should be disabled! //#define POWER_LOSS_ZRAISE 2 // (mm) Z axis raise on resume (on power loss with UPS) //#define POWER_LOSS_PIN 44 // Pin to detect power loss. Set to -1 to disable default pin on boards without module. //#define POWER_LOSS_STATE HIGH // State of pin indicating power loss @@ -1394,18 +1397,18 @@ //#define MARLIN_SNAKE //#define GAMES_EASTER_EGG // Add extra blank lines above the "Games" sub-menu -#endif // HAS_GRAPHICAL_LCD +#endif // HAS_MARLINUI_U8GLIB // // Additional options for DGUS / DWIN displays // #if HAS_DGUS_LCD - #define DGUS_SERIAL_PORT 3 - #define DGUS_BAUDRATE 115200 + #define LCD_SERIAL_PORT 3 + #define LCD_BAUDRATE 115200 #define DGUS_RX_BUFFER_SIZE 128 #define DGUS_TX_BUFFER_SIZE 48 - //#define DGUS_SERIAL_STATS_RX_BUFFER_OVERRUNS // Fix Rx overrun situation (Currently only for AVR) + //#define SERIAL_STATS_RX_BUFFER_OVERRUNS // Fix Rx overrun situation (Currently only for AVR) #define DGUS_UPDATE_INTERVAL_MS 500 // (ms) Interval between automatic screen updates @@ -1571,6 +1574,7 @@ #if ENABLED(BABYSTEPPING) //#define INTEGRATED_BABYSTEPPING // EXPERIMENTAL integration of babystepping into the Stepper ISR //#define BABYSTEP_WITHOUT_HOMING + #define BABYSTEP_ALWAYS_AVAILABLE // Allow babystepping at all times (not just during movement). //#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA! #define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way //#define BABYSTEP_MILLIMETER_UNITS // Specify BABYSTEP_MULTIPLICATOR_(XY|Z) in mm instead of micro-steps @@ -1581,8 +1585,7 @@ #if ENABLED(DOUBLECLICK_FOR_Z_BABYSTEPPING) #define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds. // Note: Extra time may be added to mitigate controller latency. - //#define BABYSTEP_ALWAYS_AVAILABLE // Allow babystepping at all times (not just during movement). - #define MOVE_Z_WHEN_IDLE // Jump to the move Z menu on doubleclick when printer is idle. + //#define MOVE_Z_WHEN_IDLE // Jump to the move Z menu on doubleclick when printer is idle. #if ENABLED(MOVE_Z_WHEN_IDLE) #define MOVE_Z_IDLE_MULTIPLICATOR 1 // Multiply 1mm by this factor for the move step size. #endif @@ -1949,7 +1952,6 @@ * Be sure to turn off auto-retract during filament change. * * Note that M207 / M208 / M209 settings are saved to EEPROM. - * */ //#define FWRETRACT #if ENABLED(FWRETRACT) @@ -1975,7 +1977,7 @@ * Universal tool change settings. * Applies to all types of extruders except where explicitly noted. */ -#if EXTRUDERS > 1 +#if HAS_MULTI_EXTRUDER // Z raise distance for tool-change, as needed for some extruders #define TOOLCHANGE_ZRAISE 2 // (mm) //#define TOOLCHANGE_ZRAISE_BEFORE_RETRACT // Apply raise before swap retraction (if enabled) @@ -2039,7 +2041,7 @@ //#define TOOLCHANGE_PARK_X_ONLY // X axis only move //#define TOOLCHANGE_PARK_Y_ONLY // Y axis only move #endif -#endif // EXTRUDERS > 1 +#endif // HAS_MULTI_EXTRUDER /** * Advanced Pause @@ -2486,7 +2488,7 @@ #define E7_HYBRID_THRESHOLD 30 /** - * Use StallGuard2 to home / probe X, Y, Z. + * Use StallGuard to home / probe X, Y, Z. * * TMC2130, TMC2160, TMC2209, TMC2660, TMC5130, and TMC5160 only * Connect the stepper driver's DIAG1 pin to the X/Y endstop pin. @@ -2507,6 +2509,8 @@ * * IMPROVE_HOMING_RELIABILITY tunes acceleration and jerk when * homing and adds a guard period for endstop triggering. + * + * Comment *_STALL_SENSITIVITY to disable sensorless homing for that axis. */ //#define SENSORLESS_HOMING // StallGuard capable drivers only @@ -3227,6 +3231,7 @@ //#define HOST_ACTION_COMMANDS #if ENABLED(HOST_ACTION_COMMANDS) //#define HOST_PROMPT_SUPPORT + //#define HOST_START_MENU_ITEM // Add a menu item that tells the host to start #endif /** @@ -3334,6 +3339,7 @@ #define JOY_X_LIMITS { 5600, 8190-100, 8190+100, 10800 } // min, deadzone start, deadzone end, max #define JOY_Y_LIMITS { 5600, 8250-100, 8250+100, 11000 } #define JOY_Z_LIMITS { 4800, 8080-100, 8080+100, 11550 } + //#define JOYSTICK_DEBUG #endif /** @@ -3411,10 +3417,10 @@ #if ENABLED(PRUSA_MMU2) // Serial port used for communication with MMU2. - // For AVR enable the UART port used for the MMU. (e.g., internalSerial) + // For AVR enable the UART port used for the MMU. (e.g., mmuSerial) // For 32-bit boards check your HAL for available serial ports. (e.g., Serial2) - #define INTERNAL_SERIAL_PORT 2 - #define MMU2_SERIAL internalSerial + #define MMU2_SERIAL_PORT 2 + #define MMU2_SERIAL mmuSerial // Use hardware reset for MMU if a pin is defined for it //#define MMU2_RST_PIN 23 @@ -3465,7 +3471,7 @@ */ //#define MMU_EXTRUDER_SENSOR #if ENABLED(MMU_EXTRUDER_SENSOR) - #define MMU_LOADING_ATTEMPTS_NR 5 //max. number of attempts to load filament if first load fail + #define MMU_LOADING_ATTEMPTS_NR 5 // max. number of attempts to load filament if first load fail #endif /** diff --git a/Marlin/Makefile b/Marlin/Makefile index 95135ab594..68dd05bdfb 100644 --- a/Marlin/Makefile +++ b/Marlin/Makefile @@ -170,110 +170,114 @@ else ifeq ($(HARDWARE_MOTHERBOARD),1100) else ifeq ($(HARDWARE_MOTHERBOARD),1101) # Velleman K8400 Controller (derived from 3Drag Controller) else ifeq ($(HARDWARE_MOTHERBOARD),1102) -# Velleman K8600 Controller (derived from 3Drag Controller) +# Velleman K8600 Controller (Vertex Nano) else ifeq ($(HARDWARE_MOTHERBOARD),1103) -# 2PrintBeta BAM&DICE with STK drivers +# Velleman K8800 Controller (Vertex Delta) else ifeq ($(HARDWARE_MOTHERBOARD),1104) -# 2PrintBeta BAM&DICE Due with STK drivers +# 2PrintBeta BAM&DICE with STK drivers else ifeq ($(HARDWARE_MOTHERBOARD),1105) -# MKS BASE v1.0 +# 2PrintBeta BAM&DICE Due with STK drivers else ifeq ($(HARDWARE_MOTHERBOARD),1106) -# MKS v1.4 with A4982 stepper drivers +# MKS BASE v1.0 else ifeq ($(HARDWARE_MOTHERBOARD),1107) -# MKS v1.5 with Allegro A4982 stepper drivers +# MKS v1.4 with A4982 stepper drivers else ifeq ($(HARDWARE_MOTHERBOARD),1108) -# MKS v1.6 with Allegro A4982 stepper drivers +# MKS v1.5 with Allegro A4982 stepper drivers else ifeq ($(HARDWARE_MOTHERBOARD),1109) -# MKS BASE 1.0 with Heroic HR4982 stepper drivers +# MKS v1.6 with Allegro A4982 stepper drivers else ifeq ($(HARDWARE_MOTHERBOARD),1110) -# MKS GEN v1.3 or 1.4 +# MKS BASE 1.0 with Heroic HR4982 stepper drivers else ifeq ($(HARDWARE_MOTHERBOARD),1111) -# MKS GEN L +# MKS GEN v1.3 or 1.4 else ifeq ($(HARDWARE_MOTHERBOARD),1112) -# zrib V2.0 control board (Chinese knock off RAMPS replica) +# MKS GEN L else ifeq ($(HARDWARE_MOTHERBOARD),1113) -# BigTreeTech or BIQU KFB2.0 +# zrib V2.0 control board (Chinese knock off RAMPS replica) else ifeq ($(HARDWARE_MOTHERBOARD),1114) -# Felix 2.0+ Electronics Board (RAMPS like) +# BigTreeTech or BIQU KFB2.0 else ifeq ($(HARDWARE_MOTHERBOARD),1115) -# Invent-A-Part RigidBoard +# Felix 2.0+ Electronics Board (RAMPS like) else ifeq ($(HARDWARE_MOTHERBOARD),1116) -# Invent-A-Part RigidBoard V2 +# Invent-A-Part RigidBoard else ifeq ($(HARDWARE_MOTHERBOARD),1117) -# Sainsmart 2-in-1 board +# Invent-A-Part RigidBoard V2 else ifeq ($(HARDWARE_MOTHERBOARD),1118) -# Ultimaker +# Sainsmart 2-in-1 board else ifeq ($(HARDWARE_MOTHERBOARD),1119) -# Ultimaker (Older electronics. Pre 1.5.4. This is rare) +# Ultimaker else ifeq ($(HARDWARE_MOTHERBOARD),1120) +# Ultimaker (Older electronics. Pre 1.5.4. This is rare) +else ifeq ($(HARDWARE_MOTHERBOARD),1121) MCU ?= atmega1280 # Azteeg X3 -else ifeq ($(HARDWARE_MOTHERBOARD),1121) -# Azteeg X3 Pro else ifeq ($(HARDWARE_MOTHERBOARD),1122) -# Ultimainboard 2.x (Uses TEMP_SENSOR 20) +# Azteeg X3 Pro else ifeq ($(HARDWARE_MOTHERBOARD),1123) -# Rumba +# Ultimainboard 2.x (Uses TEMP_SENSOR 20) else ifeq ($(HARDWARE_MOTHERBOARD),1124) -# Raise3D Rumba +# Rumba else ifeq ($(HARDWARE_MOTHERBOARD),1125) -# Rapide Lite RL200 Rumba +# Raise3D Rumba else ifeq ($(HARDWARE_MOTHERBOARD),1126) -# Formbot T-Rex 2 Plus +# Rapide Lite RL200 Rumba else ifeq ($(HARDWARE_MOTHERBOARD),1127) -# Formbot T-Rex 3 +# Formbot T-Rex 2 Plus else ifeq ($(HARDWARE_MOTHERBOARD),1128) -# Formbot Raptor +# Formbot T-Rex 3 else ifeq ($(HARDWARE_MOTHERBOARD),1129) -# Formbot Raptor 2 +# Formbot Raptor else ifeq ($(HARDWARE_MOTHERBOARD),1130) -# bq ZUM Mega 3D +# Formbot Raptor 2 else ifeq ($(HARDWARE_MOTHERBOARD),1131) -# MakeBoard Mini v2.1.2 is a control board sold by MicroMake +# bq ZUM Mega 3D else ifeq ($(HARDWARE_MOTHERBOARD),1132) -# TriGorilla Anycubic version 1.3 based on RAMPS EFB +# MakeBoard Mini v2.1.2 is a control board sold by MicroMake else ifeq ($(HARDWARE_MOTHERBOARD),1133) -# TriGorilla Anycubic version 1.4 based on RAMPS EFB +# TriGorilla Anycubic version 1.3 based on RAMPS EFB else ifeq ($(HARDWARE_MOTHERBOARD),1134) -# TriGorilla Anycubic version 1.4 Rev 1.1 +# TriGorilla Anycubic version 1.4 based on RAMPS EFB else ifeq ($(HARDWARE_MOTHERBOARD),1135) -# Creality: Ender-4, CR-8 +# TriGorilla Anycubic version 1.4 Rev 1.1 else ifeq ($(HARDWARE_MOTHERBOARD),1136) -# Creality: CR10S, CR20, CR-X +# Creality: Ender-4, CR-8 else ifeq ($(HARDWARE_MOTHERBOARD),1137) -# Dagoma F5 +# Creality: CR10S, CR20, CR-X else ifeq ($(HARDWARE_MOTHERBOARD),1138) -# FYSETC F6 1.3 +# Dagoma F5 else ifeq ($(HARDWARE_MOTHERBOARD),1139) -# FYSETC F6 1.5 +# FYSETC F6 1.3 else ifeq ($(HARDWARE_MOTHERBOARD),1140) -# Duplicator i3 Plus +# FYSETC F6 1.5 else ifeq ($(HARDWARE_MOTHERBOARD),1141) -# VORON +# Duplicator i3 Plus else ifeq ($(HARDWARE_MOTHERBOARD),1142) -# TRONXY V3 1.0 +# VORON else ifeq ($(HARDWARE_MOTHERBOARD),1143) -# Z-Bolt X Series +# TRONXY V3 1.0 else ifeq ($(HARDWARE_MOTHERBOARD),1144) -# TT OSCAR +# Z-Bolt X Series else ifeq ($(HARDWARE_MOTHERBOARD),1145) -# Overlord/Overlord Pro +# TT OSCAR else ifeq ($(HARDWARE_MOTHERBOARD),1146) -# ADIMLab Gantry v1 +# Overlord/Overlord Pro else ifeq ($(HARDWARE_MOTHERBOARD),1147) -# ADIMLab Gantry v2 +# ADIMLab Gantry v1 else ifeq ($(HARDWARE_MOTHERBOARD),1148) -# BIQU Tango V1 +# ADIMLab Gantry v2 else ifeq ($(HARDWARE_MOTHERBOARD),1149) -# MKS GEN L V2 +# BIQU Tango V1 else ifeq ($(HARDWARE_MOTHERBOARD),1150) -# Copymaster 3D +# MKS GEN L V2 else ifeq ($(HARDWARE_MOTHERBOARD),1151) -# Ortur 4 +# MKS GEN L V2.1 else ifeq ($(HARDWARE_MOTHERBOARD),1152) -# Tenlog D3 Hero +# Copymaster 3D else ifeq ($(HARDWARE_MOTHERBOARD),1153) +# Ortur 4 +else ifeq ($(HARDWARE_MOTHERBOARD),1154) +# Tenlog D3 Hero +else ifeq ($(HARDWARE_MOTHERBOARD),1155) # # RAMBo and derivatives @@ -694,7 +698,7 @@ ifeq ($(HARDWARE_VARIANT), Teensy) LIB_CXXSRC += usb_api.cpp 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"' + CDEFS += -DARDUINO_SAM_ARCHIM -DARDUINO_ARCH_SAM -D__SAM3X8E__ -DUSB_VID=0x27b1 -DUSB_PID=0x0001 -DUSBCON '-DUSB_MANUFACTURER="UltiMachine"' '-DUSB_PRODUCT_STRING="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_SRC += cortex_handlers.c iar_calls_sam3.c syscalls_sam3.c dtostrf.c itoa.c diff --git a/Marlin/Version.h b/Marlin/Version.h index 5ce04b2903..5759771f7f 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -28,7 +28,7 @@ /** * Marlin release version identifier */ -//#define SHORT_BUILD_VERSION "2.0.6.1" +//#define SHORT_BUILD_VERSION "2.0.7" /** * Verbose version identifier which should contain a reference to the location diff --git a/Marlin/src/HAL/AVR/HAL.h b/Marlin/src/HAL/AVR/HAL.h index 609375e386..b606d0c231 100644 --- a/Marlin/src/HAL/AVR/HAL.h +++ b/Marlin/src/HAL/AVR/HAL.h @@ -15,6 +15,7 @@ * * You should have received a copy of the GNU General Public License * along with this program. If not, see . + * */ #pragma once @@ -81,54 +82,29 @@ typedef int8_t pin_t; // Serial ports #ifdef USBCON - #if ENABLED(BLUETOOTH) - #define MYSERIAL0 bluetoothSerial - #else - #define MYSERIAL0 Serial - #endif - #define NUM_SERIAL 1 + #define MYSERIAL0 TERN(BLUETOOTH, bluetoothSerial, Serial) #else #if !WITHIN(SERIAL_PORT, -1, 3) #error "SERIAL_PORT must be from -1 to 3. Please update your configuration." #endif - #define MYSERIAL0 customizedSerial1 #ifdef SERIAL_PORT_2 #if !WITHIN(SERIAL_PORT_2, -1, 3) #error "SERIAL_PORT_2 must be from -1 to 3. Please update your configuration." - #elif SERIAL_PORT_2 == SERIAL_PORT - #error "SERIAL_PORT_2 must be different than SERIAL_PORT. Please update your configuration." #endif #define MYSERIAL1 customizedSerial2 - #define NUM_SERIAL 2 - #else - #define NUM_SERIAL 1 #endif #endif -#ifdef DGUS_SERIAL_PORT - #if !WITHIN(DGUS_SERIAL_PORT, -1, 3) - #error "DGUS_SERIAL_PORT must be from -1 to 3. Please update your configuration." - #elif DGUS_SERIAL_PORT == SERIAL_PORT - #error "DGUS_SERIAL_PORT must be different than SERIAL_PORT. Please update your configuration." - #elif defined(SERIAL_PORT_2) && DGUS_SERIAL_PORT == SERIAL_PORT_2 - #error "DGUS_SERIAL_PORT must be different than SERIAL_PORT_2. Please update your configuration." +#ifdef LCD_SERIAL_PORT + #if !WITHIN(LCD_SERIAL_PORT, -1, 3) + #error "LCD_SERIAL_PORT must be from -1 to 3. Please update your configuration." #endif - #define DGUS_SERIAL internalDgusSerial - - #define DGUS_SERIAL_GET_TX_BUFFER_FREE DGUS_SERIAL.get_tx_buffer_free -#endif - -#ifdef ANYCUBIC_LCD_SERIAL_PORT - #if !WITHIN(ANYCUBIC_LCD_SERIAL_PORT, -1, 3) - #error "ANYCUBIC_LCD_SERIAL_PORT must be from -1 to 3. Please update your configuration." - #elif ANYCUBIC_LCD_SERIAL_PORT == SERIAL_PORT - #error "ANYCUBIC_LCD_SERIAL_PORT must be different than SERIAL_PORT. Please update your configuration." - #elif defined(SERIAL_PORT_2) && ANYCUBIC_LCD_SERIAL_PORT == SERIAL_PORT_2 - #error "ANYCUBIC_LCD_SERIAL_PORT must be different than SERIAL_PORT_2. Please update your configuration." + #define LCD_SERIAL lcdSerial + #if HAS_DGUS_LCD + #define SERIAL_GET_TX_BUFFER_FREE() LCD_SERIAL.get_tx_buffer_free() #endif - #define ANYCUBIC_LCD_SERIAL anycubicLcdSerial #endif // ------------------------ diff --git a/Marlin/src/HAL/AVR/MarlinSerial.cpp b/Marlin/src/HAL/AVR/MarlinSerial.cpp index 3d44a3f59f..63599efd41 100644 --- a/Marlin/src/HAL/AVR/MarlinSerial.cpp +++ b/Marlin/src/HAL/AVR/MarlinSerial.cpp @@ -40,407 +40,370 @@ #if !defined(USBCON) && (defined(UBRRH) || defined(UBRR0H) || defined(UBRR1H) || defined(UBRR2H) || defined(UBRR3H)) - #include "MarlinSerial.h" - #include "../../MarlinCore.h" +#include "MarlinSerial.h" +#include "../../MarlinCore.h" + +#if ENABLED(DIRECT_STEPPING) + #include "../../feature/direct_stepping.h" +#endif + +template typename MarlinSerial::ring_buffer_r MarlinSerial::rx_buffer = { 0, 0, { 0 } }; +template typename MarlinSerial::ring_buffer_t MarlinSerial::tx_buffer = { 0 }; +template bool MarlinSerial::_written = false; +template uint8_t MarlinSerial::xon_xoff_state = MarlinSerial::XON_XOFF_CHAR_SENT | MarlinSerial::XON_CHAR; +template uint8_t MarlinSerial::rx_dropped_bytes = 0; +template uint8_t MarlinSerial::rx_buffer_overruns = 0; +template uint8_t MarlinSerial::rx_framing_errors = 0; +template typename MarlinSerial::ring_buffer_pos_t MarlinSerial::rx_max_enqueued = 0; + +// A SW memory barrier, to ensure GCC does not overoptimize loops +#define sw_barrier() asm volatile("": : :"memory"); + +#include "../../feature/e_parser.h" + +// "Atomically" read the RX head index value without disabling interrupts: +// This MUST be called with RX interrupts enabled, and CAN'T be called +// from the RX ISR itself! +template +FORCE_INLINE typename MarlinSerial::ring_buffer_pos_t MarlinSerial::atomic_read_rx_head() { + if (Cfg::RX_SIZE > 256) { + // Keep reading until 2 consecutive reads return the same value, + // meaning there was no update in-between caused by an interrupt. + // This works because serial RX interrupts happen at a slower rate + // than successive reads of a variable, so 2 consecutive reads with + // the same value means no interrupt updated it. + ring_buffer_pos_t vold, vnew = rx_buffer.head; + sw_barrier(); + do { + vold = vnew; + vnew = rx_buffer.head; + sw_barrier(); + } while (vold != vnew); + return vnew; + } + else { + // With an 8bit index, reads are always atomic. No need for special handling + return rx_buffer.head; + } +} + +template +volatile bool MarlinSerial::rx_tail_value_not_stable = false; +template +volatile uint16_t MarlinSerial::rx_tail_value_backup = 0; + +// Set RX tail index, taking into account the RX ISR could interrupt +// the write to this variable in the middle - So a backup strategy +// is used to ensure reads of the correct values. +// -Must NOT be called from the RX ISR - +template +FORCE_INLINE void MarlinSerial::atomic_set_rx_tail(typename MarlinSerial::ring_buffer_pos_t value) { + if (Cfg::RX_SIZE > 256) { + // Store the new value in the backup + rx_tail_value_backup = value; + sw_barrier(); + // Flag we are about to change the true value + rx_tail_value_not_stable = true; + sw_barrier(); + // Store the new value + rx_buffer.tail = value; + sw_barrier(); + // Signal the new value is completely stored into the value + rx_tail_value_not_stable = false; + sw_barrier(); + } + else + rx_buffer.tail = value; +} + +// Get the RX tail index, taking into account the read could be +// interrupting in the middle of the update of that index value +// -Called from the RX ISR - +template +FORCE_INLINE typename MarlinSerial::ring_buffer_pos_t MarlinSerial::atomic_read_rx_tail() { + if (Cfg::RX_SIZE > 256) { + // If the true index is being modified, return the backup value + if (rx_tail_value_not_stable) return rx_tail_value_backup; + } + // The true index is stable, return it + return rx_buffer.tail; +} + +// (called with RX interrupts disabled) +template +FORCE_INLINE void MarlinSerial::store_rxd_char() { + + static EmergencyParser::State emergency_state; // = EP_RESET + + // This must read the R_UCSRA register before reading the received byte to detect error causes + if (Cfg::DROPPED_RX && B_DOR && !++rx_dropped_bytes) --rx_dropped_bytes; + if (Cfg::RX_OVERRUNS && B_DOR && !++rx_buffer_overruns) --rx_buffer_overruns; + if (Cfg::RX_FRAMING_ERRORS && B_FE && !++rx_framing_errors) --rx_framing_errors; + + // Read the character from the USART + uint8_t c = R_UDR; #if ENABLED(DIRECT_STEPPING) - #include "../../feature/direct_stepping.h" + if (page_manager.maybe_store_rxd_char(c)) return; #endif - template typename MarlinSerial::ring_buffer_r MarlinSerial::rx_buffer = { 0, 0, { 0 } }; - template typename MarlinSerial::ring_buffer_t MarlinSerial::tx_buffer = { 0 }; - template bool MarlinSerial::_written = false; - template uint8_t MarlinSerial::xon_xoff_state = MarlinSerial::XON_XOFF_CHAR_SENT | MarlinSerial::XON_CHAR; - template uint8_t MarlinSerial::rx_dropped_bytes = 0; - template uint8_t MarlinSerial::rx_buffer_overruns = 0; - template uint8_t MarlinSerial::rx_framing_errors = 0; - template typename MarlinSerial::ring_buffer_pos_t MarlinSerial::rx_max_enqueued = 0; - - // A SW memory barrier, to ensure GCC does not overoptimize loops - #define sw_barrier() asm volatile("": : :"memory"); - - #include "../../feature/e_parser.h" - - // "Atomically" read the RX head index value without disabling interrupts: - // This MUST be called with RX interrupts enabled, and CAN'T be called - // from the RX ISR itself! - template - FORCE_INLINE typename MarlinSerial::ring_buffer_pos_t MarlinSerial::atomic_read_rx_head() { - if (Cfg::RX_SIZE > 256) { - // Keep reading until 2 consecutive reads return the same value, - // meaning there was no update in-between caused by an interrupt. - // This works because serial RX interrupts happen at a slower rate - // than successive reads of a variable, so 2 consecutive reads with - // the same value means no interrupt updated it. - ring_buffer_pos_t vold, vnew = rx_buffer.head; - sw_barrier(); - do { - vold = vnew; - vnew = rx_buffer.head; - sw_barrier(); - } while (vold != vnew); - return vnew; - } - else { - // With an 8bit index, reads are always atomic. No need for special handling - return rx_buffer.head; - } - } + // Get the tail - Nothing can alter its value while this ISR is executing, but there's + // a chance that this ISR interrupted the main process while it was updating the index. + // The backup mechanism ensures the correct value is always returned. + const ring_buffer_pos_t t = atomic_read_rx_tail(); - template - volatile bool MarlinSerial::rx_tail_value_not_stable = false; - template - volatile uint16_t MarlinSerial::rx_tail_value_backup = 0; - - // Set RX tail index, taking into account the RX ISR could interrupt - // the write to this variable in the middle - So a backup strategy - // is used to ensure reads of the correct values. - // -Must NOT be called from the RX ISR - - template - FORCE_INLINE void MarlinSerial::atomic_set_rx_tail(typename MarlinSerial::ring_buffer_pos_t value) { - if (Cfg::RX_SIZE > 256) { - // Store the new value in the backup - rx_tail_value_backup = value; - sw_barrier(); - // Flag we are about to change the true value - rx_tail_value_not_stable = true; - sw_barrier(); - // Store the new value - rx_buffer.tail = value; - sw_barrier(); - // Signal the new value is completely stored into the value - rx_tail_value_not_stable = false; - sw_barrier(); - } - else - rx_buffer.tail = value; - } + // Get the head pointer - This ISR is the only one that modifies its value, so it's safe to read here + ring_buffer_pos_t h = rx_buffer.head; - // Get the RX tail index, taking into account the read could be - // interrupting in the middle of the update of that index value - // -Called from the RX ISR - - template - FORCE_INLINE typename MarlinSerial::ring_buffer_pos_t MarlinSerial::atomic_read_rx_tail() { - if (Cfg::RX_SIZE > 256) { - // If the true index is being modified, return the backup value - if (rx_tail_value_not_stable) return rx_tail_value_backup; - } - // The true index is stable, return it - return rx_buffer.tail; - } + // Get the next element + ring_buffer_pos_t i = (ring_buffer_pos_t)(h + 1) & (ring_buffer_pos_t)(Cfg::RX_SIZE - 1); - // (called with RX interrupts disabled) - template - FORCE_INLINE void MarlinSerial::store_rxd_char() { + if (Cfg::EMERGENCYPARSER) emergency_parser.update(emergency_state, c); + + // If the character is to be stored at the index just before the tail + // (such that the head would advance to the current tail), the RX FIFO is + // full, so don't write the character or advance the head. + if (i != t) { + rx_buffer.buffer[h] = c; + h = i; + } + else if (Cfg::DROPPED_RX && !++rx_dropped_bytes) + --rx_dropped_bytes; - static EmergencyParser::State emergency_state; // = EP_RESET + if (Cfg::MAX_RX_QUEUED) { + // Calculate count of bytes stored into the RX buffer + const ring_buffer_pos_t rx_count = (ring_buffer_pos_t)(h - t) & (ring_buffer_pos_t)(Cfg::RX_SIZE - 1); - // This must read the R_UCSRA register before reading the received byte to detect error causes - if (Cfg::DROPPED_RX && B_DOR && !++rx_dropped_bytes) --rx_dropped_bytes; - if (Cfg::RX_OVERRUNS && B_DOR && !++rx_buffer_overruns) --rx_buffer_overruns; - if (Cfg::RX_FRAMING_ERRORS && B_FE && !++rx_framing_errors) --rx_framing_errors; + // Keep track of the maximum count of enqueued bytes + NOLESS(rx_max_enqueued, rx_count); + } - // Read the character from the USART - uint8_t c = R_UDR; + if (Cfg::XONOFF) { + // If the last char that was sent was an XON + if ((xon_xoff_state & XON_XOFF_CHAR_MASK) == XON_CHAR) { - #if ENABLED(DIRECT_STEPPING) - if (page_manager.maybe_store_rxd_char(c)) return; - #endif + // Bytes stored into the RX buffer + const ring_buffer_pos_t rx_count = (ring_buffer_pos_t)(h - t) & (ring_buffer_pos_t)(Cfg::RX_SIZE - 1); - // Get the tail - Nothing can alter its value while this ISR is executing, but there's - // a chance that this ISR interrupted the main process while it was updating the index. - // The backup mechanism ensures the correct value is always returned. - const ring_buffer_pos_t t = atomic_read_rx_tail(); + // If over 12.5% of RX buffer capacity, send XOFF before running out of + // RX buffer space .. 325 bytes @ 250kbits/s needed to let the host react + // and stop sending bytes. This translates to 13mS propagation time. + if (rx_count >= (Cfg::RX_SIZE) / 8) { - // Get the head pointer - This ISR is the only one that modifies its value, so it's safe to read here - ring_buffer_pos_t h = rx_buffer.head; + // At this point, definitely no TX interrupt was executing, since the TX ISR can't be preempted. + // Don't enable the TX interrupt here as a means to trigger the XOFF char, because if it happens + // to be in the middle of trying to disable the RX interrupt in the main program, eventually the + // enabling of the TX interrupt could be undone. The ONLY reliable thing this can do to ensure + // the sending of the XOFF char is to send it HERE AND NOW. - // Get the next element - ring_buffer_pos_t i = (ring_buffer_pos_t)(h + 1) & (ring_buffer_pos_t)(Cfg::RX_SIZE - 1); + // About to send the XOFF char + xon_xoff_state = XOFF_CHAR | XON_XOFF_CHAR_SENT; - if (Cfg::EMERGENCYPARSER) emergency_parser.update(emergency_state, c); + // Wait until the TX register becomes empty and send it - Here there could be a problem + // - While waiting for the TX register to empty, the RX register could receive a new + // character. This must also handle that situation! + while (!B_UDRE) { - // If the character is to be stored at the index just before the tail - // (such that the head would advance to the current tail), the RX FIFO is - // full, so don't write the character or advance the head. - if (i != t) { - rx_buffer.buffer[h] = c; - h = i; - } - else if (Cfg::DROPPED_RX && !++rx_dropped_bytes) - --rx_dropped_bytes; + if (B_RXC) { + // A char arrived while waiting for the TX buffer to be empty - Receive and process it! - if (Cfg::MAX_RX_QUEUED) { - // Calculate count of bytes stored into the RX buffer - const ring_buffer_pos_t rx_count = (ring_buffer_pos_t)(h - t) & (ring_buffer_pos_t)(Cfg::RX_SIZE - 1); + i = (ring_buffer_pos_t)(h + 1) & (ring_buffer_pos_t)(Cfg::RX_SIZE - 1); - // Keep track of the maximum count of enqueued bytes - NOLESS(rx_max_enqueued, rx_count); - } + // Read the character from the USART + c = R_UDR; - if (Cfg::XONOFF) { - // If the last char that was sent was an XON - if ((xon_xoff_state & XON_XOFF_CHAR_MASK) == XON_CHAR) { - - // Bytes stored into the RX buffer - const ring_buffer_pos_t rx_count = (ring_buffer_pos_t)(h - t) & (ring_buffer_pos_t)(Cfg::RX_SIZE - 1); - - // If over 12.5% of RX buffer capacity, send XOFF before running out of - // RX buffer space .. 325 bytes @ 250kbits/s needed to let the host react - // and stop sending bytes. This translates to 13mS propagation time. - if (rx_count >= (Cfg::RX_SIZE) / 8) { - - // At this point, definitely no TX interrupt was executing, since the TX ISR can't be preempted. - // Don't enable the TX interrupt here as a means to trigger the XOFF char, because if it happens - // to be in the middle of trying to disable the RX interrupt in the main program, eventually the - // enabling of the TX interrupt could be undone. The ONLY reliable thing this can do to ensure - // the sending of the XOFF char is to send it HERE AND NOW. - - // About to send the XOFF char - xon_xoff_state = XOFF_CHAR | XON_XOFF_CHAR_SENT; - - // Wait until the TX register becomes empty and send it - Here there could be a problem - // - While waiting for the TX register to empty, the RX register could receive a new - // character. This must also handle that situation! - while (!B_UDRE) { - - if (B_RXC) { - // A char arrived while waiting for the TX buffer to be empty - Receive and process it! - - i = (ring_buffer_pos_t)(h + 1) & (ring_buffer_pos_t)(Cfg::RX_SIZE - 1); - - // Read the character from the USART - c = R_UDR; - - if (Cfg::EMERGENCYPARSER) emergency_parser.update(emergency_state, c); - - // If the character is to be stored at the index just before the tail - // (such that the head would advance to the current tail), the FIFO is - // full, so don't write the character or advance the head. - if (i != t) { - rx_buffer.buffer[h] = c; - h = i; - } - else if (Cfg::DROPPED_RX && !++rx_dropped_bytes) - --rx_dropped_bytes; - } - sw_barrier(); - } + if (Cfg::EMERGENCYPARSER) emergency_parser.update(emergency_state, c); - R_UDR = XOFF_CHAR; - - // Clear the TXC bit -- "can be cleared by writing a one to its bit - // location". This makes sure flush() won't return until the bytes - // actually got written - B_TXC = 1; - - // At this point there could be a race condition between the write() function - // and this sending of the XOFF char. This interrupt could happen between the - // wait to be empty TX buffer loop and the actual write of the character. Since - // the TX buffer is full because it's sending the XOFF char, the only way to be - // sure the write() function will succeed is to wait for the XOFF char to be - // completely sent. Since an extra character could be received during the wait - // it must also be handled! - while (!B_UDRE) { - - if (B_RXC) { - // A char arrived while waiting for the TX buffer to be empty - Receive and process it! - - i = (ring_buffer_pos_t)(h + 1) & (ring_buffer_pos_t)(Cfg::RX_SIZE - 1); - - // Read the character from the USART - c = R_UDR; - - if (Cfg::EMERGENCYPARSER) - emergency_parser.update(emergency_state, c); - - // If the character is to be stored at the index just before the tail - // (such that the head would advance to the current tail), the FIFO is - // full, so don't write the character or advance the head. - if (i != t) { - rx_buffer.buffer[h] = c; - h = i; - } - else if (Cfg::DROPPED_RX && !++rx_dropped_bytes) - --rx_dropped_bytes; + // If the character is to be stored at the index just before the tail + // (such that the head would advance to the current tail), the FIFO is + // full, so don't write the character or advance the head. + if (i != t) { + rx_buffer.buffer[h] = c; + h = i; } - sw_barrier(); + else if (Cfg::DROPPED_RX && !++rx_dropped_bytes) + --rx_dropped_bytes; } - - // At this point everything is ready. The write() function won't - // have any issues writing to the UART TX register if it needs to! + sw_barrier(); } - } - } - // Store the new head value - The main loop will retry until the value is stable - rx_buffer.head = h; - } + R_UDR = XOFF_CHAR; - // (called with TX irqs disabled) - template - FORCE_INLINE void MarlinSerial::_tx_udr_empty_irq() { - if (Cfg::TX_SIZE > 0) { - // Read positions - uint8_t t = tx_buffer.tail; - const uint8_t h = tx_buffer.head; + // Clear the TXC bit -- "can be cleared by writing a one to its bit + // location". This makes sure flush() won't return until the bytes + // actually got written + B_TXC = 1; - if (Cfg::XONOFF) { - // If an XON char is pending to be sent, do it now - if (xon_xoff_state == XON_CHAR) { + // At this point there could be a race condition between the write() function + // and this sending of the XOFF char. This interrupt could happen between the + // wait to be empty TX buffer loop and the actual write of the character. Since + // the TX buffer is full because it's sending the XOFF char, the only way to be + // sure the write() function will succeed is to wait for the XOFF char to be + // completely sent. Since an extra character could be received during the wait + // it must also be handled! + while (!B_UDRE) { - // Send the character - R_UDR = XON_CHAR; + if (B_RXC) { + // A char arrived while waiting for the TX buffer to be empty - Receive and process it! - // clear the TXC bit -- "can be cleared by writing a one to its bit - // location". This makes sure flush() won't return until the bytes - // actually got written - B_TXC = 1; + i = (ring_buffer_pos_t)(h + 1) & (ring_buffer_pos_t)(Cfg::RX_SIZE - 1); - // Remember we sent it. - xon_xoff_state = XON_CHAR | XON_XOFF_CHAR_SENT; + // Read the character from the USART + c = R_UDR; - // If nothing else to transmit, just disable TX interrupts. - if (h == t) B_UDRIE = 0; // (Non-atomic, could be reenabled by the main program, but eventually this will succeed) + if (Cfg::EMERGENCYPARSER) + emergency_parser.update(emergency_state, c); - return; + // If the character is to be stored at the index just before the tail + // (such that the head would advance to the current tail), the FIFO is + // full, so don't write the character or advance the head. + if (i != t) { + rx_buffer.buffer[h] = c; + h = i; + } + else if (Cfg::DROPPED_RX && !++rx_dropped_bytes) + --rx_dropped_bytes; + } + sw_barrier(); } - } - // If nothing to transmit, just disable TX interrupts. This could - // happen as the result of the non atomicity of the disabling of RX - // interrupts that could end reenabling TX interrupts as a side effect. - if (h == t) { - B_UDRIE = 0; // (Non-atomic, could be reenabled by the main program, but eventually this will succeed) - return; + // At this point everything is ready. The write() function won't + // have any issues writing to the UART TX register if it needs to! } - - // There is something to TX, Send the next byte - const uint8_t c = tx_buffer.buffer[t]; - t = (t + 1) & (Cfg::TX_SIZE - 1); - R_UDR = c; - tx_buffer.tail = t; - - // Clear the TXC bit (by writing a one to its bit location). - // Ensures flush() won't return until the bytes are actually written/ - B_TXC = 1; - - // Disable interrupts if there is nothing to transmit following this byte - if (h == t) B_UDRIE = 0; // (Non-atomic, could be reenabled by the main program, but eventually this will succeed) - } - } - - // Public Methods - template - void MarlinSerial::begin(const long baud) { - uint16_t baud_setting; - bool useU2X = true; - - #if F_CPU == 16000000UL && SERIAL_PORT == 0 - // Hard-coded exception for compatibility with the bootloader shipped - // with the Duemilanove and previous boards, and the firmware on the - // 8U2 on the Uno and Mega 2560. - if (baud == 57600) useU2X = false; - #endif - - R_UCSRA = 0; - if (useU2X) { - B_U2X = 1; - baud_setting = (F_CPU / 4 / baud - 1) / 2; } - else - baud_setting = (F_CPU / 8 / baud - 1) / 2; - - // assign the baud_setting, a.k.a. ubbr (USART Baud Rate Register) - R_UBRRH = baud_setting >> 8; - R_UBRRL = baud_setting; - - B_RXEN = 1; - B_TXEN = 1; - B_RXCIE = 1; - if (Cfg::TX_SIZE > 0) B_UDRIE = 0; - _written = false; } - template - void MarlinSerial::end() { - B_RXEN = 0; - B_TXEN = 0; - B_RXCIE = 0; - B_UDRIE = 0; - } + // Store the new head value - The main loop will retry until the value is stable + rx_buffer.head = h; +} - template - int MarlinSerial::peek() { - const ring_buffer_pos_t h = atomic_read_rx_head(), t = rx_buffer.tail; - return h == t ? -1 : rx_buffer.buffer[t]; - } +// (called with TX irqs disabled) +template +FORCE_INLINE void MarlinSerial::_tx_udr_empty_irq() { + if (Cfg::TX_SIZE > 0) { + // Read positions + uint8_t t = tx_buffer.tail; + const uint8_t h = tx_buffer.head; - template - int MarlinSerial::read() { - const ring_buffer_pos_t h = atomic_read_rx_head(); + if (Cfg::XONOFF) { + // If an XON char is pending to be sent, do it now + if (xon_xoff_state == XON_CHAR) { - // Read the tail. Main thread owns it, so it is safe to directly read it - ring_buffer_pos_t t = rx_buffer.tail; + // Send the character + R_UDR = XON_CHAR; - // If nothing to read, return now - if (h == t) return -1; + // clear the TXC bit -- "can be cleared by writing a one to its bit + // location". This makes sure flush() won't return until the bytes + // actually got written + B_TXC = 1; - // Get the next char - const int v = rx_buffer.buffer[t]; - t = (ring_buffer_pos_t)(t + 1) & (Cfg::RX_SIZE - 1); + // Remember we sent it. + xon_xoff_state = XON_CHAR | XON_XOFF_CHAR_SENT; - // Advance tail - Making sure the RX ISR will always get an stable value, even - // if it interrupts the writing of the value of that variable in the middle. - atomic_set_rx_tail(t); + // If nothing else to transmit, just disable TX interrupts. + if (h == t) B_UDRIE = 0; // (Non-atomic, could be reenabled by the main program, but eventually this will succeed) - if (Cfg::XONOFF) { - // If the XOFF char was sent, or about to be sent... - if ((xon_xoff_state & XON_XOFF_CHAR_MASK) == XOFF_CHAR) { - // Get count of bytes in the RX buffer - const ring_buffer_pos_t rx_count = (ring_buffer_pos_t)(h - t) & (ring_buffer_pos_t)(Cfg::RX_SIZE - 1); - if (rx_count < (Cfg::RX_SIZE) / 10) { - if (Cfg::TX_SIZE > 0) { - // Signal we want an XON character to be sent. - xon_xoff_state = XON_CHAR; - // Enable TX ISR. Non atomic, but it will eventually enable them - B_UDRIE = 1; - } - else { - // If not using TX interrupts, we must send the XON char now - xon_xoff_state = XON_CHAR | XON_XOFF_CHAR_SENT; - while (!B_UDRE) sw_barrier(); - R_UDR = XON_CHAR; - } - } + return; } } - return v; - } + // If nothing to transmit, just disable TX interrupts. This could + // happen as the result of the non atomicity of the disabling of RX + // interrupts that could end reenabling TX interrupts as a side effect. + if (h == t) { + B_UDRIE = 0; // (Non-atomic, could be reenabled by the main program, but eventually this will succeed) + return; + } - template - typename MarlinSerial::ring_buffer_pos_t MarlinSerial::available() { - const ring_buffer_pos_t h = atomic_read_rx_head(), t = rx_buffer.tail; - return (ring_buffer_pos_t)(Cfg::RX_SIZE + h - t) & (Cfg::RX_SIZE - 1); + // There is something to TX, Send the next byte + const uint8_t c = tx_buffer.buffer[t]; + t = (t + 1) & (Cfg::TX_SIZE - 1); + R_UDR = c; + tx_buffer.tail = t; + + // Clear the TXC bit (by writing a one to its bit location). + // Ensures flush() won't return until the bytes are actually written/ + B_TXC = 1; + + // Disable interrupts if there is nothing to transmit following this byte + if (h == t) B_UDRIE = 0; // (Non-atomic, could be reenabled by the main program, but eventually this will succeed) } +} - template - void MarlinSerial::flush() { +// Public Methods +template +void MarlinSerial::begin(const long baud) { + uint16_t baud_setting; + bool useU2X = true; - // Set the tail to the head: - // - Read the RX head index in a safe way. (See atomic_read_rx_head.) - // - Set the tail, making sure the RX ISR will always get a stable value, even - // if it interrupts the writing of the value of that variable in the middle. - atomic_set_rx_tail(atomic_read_rx_head()); + #if F_CPU == 16000000UL && SERIAL_PORT == 0 + // Hard-coded exception for compatibility with the bootloader shipped + // with the Duemilanove and previous boards, and the firmware on the + // 8U2 on the Uno and Mega 2560. + if (baud == 57600) useU2X = false; + #endif - if (Cfg::XONOFF) { - // If the XOFF char was sent, or about to be sent... - if ((xon_xoff_state & XON_XOFF_CHAR_MASK) == XOFF_CHAR) { + R_UCSRA = 0; + if (useU2X) { + B_U2X = 1; + baud_setting = (F_CPU / 4 / baud - 1) / 2; + } + else + baud_setting = (F_CPU / 8 / baud - 1) / 2; + + // assign the baud_setting, a.k.a. ubbr (USART Baud Rate Register) + R_UBRRH = baud_setting >> 8; + R_UBRRL = baud_setting; + + B_RXEN = 1; + B_TXEN = 1; + B_RXCIE = 1; + if (Cfg::TX_SIZE > 0) B_UDRIE = 0; + _written = false; +} + +template +void MarlinSerial::end() { + B_RXEN = 0; + B_TXEN = 0; + B_RXCIE = 0; + B_UDRIE = 0; +} + +template +int MarlinSerial::peek() { + const ring_buffer_pos_t h = atomic_read_rx_head(), t = rx_buffer.tail; + return h == t ? -1 : rx_buffer.buffer[t]; +} + +template +int MarlinSerial::read() { + const ring_buffer_pos_t h = atomic_read_rx_head(); + + // Read the tail. Main thread owns it, so it is safe to directly read it + ring_buffer_pos_t t = rx_buffer.tail; + + // If nothing to read, return now + if (h == t) return -1; + + // Get the next char + const int v = rx_buffer.buffer[t]; + t = (ring_buffer_pos_t)(t + 1) & (Cfg::RX_SIZE - 1); + + // Advance tail - Making sure the RX ISR will always get an stable value, even + // if it interrupts the writing of the value of that variable in the middle. + atomic_set_rx_tail(t); + + if (Cfg::XONOFF) { + // If the XOFF char was sent, or about to be sent... + if ((xon_xoff_state & XON_XOFF_CHAR_MASK) == XOFF_CHAR) { + // Get count of bytes in the RX buffer + const ring_buffer_pos_t rx_count = (ring_buffer_pos_t)(h - t) & (ring_buffer_pos_t)(Cfg::RX_SIZE - 1); + if (rx_count < (Cfg::RX_SIZE) / 10) { if (Cfg::TX_SIZE > 0) { // Signal we want an XON character to be sent. xon_xoff_state = XON_CHAR; - // Enable TX ISR. Non atomic, but it will eventually enable it. + // Enable TX ISR. Non atomic, but it will eventually enable them B_UDRIE = 1; } else { @@ -453,363 +416,384 @@ } } - template - void MarlinSerial::write(const uint8_t c) { - if (Cfg::TX_SIZE == 0) { - - _written = true; - while (!B_UDRE) sw_barrier(); - R_UDR = c; - - } - else { - - _written = true; - - // If the TX interrupts are disabled and the data register - // is empty, just write the byte to the data register and - // be done. This shortcut helps significantly improve the - // effective datarate at high (>500kbit/s) bitrates, where - // interrupt overhead becomes a slowdown. - // Yes, there is a race condition between the sending of the - // XOFF char at the RX ISR, but it is properly handled there - if (!B_UDRIE && B_UDRE) { - R_UDR = c; - - // clear the TXC bit -- "can be cleared by writing a one to its bit - // location". This makes sure flush() won't return until the bytes - // actually got written - B_TXC = 1; - return; - } - - const uint8_t i = (tx_buffer.head + 1) & (Cfg::TX_SIZE - 1); - - // If global interrupts are disabled (as the result of being called from an ISR)... - if (!ISRS_ENABLED()) { - - // Make room by polling if it is possible to transmit, and do so! - while (i == tx_buffer.tail) { - - // If we can transmit another byte, do it. - if (B_UDRE) _tx_udr_empty_irq(); - - // Make sure compiler rereads tx_buffer.tail - sw_barrier(); - } + return v; +} + +template +typename MarlinSerial::ring_buffer_pos_t MarlinSerial::available() { + const ring_buffer_pos_t h = atomic_read_rx_head(), t = rx_buffer.tail; + return (ring_buffer_pos_t)(Cfg::RX_SIZE + h - t) & (Cfg::RX_SIZE - 1); +} + +template +void MarlinSerial::flush() { + + // Set the tail to the head: + // - Read the RX head index in a safe way. (See atomic_read_rx_head.) + // - Set the tail, making sure the RX ISR will always get a stable value, even + // if it interrupts the writing of the value of that variable in the middle. + atomic_set_rx_tail(atomic_read_rx_head()); + + if (Cfg::XONOFF) { + // If the XOFF char was sent, or about to be sent... + if ((xon_xoff_state & XON_XOFF_CHAR_MASK) == XOFF_CHAR) { + if (Cfg::TX_SIZE > 0) { + // Signal we want an XON character to be sent. + xon_xoff_state = XON_CHAR; + // Enable TX ISR. Non atomic, but it will eventually enable it. + B_UDRIE = 1; } else { - // Interrupts are enabled, just wait until there is space - while (i == tx_buffer.tail) sw_barrier(); + // If not using TX interrupts, we must send the XON char now + xon_xoff_state = XON_CHAR | XON_XOFF_CHAR_SENT; + while (!B_UDRE) sw_barrier(); + R_UDR = XON_CHAR; } - - // Store new char. head is always safe to move - tx_buffer.buffer[tx_buffer.head] = c; - tx_buffer.head = i; - - // Enable TX ISR - Non atomic, but it will eventually enable TX ISR - B_UDRIE = 1; } } +} - template - void MarlinSerial::flushTX() { +template +void MarlinSerial::write(const uint8_t c) { + if (Cfg::TX_SIZE == 0) { - if (Cfg::TX_SIZE == 0) { - // No bytes written, no need to flush. This special case is needed since there's - // no way to force the TXC (transmit complete) bit to 1 during initialization. - if (!_written) return; + _written = true; + while (!B_UDRE) sw_barrier(); + R_UDR = c; - // Wait until everything was transmitted - while (!B_TXC) sw_barrier(); + } + else { - // At this point nothing is queued anymore (DRIE is disabled) and - // the hardware finished transmission (TXC is set). + _written = true; - } - else { + // If the TX interrupts are disabled and the data register + // is empty, just write the byte to the data register and + // be done. This shortcut helps significantly improve the + // effective datarate at high (>500kbit/s) bitrates, where + // interrupt overhead becomes a slowdown. + // Yes, there is a race condition between the sending of the + // XOFF char at the RX ISR, but it is properly handled there + if (!B_UDRIE && B_UDRE) { + R_UDR = c; - // No bytes written, no need to flush. This special case is needed since there's - // no way to force the TXC (transmit complete) bit to 1 during initialization. - if (!_written) return; + // clear the TXC bit -- "can be cleared by writing a one to its bit + // location". This makes sure flush() won't return until the bytes + // actually got written + B_TXC = 1; + return; + } - // If global interrupts are disabled (as the result of being called from an ISR)... - if (!ISRS_ENABLED()) { + const uint8_t i = (tx_buffer.head + 1) & (Cfg::TX_SIZE - 1); - // Wait until everything was transmitted - We must do polling, as interrupts are disabled - while (tx_buffer.head != tx_buffer.tail || !B_TXC) { + // If global interrupts are disabled (as the result of being called from an ISR)... + if (!ISRS_ENABLED()) { - // If there is more space, send an extra character - if (B_UDRE) _tx_udr_empty_irq(); + // Make room by polling if it is possible to transmit, and do so! + while (i == tx_buffer.tail) { - sw_barrier(); - } + // If we can transmit another byte, do it. + if (B_UDRE) _tx_udr_empty_irq(); + // Make sure compiler rereads tx_buffer.tail + sw_barrier(); } - else { - // Wait until everything was transmitted - while (tx_buffer.head != tx_buffer.tail || !B_TXC) sw_barrier(); - } - - // At this point nothing is queued anymore (DRIE is disabled) and - // the hardware finished transmission (TXC is set). } - } - - /** - * Imports from print.h - */ - - template - void MarlinSerial::print(char c, int base) { - print((long)c, base); - } - - template - void MarlinSerial::print(unsigned char b, int base) { - print((unsigned long)b, base); - } - - template - void MarlinSerial::print(int n, int base) { - print((long)n, base); - } - - template - void MarlinSerial::print(unsigned int n, int base) { - print((unsigned long)n, base); - } - - template - void MarlinSerial::print(long n, int base) { - if (base == 0) write(n); - else if (base == 10) { - if (n < 0) { print('-'); n = -n; } - printNumber(n, 10); + else { + // Interrupts are enabled, just wait until there is space + while (i == tx_buffer.tail) sw_barrier(); } - else - printNumber(n, base); - } - template - void MarlinSerial::print(unsigned long n, int base) { - if (base == 0) write(n); - else printNumber(n, base); - } + // Store new char. head is always safe to move + tx_buffer.buffer[tx_buffer.head] = c; + tx_buffer.head = i; - template - void MarlinSerial::print(double n, int digits) { - printFloat(n, digits); + // Enable TX ISR - Non atomic, but it will eventually enable TX ISR + B_UDRIE = 1; } +} - template - void MarlinSerial::println() { - print('\r'); - print('\n'); - } - - template - void MarlinSerial::println(const String& s) { - print(s); - println(); - } - - template - void MarlinSerial::println(const char c[]) { - print(c); - println(); - } +template +void MarlinSerial::flushTX() { - template - void MarlinSerial::println(char c, int base) { - print(c, base); - println(); - } + if (Cfg::TX_SIZE == 0) { + // No bytes written, no need to flush. This special case is needed since there's + // no way to force the TXC (transmit complete) bit to 1 during initialization. + if (!_written) return; - template - void MarlinSerial::println(unsigned char b, int base) { - print(b, base); - println(); - } + // Wait until everything was transmitted + while (!B_TXC) sw_barrier(); - template - void MarlinSerial::println(int n, int base) { - print(n, base); - println(); - } + // At this point nothing is queued anymore (DRIE is disabled) and + // the hardware finished transmission (TXC is set). - template - void MarlinSerial::println(unsigned int n, int base) { - print(n, base); - println(); } + else { - template - void MarlinSerial::println(long n, int base) { - print(n, base); - println(); - } + // No bytes written, no need to flush. This special case is needed since there's + // no way to force the TXC (transmit complete) bit to 1 during initialization. + if (!_written) return; - template - void MarlinSerial::println(unsigned long n, int base) { - print(n, base); - println(); - } + // If global interrupts are disabled (as the result of being called from an ISR)... + if (!ISRS_ENABLED()) { - template - void MarlinSerial::println(double n, int digits) { - print(n, digits); - println(); - } + // Wait until everything was transmitted - We must do polling, as interrupts are disabled + while (tx_buffer.head != tx_buffer.tail || !B_TXC) { - // Private Methods + // If there is more space, send an extra character + if (B_UDRE) _tx_udr_empty_irq(); - template - void MarlinSerial::printNumber(unsigned long n, uint8_t base) { - if (n) { - unsigned char buf[8 * sizeof(long)]; // Enough space for base 2 - int8_t i = 0; - while (n) { - buf[i++] = n % base; - n /= base; + sw_barrier(); } - while (i--) - print((char)(buf[i] + (buf[i] < 10 ? '0' : 'A' - 10))); - } - else - print('0'); - } - template - void MarlinSerial::printFloat(double number, uint8_t digits) { - // Handle negative numbers - if (number < 0.0) { - print('-'); - number = -number; } - - // Round correctly so that print(1.999, 2) prints as "2.00" - double rounding = 0.5; - LOOP_L_N(i, digits) rounding *= 0.1; - number += rounding; - - // Extract the integer part of the number and print it - unsigned long int_part = (unsigned long)number; - double remainder = number - (double)int_part; - print(int_part); - - // Print the decimal point, but only if there are digits beyond - if (digits) { - print('.'); - // Extract digits from the remainder one at a time - while (digits--) { - remainder *= 10.0; - int toPrint = int(remainder); - print(toPrint); - remainder -= toPrint; - } + else { + // Wait until everything was transmitted + while (tx_buffer.head != tx_buffer.tail || !B_TXC) sw_barrier(); } - } - // Hookup ISR handlers - ISR(SERIAL_REGNAME(USART,SERIAL_PORT,_RX_vect)) { - MarlinSerial>::store_rxd_char(); + // At this point nothing is queued anymore (DRIE is disabled) and + // the hardware finished transmission (TXC is set). } +} - ISR(SERIAL_REGNAME(USART,SERIAL_PORT,_UDRE_vect)) { - MarlinSerial>::_tx_udr_empty_irq(); - } - - // Preinstantiate - template class MarlinSerial>; - - // Instantiate - MarlinSerial> customizedSerial1; - - #ifdef SERIAL_PORT_2 +/** + * Imports from print.h + */ - // Hookup ISR handlers - ISR(SERIAL_REGNAME(USART,SERIAL_PORT_2,_RX_vect)) { - MarlinSerial>::store_rxd_char(); +template +void MarlinSerial::print(char c, int base) { + print((long)c, base); +} + +template +void MarlinSerial::print(unsigned char b, int base) { + print((unsigned long)b, base); +} + +template +void MarlinSerial::print(int n, int base) { + print((long)n, base); +} + +template +void MarlinSerial::print(unsigned int n, int base) { + print((unsigned long)n, base); +} + +template +void MarlinSerial::print(long n, int base) { + if (base == 0) write(n); + else if (base == 10) { + if (n < 0) { print('-'); n = -n; } + printNumber(n, 10); + } + else + printNumber(n, base); +} + +template +void MarlinSerial::print(unsigned long n, int base) { + if (base == 0) write(n); + else printNumber(n, base); +} + +template +void MarlinSerial::print(double n, int digits) { + printFloat(n, digits); +} + +template +void MarlinSerial::println() { + print('\r'); + print('\n'); +} + +template +void MarlinSerial::println(const String& s) { + print(s); + println(); +} + +template +void MarlinSerial::println(const char c[]) { + print(c); + println(); +} + +template +void MarlinSerial::println(char c, int base) { + print(c, base); + println(); +} + +template +void MarlinSerial::println(unsigned char b, int base) { + print(b, base); + println(); +} + +template +void MarlinSerial::println(int n, int base) { + print(n, base); + println(); +} + +template +void MarlinSerial::println(unsigned int n, int base) { + print(n, base); + println(); +} + +template +void MarlinSerial::println(long n, int base) { + print(n, base); + println(); +} + +template +void MarlinSerial::println(unsigned long n, int base) { + print(n, base); + println(); +} + +template +void MarlinSerial::println(double n, int digits) { + print(n, digits); + println(); +} + +// Private Methods + +template +void MarlinSerial::printNumber(unsigned long n, uint8_t base) { + if (n) { + unsigned char buf[8 * sizeof(long)]; // Enough space for base 2 + int8_t i = 0; + while (n) { + buf[i++] = n % base; + n /= base; } - - ISR(SERIAL_REGNAME(USART,SERIAL_PORT_2,_UDRE_vect)) { - MarlinSerial>::_tx_udr_empty_irq(); + while (i--) + print((char)(buf[i] + (buf[i] < 10 ? '0' : 'A' - 10))); + } + else + print('0'); +} + +template +void MarlinSerial::printFloat(double number, uint8_t digits) { + // Handle negative numbers + if (number < 0.0) { + print('-'); + number = -number; + } + + // Round correctly so that print(1.999, 2) prints as "2.00" + double rounding = 0.5; + LOOP_L_N(i, digits) rounding *= 0.1; + number += rounding; + + // Extract the integer part of the number and print it + unsigned long int_part = (unsigned long)number; + double remainder = number - (double)int_part; + print(int_part); + + // Print the decimal point, but only if there are digits beyond + if (digits) { + print('.'); + // Extract digits from the remainder one at a time + while (digits--) { + remainder *= 10.0; + int toPrint = int(remainder); + print(toPrint); + remainder -= toPrint; } + } +} - // Preinstantiate - template class MarlinSerial>; +// Hookup ISR handlers +ISR(SERIAL_REGNAME(USART, SERIAL_PORT, _RX_vect)) { + MarlinSerial>::store_rxd_char(); +} - // Instantiate - MarlinSerial> customizedSerial2; +ISR(SERIAL_REGNAME(USART, SERIAL_PORT, _UDRE_vect)) { + MarlinSerial>::_tx_udr_empty_irq(); +} - #endif +// Preinstantiate +template class MarlinSerial>; -#endif // !USBCON && (UBRRH || UBRR0H || UBRR1H || UBRR2H || UBRR3H) +// Instantiate +MarlinSerial> customizedSerial1; -#ifdef INTERNAL_SERIAL_PORT +#ifdef SERIAL_PORT_2 - ISR(SERIAL_REGNAME(USART,INTERNAL_SERIAL_PORT,_RX_vect)) { - MarlinSerial>::store_rxd_char(); + // Hookup ISR handlers + ISR(SERIAL_REGNAME(USART, SERIAL_PORT_2, _RX_vect)) { + MarlinSerial>::store_rxd_char(); } - ISR(SERIAL_REGNAME(USART,INTERNAL_SERIAL_PORT,_UDRE_vect)) { - MarlinSerial>::_tx_udr_empty_irq(); + ISR(SERIAL_REGNAME(USART, SERIAL_PORT_2, _UDRE_vect)) { + MarlinSerial>::_tx_udr_empty_irq(); } // Preinstantiate - template class MarlinSerial>; + template class MarlinSerial>; // Instantiate - MarlinSerial> internalSerial; + MarlinSerial> customizedSerial2; #endif -#ifdef DGUS_SERIAL_PORT - - template - typename MarlinSerial::ring_buffer_pos_t MarlinSerial::get_tx_buffer_free() { - const ring_buffer_pos_t t = tx_buffer.tail, // next byte to send. - h = tx_buffer.head; // next pos for queue. - int ret = t - h - 1; - if (ret < 0) ret += Cfg::TX_SIZE + 1; - return ret; - } +#ifdef MMU2_SERIAL_PORT - ISR(SERIAL_REGNAME(USART,DGUS_SERIAL_PORT,_RX_vect)) { - MarlinSerial>::store_rxd_char(); + ISR(SERIAL_REGNAME(USART, MMU2_SERIAL_PORT, _RX_vect)) { + MarlinSerial>::store_rxd_char(); } - ISR(SERIAL_REGNAME(USART,DGUS_SERIAL_PORT,_UDRE_vect)) { - MarlinSerial>::_tx_udr_empty_irq(); + ISR(SERIAL_REGNAME(USART, MMU2_SERIAL_PORT, _UDRE_vect)) { + MarlinSerial>::_tx_udr_empty_irq(); } // Preinstantiate - template class MarlinSerial>; + template class MarlinSerial>; // Instantiate - MarlinSerial> internalDgusSerial; + MarlinSerial> mmuSerial; #endif -#ifdef ANYCUBIC_LCD_SERIAL_PORT +#ifdef LCD_SERIAL_PORT - ISR(SERIAL_REGNAME(USART,ANYCUBIC_LCD_SERIAL_PORT,_RX_vect)) { - MarlinSerial>::store_rxd_char(); + ISR(SERIAL_REGNAME(USART, LCD_SERIAL_PORT, _RX_vect)) { + MarlinSerial>::store_rxd_char(); } - ISR(SERIAL_REGNAME(USART,ANYCUBIC_LCD_SERIAL_PORT,_UDRE_vect)) { - MarlinSerial>::_tx_udr_empty_irq(); + ISR(SERIAL_REGNAME(USART, LCD_SERIAL_PORT, _UDRE_vect)) { + MarlinSerial>::_tx_udr_empty_irq(); } // Preinstantiate - template class MarlinSerial>; + template class MarlinSerial>; // Instantiate - MarlinSerial> anycubicLcdSerial; + MarlinSerial> lcdSerial; + + #if HAS_DGUS_LCD + template + typename MarlinSerial::ring_buffer_pos_t MarlinSerial::get_tx_buffer_free() { + const ring_buffer_pos_t t = tx_buffer.tail, // next byte to send. + h = tx_buffer.head; // next pos for queue. + int ret = t - h - 1; + if (ret < 0) ret += Cfg::TX_SIZE + 1; + return ret; + } + #endif #endif +#endif // !USBCON && (UBRRH || UBRR0H || UBRR1H || UBRR2H || UBRR3H) + // For AT90USB targets use the UART for BT interfacing #if defined(USBCON) && ENABLED(BLUETOOTH) HardwareSerial bluetoothSerial; diff --git a/Marlin/src/HAL/AVR/MarlinSerial.h b/Marlin/src/HAL/AVR/MarlinSerial.h index e8bfc5583a..8a0423d143 100644 --- a/Marlin/src/HAL/AVR/MarlinSerial.h +++ b/Marlin/src/HAL/AVR/MarlinSerial.h @@ -48,11 +48,11 @@ // These are macros to build serial port register names for the selected SERIAL_PORT (C preprocessor // requires two levels of indirection to expand macro values properly) - #define SERIAL_REGNAME(registerbase,number,suffix) SERIAL_REGNAME_INTERNAL(registerbase,number,suffix) + #define SERIAL_REGNAME(registerbase,number,suffix) _SERIAL_REGNAME(registerbase,number,suffix) #if SERIAL_PORT == 0 && (!defined(UBRR0H) || !defined(UDR0)) // use un-numbered registers if necessary - #define SERIAL_REGNAME_INTERNAL(registerbase,number,suffix) registerbase##suffix + #define _SERIAL_REGNAME(registerbase,number,suffix) registerbase##suffix #else - #define SERIAL_REGNAME_INTERNAL(registerbase,number,suffix) registerbase##number##suffix + #define _SERIAL_REGNAME(registerbase,number,suffix) registerbase##number##suffix #endif // Registers used by MarlinSerial class (expanded depending on selected serial port) @@ -217,10 +217,12 @@ static ring_buffer_pos_t available(); static void write(const uint8_t c); static void flushTX(); - #ifdef DGUS_SERIAL_PORT + #if HAS_DGUS_LCD static ring_buffer_pos_t get_tx_buffer_free(); #endif + static inline bool emergency_parser_enabled() { return Cfg::EMERGENCYPARSER; } + FORCE_INLINE static uint8_t dropped() { return Cfg::DROPPED_RX ? rx_dropped_bytes : 0; } FORCE_INLINE static uint8_t buffer_overruns() { return Cfg::RX_OVERRUNS ? rx_buffer_overruns : 0; } FORCE_INLINE static uint8_t framing_errors() { return Cfg::RX_FRAMING_ERRORS ? rx_framing_errors : 0; } @@ -278,55 +280,50 @@ #endif // !USBCON -#ifdef INTERNAL_SERIAL_PORT +#ifdef MMU2_SERIAL_PORT template - struct MarlinInternalSerialCfg { + struct MMU2SerialCfg { static constexpr int PORT = serial; - static constexpr unsigned int RX_SIZE = 32; - static constexpr unsigned int TX_SIZE = 32; static constexpr bool XONOFF = false; static constexpr bool EMERGENCYPARSER = false; static constexpr bool DROPPED_RX = false; - static constexpr bool RX_OVERRUNS = false; static constexpr bool RX_FRAMING_ERRORS = false; static constexpr bool MAX_RX_QUEUED = false; + static constexpr unsigned int RX_SIZE = 32; + static constexpr unsigned int TX_SIZE = 32; + static constexpr bool RX_OVERRUNS = false; }; - extern MarlinSerial> internalSerial; + extern MarlinSerial> mmuSerial; #endif -#ifdef DGUS_SERIAL_PORT - template - struct MarlinInternalSerialCfg { - static constexpr int PORT = serial; - static constexpr unsigned int RX_SIZE = DGUS_RX_BUFFER_SIZE; - static constexpr unsigned int TX_SIZE = DGUS_TX_BUFFER_SIZE; - static constexpr bool XONOFF = false; - static constexpr bool EMERGENCYPARSER = false; - static constexpr bool DROPPED_RX = false; - static constexpr bool RX_OVERRUNS = BOTH(HAS_DGUS_LCD, DGUS_SERIAL_STATS_RX_BUFFER_OVERRUNS); - static constexpr bool RX_FRAMING_ERRORS = false; - static constexpr bool MAX_RX_QUEUED = false; - }; - - extern MarlinSerial> internalDgusSerial; -#endif +#ifdef LCD_SERIAL_PORT -#ifdef ANYCUBIC_LCD_SERIAL_PORT template - struct AnycubicLcdSerialCfg { - static constexpr int PORT = serial; - static constexpr unsigned int RX_SIZE = 64; - static constexpr unsigned int TX_SIZE = 128; - static constexpr bool XONOFF = false; - static constexpr bool EMERGENCYPARSER = false; - static constexpr bool DROPPED_RX = false; - static constexpr bool RX_OVERRUNS = false; - static constexpr bool RX_FRAMING_ERRORS = false; - static constexpr bool MAX_RX_QUEUED = false; + struct LCDSerialCfg { + static constexpr int PORT = serial; + static constexpr bool XONOFF = false; + static constexpr bool EMERGENCYPARSER = ENABLED(EMERGENCY_PARSER); + static constexpr bool DROPPED_RX = false; + static constexpr bool RX_FRAMING_ERRORS = false; + static constexpr bool MAX_RX_QUEUED = false; + #if HAS_DGUS_LCD + static constexpr unsigned int RX_SIZE = DGUS_RX_BUFFER_SIZE; + static constexpr unsigned int TX_SIZE = DGUS_TX_BUFFER_SIZE; + static constexpr bool RX_OVERRUNS = ENABLED(SERIAL_STATS_RX_BUFFER_OVERRUNS); + #elif EITHER(ANYCUBIC_LCD_I3MEGA, ANYCUBIC_LCD_CHIRON) + static constexpr unsigned int RX_SIZE = 64; + static constexpr unsigned int TX_SIZE = 128; + static constexpr bool RX_OVERRUNS = false; + #else + static constexpr unsigned int RX_SIZE = 64; + static constexpr unsigned int TX_SIZE = 128; + static constexpr bool RX_OVERRUNS = false + #endif }; - extern MarlinSerial> anycubicLcdSerial; + extern MarlinSerial> lcdSerial; + #endif // Use the UART for Bluetooth in AT90USB configurations diff --git a/Marlin/src/HAL/AVR/Servo.cpp b/Marlin/src/HAL/AVR/Servo.cpp index 66ed993c6f..526352b773 100644 --- a/Marlin/src/HAL/AVR/Servo.cpp +++ b/Marlin/src/HAL/AVR/Servo.cpp @@ -48,7 +48,6 @@ * readMicroseconds() - Get the last-written servo pulse width in microseconds. * attached() - Return true if a servo is attached. * detach() - Stop an attached servo from pulsing its i/o pin. - * */ #ifdef __AVR__ diff --git a/Marlin/src/HAL/AVR/fastio.h b/Marlin/src/HAL/AVR/fastio.h index bd6935aaf0..dd01634661 100644 --- a/Marlin/src/HAL/AVR/fastio.h +++ b/Marlin/src/HAL/AVR/fastio.h @@ -29,11 +29,17 @@ #include -#define AVR_AT90USB1286_FAMILY (defined(__AVR_AT90USB1287__) || defined(__AVR_AT90USB1286__) || defined(__AVR_AT90USB1286P__) || defined(__AVR_AT90USB646__) || defined(__AVR_AT90USB646P__) || defined(__AVR_AT90USB647__)) -#define AVR_ATmega1284_FAMILY (defined(__AVR_ATmega644__) || defined(__AVR_ATmega644P__) || defined(__AVR_ATmega644PA__) || defined(__AVR_ATmega1284P__)) -#define AVR_ATmega2560_FAMILY (defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)) -#define AVR_ATmega2561_FAMILY (defined(__AVR_ATmega1281__) || defined(__AVR_ATmega2561__)) -#define AVR_ATmega328_FAMILY (defined(__AVR_ATmega168__) || defined(__AVR_ATmega328__) || defined(__AVR_ATmega328P__)) +#if defined(__AVR_AT90USB1287__) || defined(__AVR_AT90USB1286__) || defined(__AVR_AT90USB1286P__) || defined(__AVR_AT90USB646__) || defined(__AVR_AT90USB646P__) || defined(__AVR_AT90USB647__) + #define AVR_AT90USB1286_FAMILY 1 +#elif defined(__AVR_ATmega644__) || defined(__AVR_ATmega644P__) || defined(__AVR_ATmega644PA__) || defined(__AVR_ATmega1284P__) + #define AVR_ATmega1284_FAMILY 1 +#elif defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) + #define AVR_ATmega2560_FAMILY 1 +#elif defined(__AVR_ATmega1281__) || defined(__AVR_ATmega2561__) + #define AVR_ATmega2561_FAMILY 1 +#elif defined(__AVR_ATmega168__) || defined(__AVR_ATmega328__) || defined(__AVR_ATmega328P__) + #define AVR_ATmega328_FAMILY 1 +#endif /** * Include Ports and Functions diff --git a/Marlin/src/HAL/AVR/pinsDebug.h b/Marlin/src/HAL/AVR/pinsDebug.h index d73f520d14..dac6b1b150 100644 --- a/Marlin/src/HAL/AVR/pinsDebug.h +++ b/Marlin/src/HAL/AVR/pinsDebug.h @@ -26,7 +26,9 @@ #define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS -#define AVR_ATmega2560_FAMILY_PLUS_70 MB(BQ_ZUM_MEGA_3D, MIGHTYBOARD_REVE, MINIRAMBO, SCOOVO_X9H) +#if MB(BQ_ZUM_MEGA_3D, MIGHTYBOARD_REVE, MINIRAMBO, SCOOVO_X9H, TRIGORILLA_14) + #define AVR_ATmega2560_FAMILY_PLUS_70 1 +#endif #if AVR_AT90USB1286_FAMILY diff --git a/Marlin/src/HAL/AVR/pinsDebug_plus_70.h b/Marlin/src/HAL/AVR/pinsDebug_plus_70.h index 46c03088d2..db3fdf1f76 100644 --- a/Marlin/src/HAL/AVR/pinsDebug_plus_70.h +++ b/Marlin/src/HAL/AVR/pinsDebug_plus_70.h @@ -22,15 +22,12 @@ * Structures for 2560 family boards that use more than 70 pins */ -#undef NUM_DIGITAL_PINS -#if MB(BQ_ZUM_MEGA_3D) +#if MB(BQ_ZUM_MEGA_3D, MINIRAMBO, SCOOVO_X9H, TRIGORILLA_14) + #undef NUM_DIGITAL_PINS #define NUM_DIGITAL_PINS 85 #elif MB(MIGHTYBOARD_REVE) + #undef NUM_DIGITAL_PINS #define NUM_DIGITAL_PINS 80 -#elif MB(MINIRAMBO) - #define NUM_DIGITAL_PINS 85 -#elif MB(SCOOVO_X9H) - #define NUM_DIGITAL_PINS 85 #endif #define PA 1 diff --git a/Marlin/src/HAL/AVR/timers.h b/Marlin/src/HAL/AVR/timers.h index 6c40d32209..82eb8b14b1 100644 --- a/Marlin/src/HAL/AVR/timers.h +++ b/Marlin/src/HAL/AVR/timers.h @@ -15,6 +15,7 @@ * * You should have received a copy of the GNU General Public License * along with this program. If not, see . + * */ #pragma once diff --git a/Marlin/src/HAL/AVR/u8g_com_HAL_AVR_sw_spi.cpp b/Marlin/src/HAL/AVR/u8g_com_HAL_AVR_sw_spi.cpp index c29b195578..cb95a48ccc 100644 --- a/Marlin/src/HAL/AVR/u8g_com_HAL_AVR_sw_spi.cpp +++ b/Marlin/src/HAL/AVR/u8g_com_HAL_AVR_sw_spi.cpp @@ -57,7 +57,7 @@ #include "../../inc/MarlinConfigPre.h" -#if HAS_GRAPHICAL_LCD +#if HAS_MARLINUI_U8GLIB #include "../shared/Marduino.h" #include "../shared/Delay.h" @@ -189,5 +189,5 @@ uint8_t u8g_com_HAL_AVR_sw_sp_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void return 1; } -#endif // HAS_GRAPHICAL_LCD +#endif // HAS_MARLINUI_U8GLIB #endif // ARDUINO_ARCH_SAM diff --git a/Marlin/src/HAL/DUE/HAL.h b/Marlin/src/HAL/DUE/HAL.h index 31409c76dd..7a057fdae4 100644 --- a/Marlin/src/HAL/DUE/HAL.h +++ b/Marlin/src/HAL/DUE/HAL.h @@ -38,59 +38,36 @@ #include +#define _MSERIAL(X) Serial##X +#define MSERIAL(X) _MSERIAL(X) +#define Serial0 Serial + // Define MYSERIAL0/1 before MarlinSerial includes! #if SERIAL_PORT == -1 || ENABLED(EMERGENCY_PARSER) #define MYSERIAL0 customizedSerial1 -#elif SERIAL_PORT == 0 - #define MYSERIAL0 Serial -#elif SERIAL_PORT == 1 - #define MYSERIAL0 Serial1 -#elif SERIAL_PORT == 2 - #define MYSERIAL0 Serial2 -#elif SERIAL_PORT == 3 - #define MYSERIAL0 Serial3 +#elif WITHIN(SERIAL_PORT, 0, 3) + #define MYSERIAL0 MSERIAL(SERIAL_PORT) #else #error "The required SERIAL_PORT must be from -1 to 3. Please update your configuration." #endif #ifdef SERIAL_PORT_2 - #if SERIAL_PORT_2 == SERIAL_PORT - #error "SERIAL_PORT_2 must be different from SERIAL_PORT. Please update your configuration." - #elif SERIAL_PORT_2 == -1 || ENABLED(EMERGENCY_PARSER) + #if SERIAL_PORT_2 == -1 || ENABLED(EMERGENCY_PARSER) #define MYSERIAL1 customizedSerial2 - #elif SERIAL_PORT_2 == 0 - #define MYSERIAL1 Serial - #elif SERIAL_PORT_2 == 1 - #define MYSERIAL1 Serial1 - #elif SERIAL_PORT_2 == 2 - #define MYSERIAL1 Serial2 - #elif SERIAL_PORT_2 == 3 - #define MYSERIAL1 Serial3 + #elif WITHIN(SERIAL_PORT_2, 0, 3) + #define MYSERIAL1 MSERIAL(SERIAL_PORT_2) #else #error "SERIAL_PORT_2 must be from -1 to 3. Please update your configuration." #endif - #define NUM_SERIAL 2 -#else - #define NUM_SERIAL 1 #endif -#ifdef DGUS_SERIAL_PORT - #if DGUS_SERIAL_PORT == SERIAL_PORT - #error "DGUS_SERIAL_PORT must be different from SERIAL_PORT. Please update your configuration." - #elif defined(SERIAL_PORT_2) && DGUS_SERIAL_PORT == SERIAL_PORT_2 - #error "DGUS_SERIAL_PORT must be different than SERIAL_PORT_2. Please update your configuration." - #elif DGUS_SERIAL_PORT == -1 - #define DGUS_SERIAL internalDgusSerial - #elif DGUS_SERIAL_PORT == 0 - #define DGUS_SERIAL Serial - #elif DGUS_SERIAL_PORT == 1 - #define DGUS_SERIAL Serial1 - #elif DGUS_SERIAL_PORT == 2 - #define DGUS_SERIAL Serial2 - #elif DGUS_SERIAL_PORT == 3 - #define DGUS_SERIAL Serial3 +#ifdef LCD_SERIAL_PORT + #if LCD_SERIAL_PORT == -1 + #define LCD_SERIAL lcdSerial + #elif WITHIN(LCD_SERIAL_PORT, 0, 3) + #define LCD_SERIAL MSERIAL(LCD_SERIAL_PORT) #else - #error "DGUS_SERIAL_PORT must be from -1 to 3. Please update your configuration." + #error "LCD_SERIAL_PORT must be from -1 to 3. Please update your configuration." #endif #endif diff --git a/Marlin/src/HAL/DUE/HAL_SPI.cpp b/Marlin/src/HAL/DUE/HAL_SPI.cpp index 6d8f7ef819..54ae8eceb1 100644 --- a/Marlin/src/HAL/DUE/HAL_SPI.cpp +++ b/Marlin/src/HAL/DUE/HAL_SPI.cpp @@ -595,7 +595,7 @@ SPI_Enable(SPI0); SET_OUTPUT(DAC0_SYNC); - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER SET_OUTPUT(DAC1_SYNC); WRITE(DAC1_SYNC, HIGH); #endif @@ -759,7 +759,6 @@ * * All of the above can be avoided by defining FORCE_SOFT_SPI to force the * display to use software SPI. - * */ void spiInit(uint8_t spiRate=6) { // Default to slowest rate if not specified) diff --git a/Marlin/src/HAL/DUE/MarlinSerial.h b/Marlin/src/HAL/DUE/MarlinSerial.h index dfafa15141..a194eba2f3 100644 --- a/Marlin/src/HAL/DUE/MarlinSerial.h +++ b/Marlin/src/HAL/DUE/MarlinSerial.h @@ -122,6 +122,8 @@ public: static void write(const uint8_t c); static void flushTX(); + static inline bool emergency_parser_enabled() { return Cfg::EMERGENCYPARSER; } + FORCE_INLINE static uint8_t dropped() { return Cfg::DROPPED_RX ? rx_dropped_bytes : 0; } FORCE_INLINE static uint8_t buffer_overruns() { return Cfg::RX_OVERRUNS ? rx_buffer_overruns : 0; } FORCE_INLINE static uint8_t framing_errors() { return Cfg::RX_FRAMING_ERRORS ? rx_framing_errors : 0; } diff --git a/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_shared_hw_spi.cpp b/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_shared_hw_spi.cpp index 2ef7011b1c..be4b49c0f9 100644 --- a/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_shared_hw_spi.cpp +++ b/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_shared_hw_spi.cpp @@ -52,14 +52,13 @@ * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF * ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - * */ #ifdef __SAM3X8E__ #include "../../../inc/MarlinConfigPre.h" -#if HAS_GRAPHICAL_LCD +#if HAS_MARLINUI_U8GLIB #include @@ -145,6 +144,6 @@ uint8_t u8g_com_HAL_DUE_shared_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_va return 1; } -#endif // HAS_GRAPHICAL_LCD +#endif // HAS_MARLINUI_U8GLIB -#endif //__SAM3X8E__ +#endif // __SAM3X8E__ diff --git a/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi.cpp b/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi.cpp index 54c244d4f6..ea7204fa36 100644 --- a/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi.cpp +++ b/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi.cpp @@ -57,7 +57,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if HAS_GRAPHICAL_LCD && DISABLED(U8GLIB_ST7920) +#if HAS_MARLINUI_U8GLIB && DISABLED(U8GLIB_ST7920) #undef SPI_SPEED #define SPI_SPEED 2 // About 2 MHz @@ -144,5 +144,5 @@ uint8_t u8g_com_HAL_DUE_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void return 1; } -#endif // HAS_GRAPHICAL_LCD && !U8GLIB_ST7920 +#endif // HAS_MARLINUI_U8GLIB && !U8GLIB_ST7920 #endif // ARDUINO_ARCH_SAM diff --git a/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.cpp b/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.cpp index 960df1bd86..615a386c35 100644 --- a/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.cpp +++ b/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.cpp @@ -57,7 +57,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if HAS_GRAPHICAL_LCD +#if HAS_MARLINUI_U8GLIB #include "../../shared/Delay.h" @@ -108,5 +108,5 @@ void u8g_spiSend_sw_DUE_mode_3(uint8_t val) { // 3.5MHz } } -#endif // HAS_GRAPHICAL_LCD +#endif // HAS_MARLINUI_U8GLIB #endif // ARDUINO_ARCH_SAM diff --git a/Marlin/src/HAL/DUE/eeprom_flash.cpp b/Marlin/src/HAL/DUE/eeprom_flash.cpp index d98f06039f..67f1f9e40f 100644 --- a/Marlin/src/HAL/DUE/eeprom_flash.cpp +++ b/Marlin/src/HAL/DUE/eeprom_flash.cpp @@ -53,7 +53,6 @@ * per page. We can't emulate EE endurance with FLASH for all * bytes, but we can emulate endurance for a given percent of * bytes. - * */ //#define EE_EMU_DEBUG diff --git a/Marlin/src/HAL/DUE/pinsDebug.h b/Marlin/src/HAL/DUE/pinsDebug.h index 28687ff267..a99ca8ecce 100644 --- a/Marlin/src/HAL/DUE/pinsDebug.h +++ b/Marlin/src/HAL/DUE/pinsDebug.h @@ -179,5 +179,4 @@ void pwm_details(int32_t pin) { * ----------------+-------- * ID | PB11 * VBOF | PB10 - * */ diff --git a/Marlin/src/HAL/DUE/usb/compiler.h b/Marlin/src/HAL/DUE/usb/compiler.h index 7b746543c4..879007fa2a 100644 --- a/Marlin/src/HAL/DUE/usb/compiler.h +++ b/Marlin/src/HAL/DUE/usb/compiler.h @@ -173,11 +173,11 @@ # define __always_inline __forceinline #elif (defined __GNUC__) #ifdef __always_inline -# undef __always_inline +# undef __always_inline #endif -# define __always_inline inline __attribute__((__always_inline__)) +# define __always_inline inline __attribute__((__always_inline__)) #elif (defined __ICCARM__) -# define __always_inline _Pragma("inline=forced") +# define __always_inline _Pragma("inline=forced") #endif /** @@ -188,11 +188,11 @@ * heuristics and not inline the function. */ #ifdef __CC_ARM -# define __no_inline __attribute__((noinline)) +# define __no_inline __attribute__((noinline)) #elif (defined __GNUC__) -# define __no_inline __attribute__((__noinline__)) +# define __no_inline __attribute__((__noinline__)) #elif (defined __ICCARM__) -# define __no_inline _Pragma("inline=never") +# define __no_inline _Pragma("inline=never") #endif /*! \brief This macro is used to test fatal errors. @@ -211,9 +211,9 @@ # else #undef TEST_SUITE_DEFINE_ASSERT_MACRO # define Assert(expr) \ - {\ - if (!(expr)) while (true);\ - } + {\ + if (!(expr)) while (true);\ + } # endif #else # define Assert(expr) ((void) 0) @@ -1106,17 +1106,16 @@ static inline uint16_t convert_byte_array_to_16_bit(uint8_t *data) /* Converts a 8 Byte array into a 32-Bit value */ static inline uint32_t convert_byte_array_to_32_bit(uint8_t *data) { - union - { - uint32_t u32; - uint8_t u8[8]; - }long_addr; - uint8_t index; - for (index = 0; index < 4; index++) - { - long_addr.u8[index] = *data++; - } - return long_addr.u32; + union + { + uint32_t u32; + uint8_t u8[8]; + }long_addr; + uint8_t index; + for (index = 0; index < 4; index++) { + long_addr.u8[index] = *data++; + } + return long_addr.u32; } /** diff --git a/Marlin/src/HAL/ESP32/HAL.h b/Marlin/src/HAL/ESP32/HAL.h index c91f9efff0..f6fa46dd93 100644 --- a/Marlin/src/HAL/ESP32/HAL.h +++ b/Marlin/src/HAL/ESP32/HAL.h @@ -15,6 +15,7 @@ * * You should have received a copy of the GNU General Public License * along with this program. If not, see . + * */ #pragma once @@ -58,9 +59,6 @@ extern portMUX_TYPE spinlock; #else #define MYSERIAL1 webSocketSerial #endif - #define NUM_SERIAL 2 -#else - #define NUM_SERIAL 1 #endif #define CRITICAL_SECTION_START() portENTER_CRITICAL(&spinlock) diff --git a/Marlin/src/HAL/ESP32/WebSocketSerial.cpp b/Marlin/src/HAL/ESP32/WebSocketSerial.cpp index 533f873e4f..ca7f47a1f8 100644 --- a/Marlin/src/HAL/ESP32/WebSocketSerial.cpp +++ b/Marlin/src/HAL/ESP32/WebSocketSerial.cpp @@ -86,7 +86,7 @@ int RingBuffer::read() { ring_buffer_pos_t RingBuffer::read(uint8_t *buffer) { ring_buffer_pos_t len = available(); - for(ring_buffer_pos_t i = 0; read_index != write_index; i++) { + for (ring_buffer_pos_t i = 0; read_index != write_index; i++) { buffer[i] = data[read_index]; read_index = NEXT_INDEX(read_index, size); } @@ -139,9 +139,8 @@ size_t WebSocketSerial::write(const uint8_t c) { size_t WebSocketSerial::write(const uint8_t* buffer, size_t size) { size_t written = 0; - for(size_t i = 0; i < size; i++) { + for (size_t i = 0; i < size; i++) written += write(buffer[i]); - } return written; } diff --git a/Marlin/src/HAL/ESP32/ota.h b/Marlin/src/HAL/ESP32/ota.h index 7f9b237aa6..546ace82db 100644 --- a/Marlin/src/HAL/ESP32/ota.h +++ b/Marlin/src/HAL/ESP32/ota.h @@ -15,6 +15,7 @@ * * You should have received a copy of the GNU General Public License * along with this program. If not, see . + * */ #pragma once diff --git a/Marlin/src/HAL/HAL.h b/Marlin/src/HAL/HAL.h index c7b7531442..8b6a978d21 100644 --- a/Marlin/src/HAL/HAL.h +++ b/Marlin/src/HAL/HAL.h @@ -25,6 +25,12 @@ #include HAL_PATH(.,HAL.h) +#ifdef SERIAL_PORT_2 + #define NUM_SERIAL 2 +#else + #define NUM_SERIAL 1 +#endif + #define HAL_ADC_RANGE _BV(HAL_ADC_RESOLUTION) #ifndef I2C_ADDRESS diff --git a/Marlin/src/HAL/LINUX/HAL.h b/Marlin/src/HAL/LINUX/HAL.h index 96e121d915..778ba2db4d 100644 --- a/Marlin/src/HAL/LINUX/HAL.h +++ b/Marlin/src/HAL/LINUX/HAL.h @@ -62,7 +62,6 @@ uint8_t _getc(); extern HalSerial usb_serial; #define MYSERIAL0 usb_serial -#define NUM_SERIAL 1 #define ST7920_DELAY_1 DELAY_NS(600) #define ST7920_DELAY_2 DELAY_NS(750) diff --git a/Marlin/src/HAL/LINUX/include/serial.h b/Marlin/src/HAL/LINUX/include/serial.h index 154e95aec2..e916249389 100644 --- a/Marlin/src/HAL/LINUX/include/serial.h +++ b/Marlin/src/HAL/LINUX/include/serial.h @@ -33,7 +33,6 @@ * Generic RingBuffer * T type of the buffer array * S size of the buffer (must be power of 2) - * */ template class RingBuffer { public: @@ -79,6 +78,7 @@ public: #if ENABLED(EMERGENCY_PARSER) EmergencyParser::State emergency_state; + static inline bool emergency_parser_enabled() { return true; } #endif HalSerial() { host_connected = true; } diff --git a/Marlin/src/HAL/LINUX/main.cpp b/Marlin/src/HAL/LINUX/main.cpp index 4eeef318e7..481f059030 100644 --- a/Marlin/src/HAL/LINUX/main.cpp +++ b/Marlin/src/HAL/LINUX/main.cpp @@ -107,7 +107,7 @@ int main() { std::thread write_serial (write_serial_thread); std::thread read_serial (read_serial_thread); - #if NUM_SERIAL > 0 + #ifdef MYSERIAL0 MYSERIAL0.begin(BAUDRATE); SERIAL_ECHOLNPGM("x86_64 Initialized"); SERIAL_FLUSHTX(); diff --git a/Marlin/src/HAL/LINUX/servo_private.h b/Marlin/src/HAL/LINUX/servo_private.h index 122cfef3ea..bcc8d2037f 100644 --- a/Marlin/src/HAL/LINUX/servo_private.h +++ b/Marlin/src/HAL/LINUX/servo_private.h @@ -45,7 +45,6 @@ * Version 2 Copyright (c) 2009 Michael Margolis. All right reserved. * * The only modification was to update/delete macros to match the LPC176x. - * */ #include diff --git a/Marlin/src/HAL/LINUX/spi_pins.h b/Marlin/src/HAL/LINUX/spi_pins.h index a444196f04..01ba28e5b6 100644 --- a/Marlin/src/HAL/LINUX/spi_pins.h +++ b/Marlin/src/HAL/LINUX/spi_pins.h @@ -24,7 +24,7 @@ #include "../../core/macros.h" #include "../../inc/MarlinConfigPre.h" -#if BOTH(HAS_GRAPHICAL_LCD, SDSUPPORT) && (LCD_PINS_D4 == SCK_PIN || LCD_PINS_ENABLE == MOSI_PIN || DOGLCD_SCK == SCK_PIN || DOGLCD_MOSI == MOSI_PIN) +#if BOTH(HAS_MARLINUI_U8GLIB, SDSUPPORT) && (LCD_PINS_D4 == SCK_PIN || LCD_PINS_ENABLE == MOSI_PIN || DOGLCD_SCK == SCK_PIN || DOGLCD_MOSI == MOSI_PIN) #define LPC_SOFTWARE_SPI // If the SD card and LCD adapter share the same SPI pins, then software SPI is currently // needed due to the speed and mode required for communicating with each device being different. // This requirement can be removed if the SPI access to these devices is updated to use diff --git a/Marlin/src/HAL/LPC1768/HAL.h b/Marlin/src/HAL/LPC1768/HAL.h index 0153bacf42..3118aed1b2 100644 --- a/Marlin/src/HAL/LPC1768/HAL.h +++ b/Marlin/src/HAL/LPC1768/HAL.h @@ -63,58 +63,35 @@ extern "C" volatile uint32_t _millis; #define ST7920_DELAY_3 DELAY_NS(750) #endif +#define _MSERIAL(X) MSerial##X +#define MSERIAL(X) _MSERIAL(X) +#define MSerial0 MSerial + #if SERIAL_PORT == -1 #define MYSERIAL0 UsbSerial -#elif SERIAL_PORT == 0 - #define MYSERIAL0 MSerial -#elif SERIAL_PORT == 1 - #define MYSERIAL0 MSerial1 -#elif SERIAL_PORT == 2 - #define MYSERIAL0 MSerial2 -#elif SERIAL_PORT == 3 - #define MYSERIAL0 MSerial3 +#elif WITHIN(SERIAL_PORT, 0, 3) + #define MYSERIAL0 MSERIAL(SERIAL_PORT) #else #error "SERIAL_PORT must be from -1 to 3. Please update your configuration." #endif #ifdef SERIAL_PORT_2 - #if SERIAL_PORT_2 == SERIAL_PORT - #error "SERIAL_PORT_2 must be different than SERIAL_PORT. Please update your configuration." - #elif SERIAL_PORT_2 == -1 + #if SERIAL_PORT_2 == -1 #define MYSERIAL1 UsbSerial - #elif SERIAL_PORT_2 == 0 - #define MYSERIAL1 MSerial - #elif SERIAL_PORT_2 == 1 - #define MYSERIAL1 MSerial1 - #elif SERIAL_PORT_2 == 2 - #define MYSERIAL1 MSerial2 - #elif SERIAL_PORT_2 == 3 - #define MYSERIAL1 MSerial3 + #elif WITHIN(SERIAL_PORT_2, 0, 3) + #define MYSERIAL1 MSERIAL(SERIAL_PORT_2) #else #error "SERIAL_PORT_2 must be from -1 to 3. Please update your configuration." #endif - #define NUM_SERIAL 2 -#else - #define NUM_SERIAL 1 #endif -#ifdef DGUS_SERIAL_PORT - #if DGUS_SERIAL_PORT == SERIAL_PORT - #error "DGUS_SERIAL_PORT must be different than SERIAL_PORT. Please update your configuration." - #elif defined(SERIAL_PORT_2) && DGUS_SERIAL_PORT == SERIAL_PORT_2 - #error "DGUS_SERIAL_PORT must be different than SERIAL_PORT_2. Please update your configuration." - #elif DGUS_SERIAL_PORT == -1 - #define DGUS_SERIAL UsbSerial - #elif DGUS_SERIAL_PORT == 0 - #define DGUS_SERIAL MSerial - #elif DGUS_SERIAL_PORT == 1 - #define DGUS_SERIAL MSerial1 - #elif DGUS_SERIAL_PORT == 2 - #define DGUS_SERIAL MSerial2 - #elif DGUS_SERIAL_PORT == 3 - #define DGUS_SERIAL MSerial3 +#ifdef LCD_SERIAL_PORT + #if LCD_SERIAL_PORT == -1 + #define LCD_SERIAL UsbSerial + #elif WITHIN(LCD_SERIAL_PORT, 0, 3) + #define LCD_SERIAL MSERIAL(LCD_SERIAL_PORT) #else - #error "DGUS_SERIAL_PORT must be from -1 to 3. Please update your configuration." + #error "LCD_SERIAL_PORT must be from -1 to 3. Please update your configuration." #endif #endif diff --git a/Marlin/src/HAL/LPC1768/HAL_SPI.cpp b/Marlin/src/HAL/LPC1768/HAL_SPI.cpp index 00b4310d1d..b3d2908ac9 100644 --- a/Marlin/src/HAL/LPC1768/HAL_SPI.cpp +++ b/Marlin/src/HAL/LPC1768/HAL_SPI.cpp @@ -39,10 +39,10 @@ * Some of the LCD interfaces/adapters result in the LCD SPI and the SD card * SPI sharing pins. The SCK, MOSI & MISO pins can NOT be set/cleared with * WRITE nor digitalWrite when the hardware SPI module within the LPC17xx is - * active. If any of these pins are shared then the software SPI must be used. + * active. If any of these pins are shared then the software SPI must be used. * - * A more sophisticated hardware SPI can be found at the following link. This - * implementation has not been fully debugged. + * A more sophisticated hardware SPI can be found at the following link. + * This implementation has not been fully debugged. * https://github.com/MarlinFirmware/Marlin/tree/071c7a78f27078fd4aee9a3ef365fcf5e143531e */ @@ -100,72 +100,25 @@ #else - // decide which HW SPI device to use - #ifndef LPC_HW_SPI_DEV - #if (SCK_PIN == P0_07 && MISO_PIN == P0_08 && MOSI_PIN == P0_09) - #define LPC_HW_SPI_DEV 1 - #else - #if (SCK_PIN == P0_15 && MISO_PIN == P0_17 && MOSI_PIN == P0_18) - #define LPC_HW_SPI_DEV 0 - #else - #error "Invalid pins selected for hardware SPI" - #endif - #endif - #endif - #if LPC_HW_SPI_DEV == 0 - #define LPC_SSPn LPC_SSP0 - #else - #define LPC_SSPn LPC_SSP1 - #endif - void spiBegin() { // setup SCK, MOSI & MISO pins for SSP0 - PINSEL_CFG_Type PinCfg; // data structure to hold init values - PinCfg.Funcnum = 2; - PinCfg.OpenDrain = 0; - PinCfg.Pinmode = 0; - PinCfg.Pinnum = LPC176x::pin_bit(SCK_PIN); - PinCfg.Portnum = LPC176x::pin_port(SCK_PIN); - PINSEL_ConfigPin(&PinCfg); - SET_OUTPUT(SCK_PIN); - - PinCfg.Pinnum = LPC176x::pin_bit(MISO_PIN); - PinCfg.Portnum = LPC176x::pin_port(MISO_PIN); - PINSEL_ConfigPin(&PinCfg); - SET_INPUT(MISO_PIN); - - PinCfg.Pinnum = LPC176x::pin_bit(MOSI_PIN); - PinCfg.Portnum = LPC176x::pin_port(MOSI_PIN); - PINSEL_ConfigPin(&PinCfg); - SET_OUTPUT(MOSI_PIN); - // divide PCLK by 2 for SSP0 - CLKPWR_SetPCLKDiv(LPC_HW_SPI_DEV == 0 ? CLKPWR_PCLKSEL_SSP0 : CLKPWR_PCLKSEL_SSP1, CLKPWR_PCLKSEL_CCLK_DIV_2); - spiInit(0); - SSP_Cmd(LPC_SSPn, ENABLE); // start SSP running + spiInit(SPI_SPEED); } void spiInit(uint8_t spiRate) { - // table to convert Marlin spiRates (0-5 plus default) into bit rates - uint32_t Marlin_speed[7]; // CPSR is always 2 - Marlin_speed[0] = 8333333; //(SCR: 2) desired: 8,000,000 actual: 8,333,333 +4.2% SPI_FULL_SPEED - Marlin_speed[1] = 4166667; //(SCR: 5) desired: 4,000,000 actual: 4,166,667 +4.2% SPI_HALF_SPEED - Marlin_speed[2] = 2083333; //(SCR: 11) desired: 2,000,000 actual: 2,083,333 +4.2% SPI_QUARTER_SPEED - Marlin_speed[3] = 1000000; //(SCR: 24) desired: 1,000,000 actual: 1,000,000 SPI_EIGHTH_SPEED - Marlin_speed[4] = 500000; //(SCR: 49) desired: 500,000 actual: 500,000 SPI_SPEED_5 - Marlin_speed[5] = 250000; //(SCR: 99) desired: 250,000 actual: 250,000 SPI_SPEED_6 - Marlin_speed[6] = 125000; //(SCR:199) desired: 125,000 actual: 125,000 Default from HAL.h - // setup for SPI mode - SSP_CFG_Type HW_SPI_init; // data structure to hold init values - SSP_ConfigStructInit(&HW_SPI_init); // set values for SPI mode - HW_SPI_init.ClockRate = Marlin_speed[_MIN(spiRate, 6)]; // put in the specified bit rate - HW_SPI_init.Mode |= SSP_CR1_SSP_EN; - SSP_Init(LPC_SSPn, &HW_SPI_init); // puts the values into the proper bits in the SSP0 registers + #if MISO_PIN == BOARD_SPI1_MISO_PIN + SPI.setModule(1); + #elif MISO_PIN == BOARD_SPI2_MISO_PIN + SPI.setModule(2); + #endif + SPI.setDataSize(DATA_SIZE_8BIT); + SPI.setDataMode(SPI_MODE0); + + SPI.setClock(SPISettings::spiRate2Clock(spiRate)); + SPI.begin(); } static uint8_t doio(uint8_t b) { - /* send and receive a single byte */ - SSP_SendData(LPC_SSPn, b & 0x00FF); - while (SSP_GetStatus(LPC_SSPn, SSP_STAT_BUSY)); // wait for it to finish - return SSP_ReceiveData(LPC_SSPn) & 0x00FF; + return SPI.transfer(b & 0x00FF) & 0x00FF; } void spiSend(uint8_t b) { doio(b); } @@ -217,63 +170,74 @@ static inline void waitSpiTxEnd(LPC_SSP_TypeDef *spi_d) { while (SSP_GetStatus(spi_d, SSP_STAT_BUSY) == SET) { /* nada */ } // wait until BSY=0 } +// Retain the pin init state of the SPI, to avoid init more than once, +// even if more instances of SPIClass exist +static bool spiInitialised[BOARD_NR_SPI] = { false }; + SPIClass::SPIClass(uint8_t device) { // Init things specific to each SPI device // clock divider setup is a bit of hack, and needs to be improved at a later date. - PINSEL_CFG_Type PinCfg; // data structure to hold init values #if BOARD_NR_SPI >= 1 _settings[0].spi_d = LPC_SSP0; - // _settings[0].clockDivider = determine_baud_rate(_settings[0].spi_d, _settings[0].clock); - PinCfg.Funcnum = 2; - PinCfg.OpenDrain = 0; - PinCfg.Pinmode = 0; - PinCfg.Pinnum = LPC176x::pin_bit(BOARD_SPI1_SCK_PIN); - PinCfg.Portnum = LPC176x::pin_port(BOARD_SPI1_SCK_PIN); - PINSEL_ConfigPin(&PinCfg); - SET_OUTPUT(BOARD_SPI1_SCK_PIN); - - PinCfg.Pinnum = LPC176x::pin_bit(BOARD_SPI1_MISO_PIN); - PinCfg.Portnum = LPC176x::pin_port(BOARD_SPI1_MISO_PIN); - PINSEL_ConfigPin(&PinCfg); - SET_INPUT(BOARD_SPI1_MISO_PIN); - - PinCfg.Pinnum = LPC176x::pin_bit(BOARD_SPI1_MOSI_PIN); - PinCfg.Portnum = LPC176x::pin_port(BOARD_SPI1_MOSI_PIN); - PINSEL_ConfigPin(&PinCfg); - SET_OUTPUT(BOARD_SPI1_MOSI_PIN); + _settings[0].dataMode = SPI_MODE0; + _settings[0].dataSize = DATA_SIZE_8BIT; + _settings[0].clock = SPI_CLOCK_MAX; + //_settings[0].clockDivider = determine_baud_rate(_settings[0].spi_d, _settings[0].clock); #endif #if BOARD_NR_SPI >= 2 _settings[1].spi_d = LPC_SSP1; - // _settings[1].clockDivider = determine_baud_rate(_settings[1].spi_d, _settings[1].clock); + _settings[1].dataMode = SPI_MODE0; + _settings[1].dataSize = DATA_SIZE_8BIT; + _settings[1].clock = SPI_CLOCK_MAX; + //_settings[1].clockDivider = determine_baud_rate(_settings[1].spi_d, _settings[1].clock); + #endif + + setModule(device); + + // Init the GPDMA controller + // TODO: call once in the constructor? or each time? + GPDMA_Init(); +} + +void SPIClass::begin() { + // Init the SPI pins in the first begin call + if ((_currentSetting->spi_d == LPC_SSP0 && spiInitialised[0] == false) || + (_currentSetting->spi_d == LPC_SSP1 && spiInitialised[1] == false)) { + pin_t sck, miso, mosi; + if (_currentSetting->spi_d == LPC_SSP0) { + sck = BOARD_SPI1_SCK_PIN; + miso = BOARD_SPI1_MISO_PIN; + mosi = BOARD_SPI1_MOSI_PIN; + spiInitialised[0] = true; + } + else if (_currentSetting->spi_d == LPC_SSP1) { + sck = BOARD_SPI2_SCK_PIN; + miso = BOARD_SPI2_MISO_PIN; + mosi = BOARD_SPI2_MOSI_PIN; + spiInitialised[1] = true; + } + PINSEL_CFG_Type PinCfg; // data structure to hold init values PinCfg.Funcnum = 2; PinCfg.OpenDrain = 0; PinCfg.Pinmode = 0; - PinCfg.Pinnum = LPC176x::pin_bit(BOARD_SPI2_SCK_PIN); - PinCfg.Portnum = LPC176x::pin_port(BOARD_SPI2_SCK_PIN); + PinCfg.Pinnum = LPC176x::pin_bit(sck); + PinCfg.Portnum = LPC176x::pin_port(sck); PINSEL_ConfigPin(&PinCfg); - SET_OUTPUT(BOARD_SPI2_SCK_PIN); + SET_OUTPUT(sck); - PinCfg.Pinnum = LPC176x::pin_bit(BOARD_SPI2_MISO_PIN); - PinCfg.Portnum = LPC176x::pin_port(BOARD_SPI2_MISO_PIN); + PinCfg.Pinnum = LPC176x::pin_bit(miso); + PinCfg.Portnum = LPC176x::pin_port(miso); PINSEL_ConfigPin(&PinCfg); - SET_INPUT(BOARD_SPI2_MISO_PIN); + SET_INPUT(miso); - PinCfg.Pinnum = LPC176x::pin_bit(BOARD_SPI2_MOSI_PIN); - PinCfg.Portnum = LPC176x::pin_port(BOARD_SPI2_MOSI_PIN); + PinCfg.Pinnum = LPC176x::pin_bit(mosi); + PinCfg.Portnum = LPC176x::pin_port(mosi); PINSEL_ConfigPin(&PinCfg); - SET_OUTPUT(BOARD_SPI2_MOSI_PIN); - #endif - - setModule(device); - - /* Initialize GPDMA controller */ - //TODO: call once in the constructor? or each time? - GPDMA_Init(); -} + SET_OUTPUT(mosi); + } -void SPIClass::begin() { updateSettings(); SSP_Cmd(_currentSetting->spi_d, ENABLE); // start SSP running } @@ -287,7 +251,7 @@ void SPIClass::beginTransaction(const SPISettings &cfg) { } uint8_t SPIClass::transfer(const uint16_t b) { - /* send and receive a single byte */ + // Send and receive a single byte SSP_ReceiveData(_currentSetting->spi_d); // read any previous data SSP_SendData(_currentSetting->spi_d, b); waitSpiTxEnd(_currentSetting->spi_d); // wait for it to finish @@ -295,8 +259,7 @@ uint8_t SPIClass::transfer(const uint16_t b) { } uint16_t SPIClass::transfer16(const uint16_t data) { - return (transfer((data >> 8) & 0xFF) << 8) - | (transfer(data & 0xFF) & 0xFF); + return (transfer((data >> 8) & 0xFF) << 8) | (transfer(data & 0xFF) & 0xFF); } void SPIClass::end() { @@ -320,7 +283,7 @@ void SPIClass::dmaSend(void *buf, uint16_t length, bool minc) { // Destination memory - Not used GPDMACfg.DstMemAddr = 0; // Transfer size - GPDMACfg.TransferSize = (minc ? length : 1); + GPDMACfg.TransferSize = length; // Transfer width GPDMACfg.TransferWidth = (_currentSetting->dataSize == DATA_SIZE_16BIT) ? GPDMA_WIDTH_HALFWORD : GPDMA_WIDTH_BYTE; // Transfer type @@ -335,26 +298,24 @@ void SPIClass::dmaSend(void *buf, uint16_t length, bool minc) { // Enable dma on SPI SSP_DMACmd(_currentSetting->spi_d, SSP_DMA_TX, ENABLE); - // if minc=false, I'm repeating the same byte 'length' times, as I could not find yet how do GPDMA without memory increment - do { - // Setup channel with given parameter - GPDMA_Setup(&GPDMACfg); + // Only increase memory if minc is true + GPDMACfg.MemoryIncrease = (minc ? GPDMA_DMACCxControl_SI : 0); - // enabled dma - GPDMA_ChannelCmd(0, ENABLE); + // Setup channel with given parameter + GPDMA_Setup(&GPDMACfg); - // wait data transfer - while (!GPDMA_IntGetStatus(GPDMA_STAT_INTTC, 0) && !GPDMA_IntGetStatus(GPDMA_STAT_INTERR, 0)) { } + // Enable DMA + GPDMA_ChannelCmd(0, ENABLE); - // clear err and int - GPDMA_ClearIntPending (GPDMA_STATCLR_INTTC, 0); - GPDMA_ClearIntPending (GPDMA_STATCLR_INTERR, 0); + // Wait for data transfer + while (!GPDMA_IntGetStatus(GPDMA_STAT_RAWINTTC, 0) && !GPDMA_IntGetStatus(GPDMA_STAT_RAWINTERR, 0)) { } - // dma disable - GPDMA_ChannelCmd(0, DISABLE); + // Clear err and int + GPDMA_ClearIntPending (GPDMA_STATCLR_INTTC, 0); + GPDMA_ClearIntPending (GPDMA_STATCLR_INTERR, 0); - --length; - } while (!minc && length > 0); + // Disable DMA + GPDMA_ChannelCmd(0, DISABLE); waitSpiTxEnd(_currentSetting->spi_d); @@ -382,7 +343,7 @@ void SPIClass::setBitOrder(uint8_t bitOrder) { } void SPIClass::setDataMode(uint8_t dataMode) { - _currentSetting->dataSize = dataMode; + _currentSetting->dataMode = dataMode; } void SPIClass::setDataSize(uint32_t ds) { @@ -413,19 +374,19 @@ void SPIClass::updateSettings() { switch (_currentSetting->dataMode) { case SPI_MODE0: HW_SPI_init.CPHA = SSP_CPHA_FIRST; - HW_SPI_init.CPOL = SSP_CPOL_HI; + HW_SPI_init.CPOL = SSP_CPOL_HI; break; case SPI_MODE1: HW_SPI_init.CPHA = SSP_CPHA_SECOND; - HW_SPI_init.CPOL = SSP_CPOL_HI; + HW_SPI_init.CPOL = SSP_CPOL_HI; break; case SPI_MODE2: HW_SPI_init.CPHA = SSP_CPHA_FIRST; - HW_SPI_init.CPOL = SSP_CPOL_LO; + HW_SPI_init.CPOL = SSP_CPOL_LO; break; case SPI_MODE3: HW_SPI_init.CPHA = SSP_CPHA_SECOND; - HW_SPI_init.CPOL = SSP_CPOL_LO; + HW_SPI_init.CPOL = SSP_CPOL_LO; break; default: break; diff --git a/Marlin/src/HAL/LPC1768/MarlinSerial.cpp b/Marlin/src/HAL/LPC1768/MarlinSerial.cpp index c3fb3bd0e4..5374e005d3 100644 --- a/Marlin/src/HAL/LPC1768/MarlinSerial.cpp +++ b/Marlin/src/HAL/LPC1768/MarlinSerial.cpp @@ -24,28 +24,28 @@ #include "../../inc/MarlinConfigPre.h" #include "MarlinSerial.h" -#if (defined(SERIAL_PORT) && SERIAL_PORT == 0) || (defined(SERIAL_PORT_2) && SERIAL_PORT_2 == 0) || (defined(DGUS_SERIAL_PORT) && DGUS_SERIAL_PORT == 0) +#if USING_SERIAL_0 MarlinSerial MSerial(LPC_UART0); extern "C" void UART0_IRQHandler() { MSerial.IRQHandler(); } #endif -#if SERIAL_PORT == 1 || SERIAL_PORT_2 == 1 || DGUS_SERIAL_PORT == 1 +#if USING_SERIAL_1 MarlinSerial MSerial1((LPC_UART_TypeDef *) LPC_UART1); extern "C" void UART1_IRQHandler() { MSerial1.IRQHandler(); } #endif -#if SERIAL_PORT == 2 || SERIAL_PORT_2 == 2 || DGUS_SERIAL_PORT == 2 +#if USING_SERIAL_2 MarlinSerial MSerial2(LPC_UART2); extern "C" void UART2_IRQHandler() { MSerial2.IRQHandler(); } #endif -#if SERIAL_PORT == 3 || SERIAL_PORT_2 == 3 || DGUS_SERIAL_PORT == 3 +#if USING_SERIAL_3 MarlinSerial MSerial3(LPC_UART3); extern "C" void UART3_IRQHandler() { MSerial3.IRQHandler(); diff --git a/Marlin/src/HAL/LPC1768/MarlinSerial.h b/Marlin/src/HAL/LPC1768/MarlinSerial.h index 98ce73d377..8d6b64378a 100644 --- a/Marlin/src/HAL/LPC1768/MarlinSerial.h +++ b/Marlin/src/HAL/LPC1768/MarlinSerial.h @@ -57,6 +57,7 @@ public: } EmergencyParser::State emergency_state; + static inline bool emergency_parser_enabled() { return true; } #endif }; diff --git a/Marlin/src/HAL/LPC1768/Servo.h b/Marlin/src/HAL/LPC1768/Servo.h index e953cb9204..eb12fd20f4 100644 --- a/Marlin/src/HAL/LPC1768/Servo.h +++ b/Marlin/src/HAL/LPC1768/Servo.h @@ -46,7 +46,6 @@ * Version 2 Copyright (c) 2009 Michael Margolis. All right reserved. * * The only modification was to update/delete macros to match the LPC176x. - * */ #include diff --git a/Marlin/src/HAL/LPC1768/inc/SanityCheck.h b/Marlin/src/HAL/LPC1768/inc/SanityCheck.h index 0a4e59c6c4..fd82e2884a 100644 --- a/Marlin/src/HAL/LPC1768/inc/SanityCheck.h +++ b/Marlin/src/HAL/LPC1768/inc/SanityCheck.h @@ -24,7 +24,7 @@ #if PIO_PLATFORM_VERSION < 1001 #error "nxplpc-arduino-lpc176x package is out of date, Please update the PlatformIO platforms, frameworks and libraries. You may need to remove the platform and let it reinstall automatically." #endif -#if PIO_FRAMEWORK_VERSION < 2002 +#if PIO_FRAMEWORK_VERSION < 2005 #error "framework-arduino-lpc176x package is out of date, Please update the PlatformIO platforms, frameworks and libraries." #endif @@ -89,7 +89,10 @@ static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported o * Serial2 | P0_10 | P0_11 | * Serial3 | P0_00 | P0_01 | */ -#if (defined(SERIAL_PORT) && SERIAL_PORT == 0) || (defined(SERIAL_PORT_2) && SERIAL_PORT_2 == 0) || (defined(DGUS_SERIAL_PORT) && DGUS_SERIAL_PORT == 0) +#define ANY_TX(N,V...) DO(IS_TX##N,||,V) +#define ANY_RX(N,V...) DO(IS_RX##N,||,V) + +#if USING_SERIAL_0 #define IS_TX0(P) (P == P0_02) #define IS_RX0(P) (P == P0_03) #if IS_TX0(TMC_SW_MISO) || IS_RX0(TMC_SW_MOSI) @@ -103,60 +106,67 @@ static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported o #undef IS_RX0 #endif -#if SERIAL_PORT == 1 || SERIAL_PORT_2 == 1 || DGUS_SERIAL_PORT == 1 +#if USING_SERIAL_1 #define IS_TX1(P) (P == P0_15) #define IS_RX1(P) (P == P0_16) + #define _IS_TX1_1 IS_TX1 + #define _IS_RX1_1 IS_RX1 #if IS_TX1(TMC_SW_SCK) #error "Serial port pins (1) conflict with other pins!" - #elif HAS_SPI_LCD + #elif HAS_WIRED_LCD #if IS_TX1(BTN_EN2) || IS_RX1(BTN_EN1) #error "Serial port pins (1) conflict with Encoder Buttons!" - #elif IS_TX1(SCK_PIN) || IS_TX1(LCD_PINS_D4) || IS_TX1(DOGLCD_SCK) || IS_TX1(LCD_RESET_PIN) || IS_TX1(LCD_PINS_RS) || IS_TX1(SHIFT_CLK) \ - || IS_RX1(LCD_SDSS) || IS_RX1(LCD_PINS_RS) || IS_RX1(MISO_PIN) || IS_RX1(DOGLCD_A0) || IS_RX1(SS_PIN) || IS_RX1(LCD_SDSS) || IS_RX1(DOGLCD_CS) || IS_RX1(LCD_RESET_PIN) || IS_RX1(LCD_BACKLIGHT_PIN) + #elif ANY_TX(1, SCK_PIN, LCD_PINS_D4, DOGLCD_SCK, LCD_RESET_PIN, LCD_PINS_RS, SHIFT_CLK) \ + || ANY_RX(1, LCD_SDSS, LCD_PINS_RS, MISO_PIN, DOGLCD_A0, SS_PIN, LCD_SDSS, DOGLCD_CS, LCD_RESET_PIN, LCD_BACKLIGHT_PIN) #error "Serial port pins (1) conflict with LCD pins!" #endif #endif #undef IS_TX1 #undef IS_RX1 + #undef _IS_TX1_1 + #undef _IS_RX1_1 #endif -#if SERIAL_PORT == 2 || SERIAL_PORT_2 == 2 || DGUS_SERIAL_PORT == 2 +#if USING_SERIAL_2 #define IS_TX2(P) (P == P0_10) #define IS_RX2(P) (P == P0_11) - #if IS_TX2(X2_ENABLE_PIN) || IS_RX2(X2_DIR_PIN) || IS_RX2(X2_STEP_PIN) || (AXIS_HAS_SPI(X2) && IS_TX2(X2_CS_PIN)) + #define _IS_TX2_1 IS_TX2 + #define _IS_RX2_1 IS_RX2 + #if IS_TX2(X2_ENABLE_PIN) || ANY_RX(2, X2_DIR_PIN, X2_STEP_PIN) || (AXIS_HAS_SPI(X2) && IS_TX2(X2_CS_PIN)) #error "Serial port pins (2) conflict with X2 pins!" - #elif IS_TX2(Y2_ENABLE_PIN) || IS_RX2(Y2_DIR_PIN) || IS_RX2(Y2_STEP_PIN) || (AXIS_HAS_SPI(Y2) && IS_TX2(Y2_CS_PIN)) + #elif IS_TX2(Y2_ENABLE_PIN) || ANY_RX(2, Y2_DIR_PIN, Y2_STEP_PIN) || (AXIS_HAS_SPI(Y2) && IS_TX2(Y2_CS_PIN)) #error "Serial port pins (2) conflict with Y2 pins!" - #elif IS_TX2(Z2_ENABLE_PIN) || IS_RX2(Z2_DIR_PIN) || IS_RX2(Z2_STEP_PIN) || (AXIS_HAS_SPI(Z2) && IS_TX2(Z2_CS_PIN)) + #elif IS_TX2(Z2_ENABLE_PIN) || ANY_RX(2, Z2_DIR_PIN, Z2_STEP_PIN) || (AXIS_HAS_SPI(Z2) && IS_TX2(Z2_CS_PIN)) #error "Serial port pins (2) conflict with Z2 pins!" - #elif IS_TX2(Z3_ENABLE_PIN) || IS_RX2(Z3_DIR_PIN) || IS_RX2(Z3_STEP_PIN) || (AXIS_HAS_SPI(Z3) && IS_TX2(Z3_CS_PIN)) + #elif IS_TX2(Z3_ENABLE_PIN) || ANY_RX(2, Z3_DIR_PIN, Z3_STEP_PIN) || (AXIS_HAS_SPI(Z3) && IS_TX2(Z3_CS_PIN)) #error "Serial port pins (2) conflict with Z3 pins!" - #elif IS_TX2(Z4_ENABLE_PIN) || IS_RX2(Z4_DIR_PIN) || IS_RX2(Z4_STEP_PIN) || (AXIS_HAS_SPI(Z4) && IS_TX2(Z4_CS_PIN)) + #elif IS_TX2(Z4_ENABLE_PIN) || ANY_RX(2, Z4_DIR_PIN, Z4_STEP_PIN) || (AXIS_HAS_SPI(Z4) && IS_TX2(Z4_CS_PIN)) #error "Serial port pins (2) conflict with Z4 pins!" - #elif IS_RX2(X_DIR_PIN) || IS_RX2(Y_DIR_PIN) + #elif ANY_RX(2, X_DIR_PIN, Y_DIR_PIN) #error "Serial port pins (2) conflict with other pins!" #elif Y_HOME_DIR < 0 && IS_TX2(Y_STOP_PIN) #error "Serial port pins (2) conflict with Y endstop pin!" #elif HAS_CUSTOM_PROBE_PIN && IS_TX2(Z_MIN_PROBE_PIN) #error "Serial port pins (2) conflict with probe pin!" - #elif IS_TX2(X_ENABLE_PIN) || IS_RX2(X_DIR_PIN) || IS_TX2(Y_ENABLE_PIN) || IS_RX2(Y_DIR_PIN) + #elif ANY_TX(2, X_ENABLE_PIN, Y_ENABLE_PIN) || ANY_RX(2, X_DIR_PIN, Y_DIR_PIN) #error "Serial port pins (2) conflict with X/Y stepper pins!" - #elif EXTRUDERS > 1 && (IS_TX2(E1_ENABLE_PIN) || (AXIS_HAS_SPI(E1) && IS_TX2(E1_CS_PIN))) + #elif HAS_MULTI_EXTRUDER && (IS_TX2(E1_ENABLE_PIN) || (AXIS_HAS_SPI(E1) && IS_TX2(E1_CS_PIN))) #error "Serial port pins (2) conflict with E1 stepper pins!" - #elif EXTRUDERS && (IS_RX2(E0_DIR_PIN) || IS_RX2(E0_STEP_PIN)) + #elif EXTRUDERS && ANY_RX(2, E0_DIR_PIN, E0_STEP_PIN) #error "Serial port pins (2) conflict with E stepper pins!" #endif #undef IS_TX2 #undef IS_RX2 + #undef _IS_TX2_1 + #undef _IS_RX2_1 #endif -#if SERIAL_PORT == 3 || SERIAL_PORT_2 == 3 || DGUS_SERIAL_PORT == 3 +#if USING_SERIAL_3 #define PIN_IS_TX3(P) (PIN_EXISTS(P) && P##_PIN == P0_00) #define PIN_IS_RX3(P) (P##_PIN == P0_01) #if PIN_IS_TX3(X_MIN) || PIN_IS_RX3(X_MAX) #error "Serial port pins (3) conflict with X endstop pins!" - #elif PIN_IS_TX3(Y_SERIAL_TX) || PIN_IS_TX3(Y_SERIAL_RX) \ - || PIN_IS_RX3(X_SERIAL_TX) || PIN_IS_RX3(X_SERIAL_RX) + #elif PIN_IS_TX3(Y_SERIAL_TX) || PIN_IS_TX3(Y_SERIAL_RX) || PIN_IS_RX3(X_SERIAL_TX) || PIN_IS_RX3(X_SERIAL_RX) #error "Serial port pins (3) conflict with X/Y axis UART pins!" #elif PIN_IS_TX3(X2_DIR) || PIN_IS_RX3(X2_STEP) #error "Serial port pins (3) conflict with X2 pins!" @@ -168,13 +178,16 @@ static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported o #error "Serial port pins (3) conflict with Z3 pins!" #elif PIN_IS_TX3(Z4_DIR) || PIN_IS_RX3(Z4_STEP) #error "Serial port pins (3) conflict with Z4 pins!" - #elif EXTRUDERS > 1 && (PIN_IS_TX3(E1_DIR) || PIN_IS_RX3(E1_STEP)) + #elif HAS_MULTI_EXTRUDER && (PIN_IS_TX3(E1_DIR) || PIN_IS_RX3(E1_STEP)) #error "Serial port pins (3) conflict with E1 pins!" #endif #undef PIN_IS_TX3 #undef PIN_IS_RX3 #endif +#undef ANY_TX +#undef ANY_RX + // // Flag any i2c pin conflicts // @@ -214,7 +227,7 @@ static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported o #error "One or more i2c (1) pins overlaps with Z3 pins! Disable i2c peripherals." #elif PIN_IS_SDA1(Z4_DIR) || PIN_IS_SCL1(Z4_STEP) #error "One or more i2c (1) pins overlaps with Z4 pins! Disable i2c peripherals." - #elif EXTRUDERS > 1 && (PIN_IS_SDA1(E1_DIR) || PIN_IS_SCL1(E1_STEP)) + #elif HAS_MULTI_EXTRUDER && (PIN_IS_SDA1(E1_DIR) || PIN_IS_SCL1(E1_STEP)) #error "One or more i2c (1) pins overlaps with E1 pins! Disable i2c peripherals." #endif #undef PIN_IS_SDA1 @@ -240,9 +253,9 @@ static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported o #error "i2c SDA2 overlaps with Z3 enable pin! Disable i2c peripherals." #elif PIN_IS_SDA2(Z4_ENABLE) #error "i2c SDA2 overlaps with Z4 enable pin! Disable i2c peripherals." - #elif EXTRUDERS > 1 && PIN_IS_SDA2(E1_ENABLE) + #elif HAS_MULTI_EXTRUDER && PIN_IS_SDA2(E1_ENABLE) #error "i2c SDA2 overlaps with E1 enable pin! Disable i2c peripherals." - #elif EXTRUDERS > 1 && AXIS_HAS_SPI(E1) && PIN_IS_SDA2(E1_CS) + #elif HAS_MULTI_EXTRUDER && AXIS_HAS_SPI(E1) && PIN_IS_SDA2(E1_CS) #error "i2c SDA2 overlaps with E1 CS pin! Disable i2c peripherals." #elif EXTRUDERS && (PIN_IS_SDA2(E0_STEP) || PIN_IS_SDA2(E0_DIR)) #error "i2c SCL2 overlaps with E0 STEP/DIR pin! Disable i2c peripherals." diff --git a/Marlin/src/HAL/LPC1768/include/SPI.h b/Marlin/src/HAL/LPC1768/include/SPI.h index e2645b9290..9da2a32556 100644 --- a/Marlin/src/HAL/LPC1768/include/SPI.h +++ b/Marlin/src/HAL/LPC1768/include/SPI.h @@ -61,7 +61,9 @@ class SPISettings { public: - SPISettings(uint32_t speed, int, int) : spi_speed(speed) {}; + SPISettings(uint32_t spiRate, int inBitOrder, int inDataMode) { + init_AlwaysInline(spiRate2Clock(spiRate), inBitOrder, inDataMode, DATA_SIZE_8BIT); + } SPISettings(uint32_t inClock, uint8_t inBitOrder, uint8_t inDataMode, uint32_t inDataSize) { if (__builtin_constant_p(inClock)) init_AlwaysInline(inClock, inBitOrder, inDataMode, inDataSize); @@ -72,7 +74,19 @@ public: init_AlwaysInline(4000000, MSBFIRST, SPI_MODE0, DATA_SIZE_8BIT); } - uint32_t spiRate() const { return spi_speed; } + //uint32_t spiRate() const { return spi_speed; } + + static inline uint32_t spiRate2Clock(uint32_t spiRate) { + uint32_t Marlin_speed[7]; // CPSR is always 2 + Marlin_speed[0] = 8333333; //(SCR: 2) desired: 8,000,000 actual: 8,333,333 +4.2% SPI_FULL_SPEED + Marlin_speed[1] = 4166667; //(SCR: 5) desired: 4,000,000 actual: 4,166,667 +4.2% SPI_HALF_SPEED + Marlin_speed[2] = 2083333; //(SCR: 11) desired: 2,000,000 actual: 2,083,333 +4.2% SPI_QUARTER_SPEED + Marlin_speed[3] = 1000000; //(SCR: 24) desired: 1,000,000 actual: 1,000,000 SPI_EIGHTH_SPEED + Marlin_speed[4] = 500000; //(SCR: 49) desired: 500,000 actual: 500,000 SPI_SPEED_5 + Marlin_speed[5] = 250000; //(SCR: 99) desired: 250,000 actual: 250,000 SPI_SPEED_6 + Marlin_speed[6] = 125000; //(SCR:199) desired: 125,000 actual: 125,000 Default from HAL.h + return Marlin_speed[spiRate > 6 ? 6 : spiRate]; + } private: void init_MightInline(uint32_t inClock, uint8_t inBitOrder, uint8_t inDataMode, uint32_t inDataSize) { @@ -85,7 +99,7 @@ private: dataSize = inDataSize; } - uint32_t spi_speed; + //uint32_t spi_speed; uint32_t clock; uint32_t dataSize; //uint32_t clockDivider; @@ -122,7 +136,7 @@ public: void end(); void beginTransaction(const SPISettings&); - void endTransaction() {}; + void endTransaction() {} // Transfer using 1 "Data Size" uint8_t transfer(uint16_t data); diff --git a/Marlin/src/HAL/LPC1768/spi_pins.h b/Marlin/src/HAL/LPC1768/spi_pins.h index 2e6749bf57..b4da5d4df2 100644 --- a/Marlin/src/HAL/LPC1768/spi_pins.h +++ b/Marlin/src/HAL/LPC1768/spi_pins.h @@ -23,7 +23,7 @@ #include "../../core/macros.h" -#if BOTH(SDSUPPORT, HAS_GRAPHICAL_LCD) && (LCD_PINS_D4 == SCK_PIN || LCD_PINS_ENABLE == MOSI_PIN || DOGLCD_SCK == SCK_PIN || DOGLCD_MOSI == MOSI_PIN) +#if BOTH(SDSUPPORT, HAS_MARLINUI_U8GLIB) && (LCD_PINS_D4 == SCK_PIN || LCD_PINS_ENABLE == MOSI_PIN || DOGLCD_SCK == SCK_PIN || DOGLCD_MOSI == MOSI_PIN) #define LPC_SOFTWARE_SPI // If the SD card and LCD adapter share the same SPI pins, then software SPI is currently // needed due to the speed and mode required for communicating with each device being different. // This requirement can be removed if the SPI access to these devices is updated to use diff --git a/Marlin/src/HAL/LPC1768/tft/xpt2046.cpp b/Marlin/src/HAL/LPC1768/tft/xpt2046.cpp index c72e5f0eac..5f96630043 100644 --- a/Marlin/src/HAL/LPC1768/tft/xpt2046.cpp +++ b/Marlin/src/HAL/LPC1768/tft/xpt2046.cpp @@ -72,7 +72,6 @@ bool XPT2046::getRawPoint(int16_t *x, int16_t *y) { if (!isTouched()) return false; *x = getRawData(XPT2046_X); *y = getRawData(XPT2046_Y); - SERIAL_ECHOLNPAIR("X: ", *x, ", Y: ", *y); return isTouched(); } diff --git a/Marlin/src/HAL/LPC1768/timers.h b/Marlin/src/HAL/LPC1768/timers.h index 23dc20e2eb..e6744fb005 100644 --- a/Marlin/src/HAL/LPC1768/timers.h +++ b/Marlin/src/HAL/LPC1768/timers.h @@ -21,7 +21,6 @@ #pragma once /** - * * HAL For LPC1768 */ diff --git a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_hw_spi.cpp b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_hw_spi.cpp index befc348fab..057e10e0f5 100644 --- a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_hw_spi.cpp +++ b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_hw_spi.cpp @@ -57,7 +57,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if HAS_GRAPHICAL_LCD +#if HAS_MARLINUI_U8GLIB #include #include "../../shared/HAL_SPI.h" @@ -124,6 +124,6 @@ uint8_t u8g_com_HAL_LPC1768_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, return 1; } -#endif // HAS_GRAPHICAL_LCD +#endif // HAS_MARLINUI_U8GLIB #endif // TARGET_LPC1768 diff --git a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_ssd_hw_i2c.cpp b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_ssd_hw_i2c.cpp index f03be9ab34..6f7efba4ae 100644 --- a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_ssd_hw_i2c.cpp +++ b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_ssd_hw_i2c.cpp @@ -77,7 +77,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if HAS_GRAPHICAL_LCD +#if HAS_MARLINUI_U8GLIB #include @@ -193,6 +193,6 @@ uint8_t u8g_com_HAL_LPC1768_ssd_hw_i2c_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_v return 1; } -#endif // HAS_GRAPHICAL_LCD +#endif // HAS_MARLINUI_U8GLIB #endif // TARGET_LPC1768 diff --git a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_hw_spi.cpp b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_hw_spi.cpp index 1500c22a0d..592e27f6c0 100644 --- a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_hw_spi.cpp +++ b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_hw_spi.cpp @@ -57,7 +57,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if HAS_GRAPHICAL_LCD +#if HAS_MARLINUI_U8GLIB #include #include "../../shared/HAL_SPI.h" @@ -133,6 +133,6 @@ uint8_t u8g_com_HAL_LPC1768_ST7920_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t ar return 1; } -#endif // HAS_GRAPHICAL_LCD +#endif // HAS_MARLINUI_U8GLIB #endif // TARGET_LPC1768 diff --git a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_sw_spi.cpp b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_sw_spi.cpp index 4f52f7dd01..ca9d6ecfbe 100644 --- a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_sw_spi.cpp +++ b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_sw_spi.cpp @@ -57,7 +57,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if HAS_GRAPHICAL_LCD && DISABLED(U8GLIB_ST7920) +#if HAS_MARLINUI_U8GLIB && DISABLED(U8GLIB_ST7920) #include @@ -203,5 +203,5 @@ uint8_t u8g_com_HAL_LPC1768_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, return 1; } -#endif // HAS_GRAPHICAL_LCD && !U8GLIB_ST7920 +#endif // HAS_MARLINUI_U8GLIB && !U8GLIB_ST7920 #endif // TARGET_LPC1768 diff --git a/Marlin/src/HAL/LPC1768/usb_serial.cpp b/Marlin/src/HAL/LPC1768/usb_serial.cpp index 63a570efdf..d225ce4188 100644 --- a/Marlin/src/HAL/LPC1768/usb_serial.cpp +++ b/Marlin/src/HAL/LPC1768/usb_serial.cpp @@ -26,7 +26,9 @@ #if ENABLED(EMERGENCY_PARSER) #include "../../feature/e_parser.h" + EmergencyParser::State emergency_state; + bool CDC_RecvCallback(const char buffer) { emergency_parser.update(emergency_state, buffer); return true; diff --git a/Marlin/src/HAL/SAMD51/HAL.h b/Marlin/src/HAL/SAMD51/HAL.h index ea0f694cdc..7fd826a1b6 100644 --- a/Marlin/src/HAL/SAMD51/HAL.h +++ b/Marlin/src/HAL/SAMD51/HAL.h @@ -35,58 +35,34 @@ // MYSERIAL0 required before MarlinSerial includes! + #define _MSERIAL(X) Serial##X + #define MSERIAL(X) _MSERIAL(INCREMENT(X)) + #if SERIAL_PORT == -1 #define MYSERIAL0 Serial - #elif SERIAL_PORT == 0 - #define MYSERIAL0 Serial1 - #elif SERIAL_PORT == 1 - #define MYSERIAL0 Serial2 - #elif SERIAL_PORT == 2 - #define MYSERIAL0 Serial3 - #elif SERIAL_PORT == 3 - #define MYSERIAL0 Serial4 + #elif WITHIN(SERIAL_PORT, 0, 3) + #define MYSERIAL0 MSERIAL(SERIAL_PORT) #else #error "SERIAL_PORT must be from -1 to 3. Please update your configuration." #endif #ifdef SERIAL_PORT_2 - #if SERIAL_PORT_2 == SERIAL_PORT - #error "SERIAL_PORT_2 must be different than SERIAL_PORT. Please update your configuration." - #elif SERIAL_PORT_2 == -1 + #if SERIAL_PORT_2 == -1 #define MYSERIAL1 Serial - #elif SERIAL_PORT_2 == 0 - #define MYSERIAL1 Serial1 - #elif SERIAL_PORT_2 == 1 - #define MYSERIAL1 Serial2 - #elif SERIAL_PORT_2 == 2 - #define MYSERIAL1 Serial3 - #elif SERIAL_PORT_2 == 3 - #define MYSERIAL1 Serial4 + #elif WITHIN(SERIAL_PORT_2, 0, 3) + #define MYSERIAL1 MSERIAL(SERIAL_PORT_2) #else #error "SERIAL_PORT_2 must be from -1 to 3. Please update your configuration." #endif - #define NUM_SERIAL 2 - #else - #define NUM_SERIAL 1 #endif - #ifdef DGUS_SERIAL_PORT - #if DGUS_SERIAL_PORT == SERIAL_PORT - #error "DGUS_SERIAL_PORT must be different than SERIAL_PORT. Please update your configuration." - #elif defined(SERIAL_PORT_2) && DGUS_SERIAL_PORT == SERIAL_PORT_2 - #error "DGUS_SERIAL_PORT must be different than SERIAL_PORT_2. Please update your configuration." - #elif DGUS_SERIAL_PORT == -1 - #define DGUS_SERIAL Serial - #elif DGUS_SERIAL_PORT == 0 - #define DGUS_SERIAL Serial1 - #elif DGUS_SERIAL_PORT == 1 - #define DGUS_SERIAL Serial2 - #elif DGUS_SERIAL_PORT == 2 - #define DGUS_SERIAL Serial3 - #elif DGUS_SERIAL_PORT == 2 - #define DGUS_SERIAL Serial4 + #ifdef LCD_SERIAL_PORT + #if LCD_SERIAL_PORT == -1 + #define LCD_SERIAL Serial + #elif WITHIN(LCD_SERIAL_PORT, 0, 3) + #define LCD_SERIAL MSERIAL(LCD_SERIAL_PORT) #else - #error "DGUS_SERIAL_PORT must be from -1 to 3. Please update your configuration." + #error "LCD_SERIAL_PORT must be from -1 to 3. Please update your configuration." #endif #endif diff --git a/Marlin/src/HAL/SAMD51/QSPIFlash.h b/Marlin/src/HAL/SAMD51/QSPIFlash.h index b6f22769ff..db4abec91c 100644 --- a/Marlin/src/HAL/SAMD51/QSPIFlash.h +++ b/Marlin/src/HAL/SAMD51/QSPIFlash.h @@ -24,7 +24,6 @@ * THE SOFTWARE. * * Derived from Adafruit_SPIFlash class with no SdFat references - * */ #pragma once diff --git a/Marlin/src/HAL/SAMD51/pinsDebug.h b/Marlin/src/HAL/SAMD51/pinsDebug.h index c28937d6c6..81376db79a 100644 --- a/Marlin/src/HAL/SAMD51/pinsDebug.h +++ b/Marlin/src/HAL/SAMD51/pinsDebug.h @@ -150,5 +150,4 @@ void pwm_details(int32_t pin) { * 93 | PA10 | QSPI: IO2 * 94 | PA11 | QSPI: IO3 * 95 | PB31 | SD: DETECT - * */ diff --git a/Marlin/src/HAL/STM32/HAL.h b/Marlin/src/HAL/STM32/HAL.h index 08081331b7..60ab45374a 100644 --- a/Marlin/src/HAL/STM32/HAL.h +++ b/Marlin/src/HAL/STM32/HAL.h @@ -43,83 +43,40 @@ // ------------------------ // Defines // ------------------------ +#define _MSERIAL(X) MSerial##X +#define MSERIAL(X) _MSERIAL(X) -#if SERIAL_PORT == 0 - #error "SERIAL_PORT cannot be 0. (Port 0 does not exist.) Please update your configuration." -#elif SERIAL_PORT == -1 +#if SERIAL_PORT == -1 #define MYSERIAL0 SerialUSB -#elif SERIAL_PORT == 1 - #define MYSERIAL0 MSerial1 -#elif SERIAL_PORT == 2 - #define MYSERIAL0 MSerial2 -#elif SERIAL_PORT == 3 - #define MYSERIAL0 MSerial3 -#elif SERIAL_PORT == 4 - #define MYSERIAL0 MSerial4 -#elif SERIAL_PORT == 5 - #define MYSERIAL0 MSerial5 -#elif SERIAL_PORT == 6 - #define MYSERIAL0 MSerial6 +#elif WITHIN(SERIAL_PORT, 1, 6) + #define MYSERIAL0 MSERIAL(SERIAL_PORT) #else - #error "SERIAL_PORT must be from -1 to 6. Please update your configuration." + #error "SERIAL_PORT must be -1 or from 1 to 6. Please update your configuration." #endif #ifdef SERIAL_PORT_2 - #define NUM_SERIAL 2 - #if SERIAL_PORT_2 == 0 - #error "SERIAL_PORT_2 cannot be 0. (Port 0 does not exist.) Please update your configuration." - #elif SERIAL_PORT_2 == SERIAL_PORT - #error "SERIAL_PORT_2 must be different than SERIAL_PORT. Please update your configuration." - #elif SERIAL_PORT_2 == -1 + #if SERIAL_PORT_2 == -1 #define MYSERIAL1 SerialUSB - #elif SERIAL_PORT_2 == 1 - #define MYSERIAL1 MSerial1 - #elif SERIAL_PORT_2 == 2 - #define MYSERIAL1 MSerial2 - #elif SERIAL_PORT_2 == 3 - #define MYSERIAL1 MSerial3 - #elif SERIAL_PORT_2 == 4 - #define MYSERIAL1 MSerial4 - #elif SERIAL_PORT_2 == 5 - #define MYSERIAL1 MSerial5 - #elif SERIAL_PORT_2 == 6 - #define MYSERIAL1 MSerial6 + #elif WITHIN(SERIAL_PORT_2, 1, 6) + #define MYSERIAL1 MSERIAL(SERIAL_PORT_2) #else - #error "SERIAL_PORT_2 must be from -1 to 6. Please update your configuration." + #error "SERIAL_PORT_2 must be -1 or from 1 to 6. Please update your configuration." #endif -#else - #define NUM_SERIAL 1 #endif -#if HAS_DGUS_LCD - #if DGUS_SERIAL_PORT == 0 - #error "DGUS_SERIAL_PORT cannot be 0. (Port 0 does not exist.) Please update your configuration." - #elif DGUS_SERIAL_PORT == SERIAL_PORT - #error "DGUS_SERIAL_PORT must be different than SERIAL_PORT. Please update your configuration." - #elif defined(SERIAL_PORT_2) && DGUS_SERIAL_PORT == SERIAL_PORT_2 - #error "DGUS_SERIAL_PORT must be different than SERIAL_PORT_2. Please update your configuration." - #elif DGUS_SERIAL_PORT == -1 - #define DGUS_SERIAL SerialUSB - #elif DGUS_SERIAL_PORT == 1 - #define DGUS_SERIAL MSerial1 - #elif DGUS_SERIAL_PORT == 2 - #define DGUS_SERIAL MSerial2 - #elif DGUS_SERIAL_PORT == 3 - #define DGUS_SERIAL MSerial3 - #elif DGUS_SERIAL_PORT == 4 - #define DGUS_SERIAL MSerial4 - #elif DGUS_SERIAL_PORT == 5 - #define DGUS_SERIAL MSerial5 - #elif DGUS_SERIAL_PORT == 6 - #define DGUS_SERIAL MSerial6 +#ifdef LCD_SERIAL_PORT + #if LCD_SERIAL_PORT == -1 + #define LCD_SERIAL SerialUSB + #elif WITHIN(LCD_SERIAL_PORT, 1, 6) + #define LCD_SERIAL MSERIAL(LCD_SERIAL_PORT) #else - #error "DGUS_SERIAL_PORT must be from -1 to 6. Please update your configuration." + #error "LCD_SERIAL_PORT must be -1 or from 1 to 6. Please update your configuration." + #endif + #if HAS_DGUS_LCD + #define SERIAL_GET_TX_BUFFER_FREE() LCD_SERIAL.availableForWrite() #endif - - #define DGUS_SERIAL_GET_TX_BUFFER_FREE DGUS_SERIAL.availableForWrite #endif - /** * TODO: review this to return 1 for pins that are not analog input */ diff --git a/Marlin/src/HAL/STM32/MarlinSerial.cpp b/Marlin/src/HAL/STM32/MarlinSerial.cpp index 8d99ab7855..a146664366 100644 --- a/Marlin/src/HAL/STM32/MarlinSerial.cpp +++ b/Marlin/src/HAL/STM32/MarlinSerial.cpp @@ -49,16 +49,14 @@ DECLARE_SERIAL_PORT_EXP(SERIAL_PORT_2) #endif -#if defined(DGUS_SERIAL_PORT) && DGUS_SERIAL_PORT >= 0 - DECLARE_SERIAL_PORT_EXP(DGUS_SERIAL_PORT) +#if defined(LCD_SERIAL_PORT) && LCD_SERIAL_PORT >= 0 + DECLARE_SERIAL_PORT_EXP(LCD_SERIAL_PORT) #endif void MarlinSerial::begin(unsigned long baud, uint8_t config) { HardwareSerial::begin(baud, config); - // replace the IRQ callback with the one we have defined - #if ENABLED(EMERGENCY_PARSER) - _serial.rx_callback = _rx_callback; - #endif + // Replace the IRQ callback with the one we have defined + TERN_(EMERGENCY_PARSER, _serial.rx_callback = _rx_callback); } // This function is Copyright (c) 2006 Nicholas Zambetti. diff --git a/Marlin/src/HAL/STM32/MarlinSerial.h b/Marlin/src/HAL/STM32/MarlinSerial.h index 5ab97ff3a9..3611cc78d7 100644 --- a/Marlin/src/HAL/STM32/MarlinSerial.h +++ b/Marlin/src/HAL/STM32/MarlinSerial.h @@ -35,6 +35,10 @@ public: #endif { } + #if ENABLED(EMERGENCY_PARSER) + static inline bool emergency_parser_enabled() { return true; } + #endif + void begin(unsigned long baud, uint8_t config); inline void begin(unsigned long baud) { begin(baud, SERIAL_8N1); } diff --git a/Marlin/src/HAL/STM32/SoftwareSerial.cpp b/Marlin/src/HAL/STM32/SoftwareSerial.cpp deleted file mode 100644 index 2228a177be..0000000000 --- a/Marlin/src/HAL/STM32/SoftwareSerial.cpp +++ /dev/null @@ -1,396 +0,0 @@ -/* - * SoftwareSerial.cpp (formerly NewSoftSerial.cpp) - * - * Multi-instance software serial library for Arduino/Wiring - * -- Interrupt-driven receive and other improvements by ladyada - * - * -- Tuning, circular buffer, derivation from class Print/Stream, - * multi-instance support, porting to 8MHz processors, - * various optimizations, PROGMEM delay tables, inverse logic and - * direct port writing by Mikal Hart - * -- Pin change interrupt macros by Paul Stoffregen - * -- 20MHz processor support by Garrett Mace - * -- ATmega1280/2560 support by Brett Hagman - * -- STM32 support by Armin van der Togt - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the GNU Lesser General Public - * License as published by the Free Software Foundation; either - * version 2.1 of the License, or (at your option) any later version. - * - * This library is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - * Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public - * License along with this library; if not, write to the Free Software - * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA - * - * The latest version of this library can always be found at - * http://arduiniana.org. - */ - -// -// Includes -// -#if defined(PLATFORMIO) && defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) - -#include "../../inc/MarlinConfig.h" - -#include "SoftwareSerial.h" - -#define OVERSAMPLE 3 // in RX, Timer will generate interruption OVERSAMPLE time during a bit. Thus OVERSAMPLE ticks in a bit. (interrupt not synchonized with edge). - -// defined in bit-periods -#define HALFDUPLEX_SWITCH_DELAY 5 -// It's best to define TIMER_SERIAL in variant.h. If not defined, we choose one here -// The order is based on (lack of) features and compare channels, we choose the simplest available -// because we only need an update interrupt -#if !defined(TIMER_SERIAL) -#if defined(TIM18_BASE) -#define TIMER_SERIAL TIM18 -#elif defined(TIM7_BASE) -#define TIMER_SERIAL TIM7 -#elif defined(TIM6_BASE) -#define TIMER_SERIAL TIM6 -#elif defined(TIM22_BASE) -#define TIMER_SERIAL TIM22 -#elif defined(TIM21_BASE) -#define TIMER_SERIAL TIM21 -#elif defined(TIM17_BASE) -#define TIMER_SERIAL TIM17 -#elif defined(TIM16_BASE) -#define TIMER_SERIAL TIM16 -#elif defined(TIM15_BASE) -#define TIMER_SERIAL TIM15 -#elif defined(TIM14_BASE) -#define TIMER_SERIAL TIM14 -#elif defined(TIM13_BASE) -#define TIMER_SERIAL TIM13 -#elif defined(TIM11_BASE) -#define TIMER_SERIAL TIM11 -#elif defined(TIM10_BASE) -#define TIMER_SERIAL TIM10 -#elif defined(TIM12_BASE) -#define TIMER_SERIAL TIM12 -#elif defined(TIM19_BASE) -#define TIMER_SERIAL TIM19 -#elif defined(TIM9_BASE) -#define TIMER_SERIAL TIM9 -#elif defined(TIM5_BASE) -#define TIMER_SERIAL TIM5 -#elif defined(TIM4_BASE) -#define TIMER_SERIAL TIM4 -#elif defined(TIM3_BASE) -#define TIMER_SERIAL TIM3 -#elif defined(TIM2_BASE) -#define TIMER_SERIAL TIM2 -#elif defined(TIM20_BASE) -#define TIMER_SERIAL TIM20 -#elif defined(TIM8_BASE) -#define TIMER_SERIAL TIM8 -#elif defined(TIM1_BASE) -#define TIMER_SERIAL TIM1 -#else -#error No suitable timer found for SoftwareSerial, define TIMER_SERIAL in variant.h -#endif -#endif -// -// Statics -// -HardwareTimer SoftwareSerial::timer(TIMER_SERIAL); -const IRQn_Type SoftwareSerial::timer_interrupt_number = static_cast(getTimerUpIrq(TIMER_SERIAL)); -uint32_t SoftwareSerial::timer_interrupt_priority = NVIC_EncodePriority(NVIC_GetPriorityGrouping(), TIM_IRQ_PRIO, TIM_IRQ_SUBPRIO); -SoftwareSerial *SoftwareSerial::active_listener = nullptr; -SoftwareSerial *volatile SoftwareSerial::active_out = nullptr; -SoftwareSerial *volatile SoftwareSerial::active_in = nullptr; -int32_t SoftwareSerial::tx_tick_cnt = 0; // OVERSAMPLE ticks needed for a bit -int32_t volatile SoftwareSerial::rx_tick_cnt = 0; // OVERSAMPLE ticks needed for a bit -uint32_t SoftwareSerial::tx_buffer = 0; -int32_t SoftwareSerial::tx_bit_cnt = 0; -uint32_t SoftwareSerial::rx_buffer = 0; -int32_t SoftwareSerial::rx_bit_cnt = -1; // rx_bit_cnt = -1 : waiting for start bit -uint32_t SoftwareSerial::cur_speed = 0; - -void SoftwareSerial::setInterruptPriority(uint32_t preemptPriority, uint32_t subPriority) { - timer_interrupt_priority = NVIC_EncodePriority(NVIC_GetPriorityGrouping(), preemptPriority, subPriority); -} - -// -// Private methods -// - -void SoftwareSerial::setSpeed(uint32_t speed) { - if (speed != cur_speed) { - timer.pause(); - if (speed != 0) { - // Disable the timer - uint32_t clock_rate, cmp_value; - // Get timer clock - clock_rate = timer.getTimerClkFreq(); - int pre = 1; - // Calculate prescale an compare value - do { - cmp_value = clock_rate / (speed * OVERSAMPLE); - if (cmp_value >= UINT16_MAX) { - clock_rate /= 2; - pre *= 2; - } - } while (cmp_value >= UINT16_MAX); - timer.setPrescaleFactor(pre); - timer.setOverflow(cmp_value); - timer.setCount(0); - timer.attachInterrupt(&handleInterrupt); - timer.resume(); - NVIC_SetPriority(timer_interrupt_number, timer_interrupt_priority); - } - else - timer.detachInterrupt(); - cur_speed = speed; - } -} - -// This function sets the current object as the "listening" -// one and returns true if it replaces another -bool SoftwareSerial::listen() { - if (active_listener != this) { - // wait for any transmit to complete as we may change speed - while (active_out); - active_listener->stopListening(); - rx_tick_cnt = 1; // 1 : next interrupt will decrease rx_tick_cnt to 0 which means RX pin level will be considered. - rx_bit_cnt = -1; // rx_bit_cnt = -1 : waiting for start bit - setSpeed(_speed); - active_listener = this; - if (!_half_duplex) active_in = this; - return true; - } - return false; -} - -// Stop listening. Returns true if we were actually listening. -bool SoftwareSerial::stopListening() { - if (active_listener == this) { - // wait for any output to complete - while (active_out); - if (_half_duplex) setRXTX(false); - active_listener = nullptr; - active_in = nullptr; - // turn off ints - setSpeed(0); - return true; - } - return false; -} - -inline void SoftwareSerial::setTX() { - if (_inverse_logic) - LL_GPIO_ResetOutputPin(_transmitPinPort, _transmitPinNumber); - else - LL_GPIO_SetOutputPin(_transmitPinPort, _transmitPinNumber); - pinMode(_transmitPin, OUTPUT); -} - -inline void SoftwareSerial::setRX() { - pinMode(_receivePin, _inverse_logic ? INPUT_PULLDOWN : INPUT_PULLUP); // pullup for normal logic! -} - -inline void SoftwareSerial::setRXTX(bool input) { - if (_half_duplex) { - if (input) { - if (active_in != this) { - setRX(); - rx_bit_cnt = -1; // rx_bit_cnt = -1 : waiting for start bit - rx_tick_cnt = 2; // 2 : next interrupt will be discarded. 2 interrupts required to consider RX pin level - active_in = this; - } - } - else { - if (active_in == this) { - setTX(); - active_in = nullptr; - } - } - } -} - -inline void SoftwareSerial::send() { - if (--tx_tick_cnt <= 0) { // if tx_tick_cnt > 0 interrupt is discarded. Only when tx_tick_cnt reaches 0 is TX pin set. - if (tx_bit_cnt++ < 10) { // tx_bit_cnt < 10 transmission is not finished (10 = 1 start +8 bits + 1 stop) - // Send data (including start and stop bits) - if (tx_buffer & 1) - LL_GPIO_SetOutputPin(_transmitPinPort, _transmitPinNumber); - else - LL_GPIO_ResetOutputPin(_transmitPinPort, _transmitPinNumber); - tx_buffer >>= 1; - tx_tick_cnt = OVERSAMPLE; // Wait OVERSAMPLE ticks to send next bit - } - else { // Transmission finished - tx_tick_cnt = 1; - if (_output_pending) { - active_out = nullptr; - - // In half-duplex mode wait HALFDUPLEX_SWITCH_DELAY bit-periods after the byte has - // been transmitted before allowing the switch to RX mode - } - else if (tx_bit_cnt > 10 + OVERSAMPLE * HALFDUPLEX_SWITCH_DELAY) { - if (_half_duplex && active_listener == this) setRXTX(true); - active_out = nullptr; - } - } - } -} - -// -// The receive routine called by the interrupt handler -// -inline void SoftwareSerial::recv() { - if (--rx_tick_cnt <= 0) { // if rx_tick_cnt > 0 interrupt is discarded. Only when rx_tick_cnt reaches 0 is RX pin considered - bool inbit = LL_GPIO_IsInputPinSet(_receivePinPort, _receivePinNumber) ^ _inverse_logic; - if (rx_bit_cnt == -1) { // rx_bit_cnt = -1 : waiting for start bit - if (!inbit) { - // got start bit - rx_bit_cnt = 0; // rx_bit_cnt == 0 : start bit received - rx_tick_cnt = OVERSAMPLE + 1; // Wait 1 bit (OVERSAMPLE ticks) + 1 tick in order to sample RX pin in the middle of the edge (and not too close to the edge) - rx_buffer = 0; - } - else - rx_tick_cnt = 1; // Waiting for start bit, but wrong level. Wait for next Interrupt to check RX pin level - } - else if (rx_bit_cnt >= 8) { // rx_bit_cnt >= 8 : waiting for stop bit - if (inbit) { - // Stop-bit read complete. Add to buffer. - uint8_t next = (_receive_buffer_tail + 1) % _SS_MAX_RX_BUFF; - if (next != _receive_buffer_head) { - // save new data in buffer: tail points to byte destination - _receive_buffer[_receive_buffer_tail] = rx_buffer; // save new byte - _receive_buffer_tail = next; - } - else // rx_bit_cnt = x with x = [0..7] correspond to new bit x received - _buffer_overflow = true; - } - // Full trame received. Restart waiting for start bit at next interrupt - rx_tick_cnt = 1; - rx_bit_cnt = -1; - } - else { - // data bits - rx_buffer >>= 1; - if (inbit) rx_buffer |= 0x80; - rx_bit_cnt++; // Prepare for next bit - rx_tick_cnt = OVERSAMPLE; // Wait OVERSAMPLE ticks before sampling next bit - } - } -} - -// -// Interrupt handling -// - -/* static */ -inline void SoftwareSerial::handleInterrupt(HardwareTimer*) { - if (active_in) active_in->recv(); - if (active_out) active_out->send(); -} - -// -// Constructor -// -SoftwareSerial::SoftwareSerial(uint16_t receivePin, uint16_t transmitPin, bool inverse_logic /* = false */) : - _receivePin(receivePin), - _transmitPin(transmitPin), - _receivePinPort(digitalPinToPort(receivePin)), - _receivePinNumber(STM_LL_GPIO_PIN(digitalPinToPinName(receivePin))), - _transmitPinPort(digitalPinToPort(transmitPin)), - _transmitPinNumber(STM_LL_GPIO_PIN(digitalPinToPinName(transmitPin))), - _speed(0), - _buffer_overflow(false), - _inverse_logic(inverse_logic), - _half_duplex(receivePin == transmitPin), - _output_pending(0), - _receive_buffer_tail(0), - _receive_buffer_head(0) -{ - if ((receivePin < NUM_DIGITAL_PINS) || (transmitPin < NUM_DIGITAL_PINS)) { - /* Enable GPIO clock for tx and rx pin*/ - set_GPIO_Port_Clock(STM_PORT(digitalPinToPinName(transmitPin))); - set_GPIO_Port_Clock(STM_PORT(digitalPinToPinName(receivePin))); - } - else - _Error_Handler("ERROR: invalid pin number\n", -1); -} - -// -// Destructor -// -SoftwareSerial::~SoftwareSerial() { end(); } - -// -// Public methods -// - -void SoftwareSerial::begin(long speed) { - #ifdef FORCE_BAUD_RATE - speed = FORCE_BAUD_RATE; - #endif - _speed = speed; - if (!_half_duplex) { - setTX(); - setRX(); - listen(); - } - else - setTX(); -} - -void SoftwareSerial::end() { - stopListening(); -} - -// Read data from buffer -int SoftwareSerial::read() { - // Empty buffer? - if (_receive_buffer_head == _receive_buffer_tail) return -1; - - // Read from "head" - uint8_t d = _receive_buffer[_receive_buffer_head]; // grab next byte - _receive_buffer_head = (_receive_buffer_head + 1) % _SS_MAX_RX_BUFF; - return d; -} - -int SoftwareSerial::available() { - return (_receive_buffer_tail + _SS_MAX_RX_BUFF - _receive_buffer_head) % _SS_MAX_RX_BUFF; -} - -size_t SoftwareSerial::write(uint8_t b) { - // wait for previous transmit to complete - _output_pending = 1; - while (active_out) { /* nada */ } - // add start and stop bits. - tx_buffer = b << 1 | 0x200; - if (_inverse_logic) tx_buffer = ~tx_buffer; - tx_bit_cnt = 0; - tx_tick_cnt = OVERSAMPLE; - setSpeed(_speed); - if (_half_duplex) setRXTX(false); - _output_pending = 0; - // make us active - active_out = this; - return 1; -} - -void SoftwareSerial::flush() { - noInterrupts(); - _receive_buffer_head = _receive_buffer_tail = 0; - interrupts(); -} - -int SoftwareSerial::peek() { - // Empty buffer? - if (_receive_buffer_head == _receive_buffer_tail) return -1; - - // Read from "head" - return _receive_buffer[_receive_buffer_head]; -} - -#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC diff --git a/Marlin/src/HAL/STM32/SoftwareSerial.h b/Marlin/src/HAL/STM32/SoftwareSerial.h deleted file mode 100644 index 1a4f742c32..0000000000 --- a/Marlin/src/HAL/STM32/SoftwareSerial.h +++ /dev/null @@ -1,114 +0,0 @@ -/** - * SoftwareSerial.h (formerly NewSoftSerial.h) - * - * Multi-instance software serial library for Arduino/Wiring - * -- Interrupt-driven receive and other improvements by ladyada - * (https://ladyada.net) - * -- Tuning, circular buffer, derivation from class Print/Stream, - * multi-instance support, porting to 8MHz processors, - * various optimizations, PROGMEM delay tables, inverse logic and - * direct port writing by Mikal Hart (http://www.arduiniana.org) - * -- Pin change interrupt macros by Paul Stoffregen (https://www.pjrc.com) - * -- 20MHz processor support by Garrett Mace (http://www.macetech.com) - * -- ATmega1280/2560 support by Brett Hagman (https://www.roguerobotics.com/) - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the GNU Lesser General Public - * License as published by the Free Software Foundation; either - * version 2.1 of the License, or (at your option) any later version. - * - * This library is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - * Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public - * License along with this library; if not, write to the Free Software - * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA - * - * The latest version of this library can always be found at - * http://arduiniana.org. - */ -#pragma once - -#include - -/****************************************************************************** - * Definitions - ******************************************************************************/ - -#define _SS_MAX_RX_BUFF 64 // RX buffer size - -class SoftwareSerial : public Stream { - private: - // per object data - uint16_t _receivePin; - uint16_t _transmitPin; - GPIO_TypeDef *_receivePinPort; - uint32_t _receivePinNumber; - GPIO_TypeDef *_transmitPinPort; - uint32_t _transmitPinNumber; - uint32_t _speed; - - uint16_t _buffer_overflow: 1; - uint16_t _inverse_logic: 1; - uint16_t _half_duplex: 1; - uint16_t _output_pending: 1; - - unsigned char _receive_buffer[_SS_MAX_RX_BUFF]; - volatile uint8_t _receive_buffer_tail; - volatile uint8_t _receive_buffer_head; - - uint32_t delta_start = 0; - - // static data - static HardwareTimer timer; - static const IRQn_Type timer_interrupt_number; - static uint32_t timer_interrupt_priority; - static SoftwareSerial *active_listener; - static SoftwareSerial *volatile active_out; - static SoftwareSerial *volatile active_in; - static int32_t tx_tick_cnt; - static volatile int32_t rx_tick_cnt; - static uint32_t tx_buffer; - static int32_t tx_bit_cnt; - static uint32_t rx_buffer; - static int32_t rx_bit_cnt; - static uint32_t cur_speed; - - // private methods - void send(); - void recv(); - void setTX(); - void setRX(); - void setSpeed(uint32_t speed); - void setRXTX(bool input); - static void handleInterrupt(HardwareTimer *timer); - - public: - // public methods - - SoftwareSerial(uint16_t receivePin, uint16_t transmitPin, bool inverse_logic=false); - virtual ~SoftwareSerial(); - void begin(long speed); - bool listen(); - void end(); - bool isListening() { return active_listener == this; } - bool stopListening(); - bool overflow() { - bool ret = _buffer_overflow; - if (ret) _buffer_overflow = false; - return ret; - } - int peek(); - - virtual size_t write(uint8_t byte); - virtual int read(); - virtual int available(); - virtual void flush(); - operator bool() { return true; } - - static void setInterruptPriority(uint32_t preemptPriority, uint32_t subPriority); - - using Print::write; -}; diff --git a/Marlin/src/HAL/STM32/pinsDebug_STM32GENERIC.h b/Marlin/src/HAL/STM32/pinsDebug_STM32GENERIC.h index 5ff40debea..9069d9f7bd 100644 --- a/Marlin/src/HAL/STM32/pinsDebug_STM32GENERIC.h +++ b/Marlin/src/HAL/STM32/pinsDebug_STM32GENERIC.h @@ -98,7 +98,7 @@ static inline void pwm_details(const pin_t pin) { timer_dev * const tdev = PIN_MAP[pin].timer_device; const uint8_t channel = PIN_MAP[pin].timer_channel; const char num = ( - #if defined(STM32_HIGH_DENSITY) || defined(STM32_XL_DENSITY) + #if EITHER(STM32_HIGH_DENSITY, STM32_XL_DENSITY) tdev == &timer8 ? '8' : tdev == &timer5 ? '5' : #endif diff --git a/Marlin/src/HAL/STM32/tft/tft_fsmc.cpp b/Marlin/src/HAL/STM32/tft/tft_fsmc.cpp index f11fab39db..3a080d5e27 100644 --- a/Marlin/src/HAL/STM32/tft/tft_fsmc.cpp +++ b/Marlin/src/HAL/STM32/tft/tft_fsmc.cpp @@ -87,7 +87,7 @@ void TFT_FSMC::Init() { __HAL_RCC_FSMC_CLK_ENABLE(); - for(uint16_t i = 0; PinMap_FSMC[i].pin != NC; i++) + for (uint16_t i = 0; PinMap_FSMC[i].pin != NC; i++) pinmap_pinout(PinMap_FSMC[i].pin, PinMap_FSMC); pinmap_pinout(digitalPinToPinName(TFT_CS_PIN), PinMap_FSMC_CS); pinmap_pinout(digitalPinToPinName(TFT_RS_PIN), PinMap_FSMC_RS); diff --git a/Marlin/src/HAL/STM32/tft/xpt2046.cpp b/Marlin/src/HAL/STM32/tft/xpt2046.cpp index 49e64da6a1..921e377a9f 100644 --- a/Marlin/src/HAL/STM32/tft/xpt2046.cpp +++ b/Marlin/src/HAL/STM32/tft/xpt2046.cpp @@ -155,9 +155,9 @@ uint16_t XPT2046::getRawData(const XPTCoordinate coordinate) { uint16_t XPT2046::HardwareIO(uint16_t data) { __HAL_SPI_ENABLE(&SPIx); - while((SPIx.Instance->SR & SPI_FLAG_TXE) != SPI_FLAG_TXE) {} + while ((SPIx.Instance->SR & SPI_FLAG_TXE) != SPI_FLAG_TXE) {} SPIx.Instance->DR = data; - while((SPIx.Instance->SR & SPI_FLAG_RXNE) != SPI_FLAG_RXNE) {} + while ((SPIx.Instance->SR & SPI_FLAG_RXNE) != SPI_FLAG_RXNE) {} __HAL_SPI_DISABLE(&SPIx); return SPIx.Instance->DR; diff --git a/Marlin/src/HAL/STM32/timers.cpp b/Marlin/src/HAL/STM32/timers.cpp index 1196731448..c0ba19abe5 100644 --- a/Marlin/src/HAL/STM32/timers.cpp +++ b/Marlin/src/HAL/STM32/timers.cpp @@ -110,7 +110,6 @@ // ------------------------ HardwareTimer *timer_instance[NUM_HARDWARE_TIMERS] = { NULL }; -bool timer_enabled[NUM_HARDWARE_TIMERS] = { false }; // ------------------------ // Public functions @@ -135,6 +134,7 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { * which changes the prescaler when an IRQ frequency change is needed * (for example when steppers are turned on) */ + timer_instance[timer_num]->setPrescaleFactor(STEPPER_TIMER_PRESCALE); //the -1 is done internally timer_instance[timer_num]->setOverflow(_MIN(hal_timer_t(HAL_TIMER_TYPE_MAX), (HAL_TIMER_RATE) / (STEPPER_TIMER_PRESCALE) /* /frequency */), TICK_FORMAT); break; @@ -145,15 +145,13 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { break; } + // Disable preload. Leaving it default-enabled can cause the timer to stop if it happens + // to exit the ISR after the start time for the next interrupt has already passed. + timer_instance[timer_num]->setPreloadEnable(false); + HAL_timer_enable_interrupt(timer_num); - /* - * Initializes (and unfortunately starts) the timer. - * This is needed to set correct IRQ priority at the moment but causes - * no harm since every call to HAL_timer_start() is actually followed by - * a call to HAL_timer_enable_interrupt() which means that there isn't - * a case in which you want the timer to run without a callback. - */ + // Start the timer. timer_instance[timer_num]->resume(); // First call to resume() MUST follow the attachInterrupt() // This is fixed in Arduino_Core_STM32 1.8. @@ -161,47 +159,34 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { // timer_instance[timer_num]->setInterruptPriority switch (timer_num) { case STEP_TIMER_NUM: - HAL_NVIC_SetPriority(STEP_TIMER_IRQ_NAME, STEP_TIMER_IRQ_PRIO, 0); + timer_instance[timer_num]->setInterruptPriority(STEP_TIMER_IRQ_PRIO, 0); break; case TEMP_TIMER_NUM: - HAL_NVIC_SetPriority(TEMP_TIMER_IRQ_NAME, TEMP_TIMER_IRQ_PRIO, 0); + timer_instance[timer_num]->setInterruptPriority(TEMP_TIMER_IRQ_PRIO, 0); break; } } } void HAL_timer_enable_interrupt(const uint8_t timer_num) { - if (HAL_timer_initialized(timer_num) && !timer_enabled[timer_num]) { - timer_enabled[timer_num] = true; + if (HAL_timer_initialized(timer_num) && !timer_instance[timer_num]->hasInterrupt()) { switch (timer_num) { case STEP_TIMER_NUM: - timer_instance[timer_num]->attachInterrupt(Step_Handler); - break; - case TEMP_TIMER_NUM: - timer_instance[timer_num]->attachInterrupt(Temp_Handler); - break; + timer_instance[timer_num]->attachInterrupt(Step_Handler); + break; + case TEMP_TIMER_NUM: + timer_instance[timer_num]->attachInterrupt(Temp_Handler); + break; } } } void HAL_timer_disable_interrupt(const uint8_t timer_num) { - if (HAL_timer_interrupt_enabled(timer_num)) { - timer_instance[timer_num]->detachInterrupt(); - timer_enabled[timer_num] = false; - } + if (HAL_timer_initialized(timer_num)) timer_instance[timer_num]->detachInterrupt(); } bool HAL_timer_interrupt_enabled(const uint8_t timer_num) { - return HAL_timer_initialized(timer_num) && timer_enabled[timer_num]; -} - -// Only for use within the HAL -TIM_TypeDef * HAL_timer_device(const uint8_t timer_num) { - switch (timer_num) { - case STEP_TIMER_NUM: return STEP_TIMER_DEV; - case TEMP_TIMER_NUM: return TEMP_TIMER_DEV; - } - return nullptr; + return HAL_timer_initialized(timer_num) && timer_instance[timer_num]->hasInterrupt(); } void SetTimerInterruptPriorities() { @@ -209,4 +194,87 @@ void SetTimerInterruptPriorities() { TERN_(HAS_SERVOS, libServo::setInterruptPriority(SERVO_TIMER_IRQ_PRIO, 0)); } +// This is a terrible hack to replicate the behavior used in the framework's SoftwareSerial.cpp +// to choose a serial timer. It will select TIM7 on most boards used by Marlin, but this is more +// resiliant to new MCUs which may not have a TIM7. Best practice is to explicitly specify +// TIMER_SERIAL to avoid relying on framework selections which may not be predictable. +#if !defined(TIMER_SERIAL) + #if defined (TIM18_BASE) + #define TIMER_SERIAL TIM18 + #elif defined (TIM7_BASE) + #define TIMER_SERIAL TIM7 + #elif defined (TIM6_BASE) + #define TIMER_SERIAL TIM6 + #elif defined (TIM22_BASE) + #define TIMER_SERIAL TIM22 + #elif defined (TIM21_BASE) + #define TIMER_SERIAL TIM21 + #elif defined (TIM17_BASE) + #define TIMER_SERIAL TIM17 + #elif defined (TIM16_BASE) + #define TIMER_SERIAL TIM16 + #elif defined (TIM15_BASE) + #define TIMER_SERIAL TIM15 + #elif defined (TIM14_BASE) + #define TIMER_SERIAL TIM14 + #elif defined (TIM13_BASE) + #define TIMER_SERIAL TIM13 + #elif defined (TIM11_BASE) + #define TIMER_SERIAL TIM11 + #elif defined (TIM10_BASE) + #define TIMER_SERIAL TIM10 + #elif defined (TIM12_BASE) + #define TIMER_SERIAL TIM12 + #elif defined (TIM19_BASE) + #define TIMER_SERIAL TIM19 + #elif defined (TIM9_BASE) + #define TIMER_SERIAL TIM9 + #elif defined (TIM5_BASE) + #define TIMER_SERIAL TIM5 + #elif defined (TIM4_BASE) + #define TIMER_SERIAL TIM4 + #elif defined (TIM3_BASE) + #define TIMER_SERIAL TIM3 + #elif defined (TIM2_BASE) + #define TIMER_SERIAL TIM2 + #elif defined (TIM20_BASE) + #define TIMER_SERIAL TIM20 + #elif defined (TIM8_BASE) + #define TIMER_SERIAL TIM8 + #elif defined (TIM1_BASE) + #define TIMER_SERIAL TIM1 + #else + #error No suitable timer found for SoftwareSerial, define TIMER_SERIAL in variant.h + #endif +#endif + +// Place all timers used into an array, then recursively check for duplicates during compilation. +// This does not currently account for timers used for PWM, such as for fans. +// Timers are actually pointers. Convert to integers to simplify constexpr logic. +static constexpr uintptr_t timers_in_use[] = { + uintptr_t(TEMP_TIMER_DEV), // Override in pins file + uintptr_t(STEP_TIMER_DEV), // Override in pins file + #if HAS_TMC_SW_SERIAL + uintptr_t(TIMER_SERIAL), // Set in variant.h, or as a define in platformio.h if not present in variant.h + #endif + #if ENABLED(SPEAKER) + uintptr_t(TIMER_TONE), // Set in variant.h, or as a define in platformio.h if not present in variant.h + #endif + #if HAS_SERVOS + uintptr_t(TIMER_SERVO), // Set in variant.h, or as a define in platformio.h if not present in variant.h + #endif + }; + +static constexpr bool verify_no_duplicate_timers() { + LOOP_L_N(i, COUNT(timers_in_use)) + LOOP_S_L_N(j, i + 1, COUNT(timers_in_use)) + if (timers_in_use[i] == timers_in_use[j]) return false; + return true; +} + +// If this assertion fails at compile time, review the timers_in_use array. If default_envs is +// defined properly in platformio.ini, VS Code can evaluate the array when hovering over it, +// making it easy to identify the conflicting timers. +static_assert(verify_no_duplicate_timers(), "One or more timer conflict detected"); + #endif // ARDUINO_ARCH_STM32 && !STM32GENERIC diff --git a/Marlin/src/HAL/STM32/timers.h b/Marlin/src/HAL/STM32/timers.h index 000f86043b..5515219ead 100644 --- a/Marlin/src/HAL/STM32/timers.h +++ b/Marlin/src/HAL/STM32/timers.h @@ -30,8 +30,18 @@ #define FORCE_INLINE __attribute__((always_inline)) inline +// STM32 timers may be 16 or 32 bit. Limiting HAL_TIMER_TYPE_MAX to 16 bits +// avoids issues with STM32F0 MCUs, which seem to pause timers if UINT32_MAX +// is written to the register. STM32F4 timers do not manifest this issue, +// even when writing to 16 bit timers. +// +// The range of the timer can be queried at runtime using IS_TIM_32B_COUNTER_INSTANCE. +// This is a more expensive check than a simple compile-time constant, so its +// implementation is deferred until the desire for a 32-bit range outweighs the cost +// of adding a run-time check and HAL_TIMER_TYPE_MAX is refactored to allow unique +// values for each timer. #define hal_timer_t uint32_t -#define HAL_TIMER_TYPE_MAX 0xFFFFFFFF // Timers can be 16 or 32 bit +#define HAL_TIMER_TYPE_MAX UINT16_MAX #ifndef STEP_TIMER_NUM #define STEP_TIMER_NUM 0 // Timer Index for Stepper @@ -61,14 +71,14 @@ #define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM) #define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM) -extern void Step_Handler(HardwareTimer *htim); -extern void Temp_Handler(HardwareTimer *htim); +extern void Step_Handler(); +extern void Temp_Handler(); #ifndef HAL_STEP_TIMER_ISR - #define HAL_STEP_TIMER_ISR() void Step_Handler(HardwareTimer *htim) + #define HAL_STEP_TIMER_ISR() void Step_Handler() #endif #ifndef HAL_TEMP_TIMER_ISR - #define HAL_TEMP_TIMER_ISR() void Temp_Handler(HardwareTimer *htim) + #define HAL_TEMP_TIMER_ISR() void Temp_Handler() #endif // ------------------------ @@ -90,8 +100,6 @@ bool HAL_timer_interrupt_enabled(const uint8_t timer_num); // Exposed here to allow all timer priority information to reside in timers.cpp void SetTimerInterruptPriorities(); -//TIM_TypeDef* HAL_timer_device(const uint8_t timer_num); no need to be public for now. not public = not used externally - // FORCE_INLINE because these are used in performance-critical situations FORCE_INLINE bool HAL_timer_initialized(const uint8_t timer_num) { return timer_instance[timer_num] != NULL; diff --git a/Marlin/src/HAL/STM32F1/HAL.h b/Marlin/src/HAL/STM32F1/HAL.h index 5a0b046009..5c03593eb0 100644 --- a/Marlin/src/HAL/STM32F1/HAL.h +++ b/Marlin/src/HAL/STM32F1/HAL.h @@ -46,12 +46,14 @@ #include "msc_sd.h" #endif +#include "MarlinSerial.h" + // ------------------------ // Defines // ------------------------ #ifndef STM32_FLASH_SIZE - #if defined(MCU_STM32F103RE) || defined(MCU_STM32F103VE) + #if EITHER(MCU_STM32F103RE, MCU_STM32F103VE) #define STM32_FLASH_SIZE 512 #else #define STM32_FLASH_SIZE 256 @@ -64,87 +66,51 @@ #else #define UsbSerial MarlinCompositeSerial #endif - #define MSerial1 Serial1 - #define MSerial2 Serial2 - #define MSerial3 Serial3 - #define MSerial4 Serial4 - #define MSerial5 Serial5 +#endif + +#define _MSERIAL(X) MSerial##X +#define MSERIAL(X) _MSERIAL(X) + +#if EITHER(STM32_HIGH_DENSITY, STM32_XL_DENSITY) + #define NUM_UARTS 5 #else - #define MSerial1 Serial - #define MSerial2 Serial1 - #define MSerial3 Serial2 - #define MSerial4 Serial3 - #define MSerial5 Serial4 + #define NUM_UARTS 3 #endif -#if SERIAL_PORT == 0 - #error "SERIAL_PORT cannot be 0. (Port 0 does not exist.) Please update your configuration." -#elif SERIAL_PORT == -1 +#if SERIAL_PORT == -1 #define MYSERIAL0 UsbSerial -#elif SERIAL_PORT == 1 - #define MYSERIAL0 MSerial1 -#elif SERIAL_PORT == 2 - #define MYSERIAL0 MSerial2 -#elif SERIAL_PORT == 3 - #define MYSERIAL0 MSerial3 -#elif SERIAL_PORT == 4 - #define MYSERIAL0 MSerial4 -#elif SERIAL_PORT == 5 - #define MYSERIAL0 MSerial5 +#elif WITHIN(SERIAL_PORT, 1, NUM_UARTS) + #define MYSERIAL0 MSERIAL(SERIAL_PORT) +#elif NUM_UARTS == 5 + #error "SERIAL_PORT must be -1 or from 1 to 5. Please update your configuration." #else - #error "SERIAL_PORT must be from -1 to 5. Please update your configuration." + #error "SERIAL_PORT must be -1 or from 1 to 3. Please update your configuration." #endif #ifdef SERIAL_PORT_2 - #if SERIAL_PORT_2 == 0 - #error "SERIAL_PORT_2 cannot be 0. (Port 0 does not exist.) Please update your configuration." - #elif SERIAL_PORT_2 == SERIAL_PORT - #error "SERIAL_PORT_2 must be different than SERIAL_PORT. Please update your configuration." - #elif SERIAL_PORT_2 == -1 + #if SERIAL_PORT_2 == -1 #define MYSERIAL1 UsbSerial - #elif SERIAL_PORT_2 == 1 - #define MYSERIAL1 MSerial1 - #elif SERIAL_PORT_2 == 2 - #define MYSERIAL1 MSerial2 - #elif SERIAL_PORT_2 == 3 - #define MYSERIAL1 MSerial3 - #elif SERIAL_PORT_2 == 4 - #define MYSERIAL1 MSerial4 - #elif SERIAL_PORT_2 == 5 - #define MYSERIAL1 MSerial5 + #elif WITHIN(SERIAL_PORT_2, 1, NUM_UARTS) + #define MYSERIAL1 MSERIAL(SERIAL_PORT_2) + #elif NUM_UARTS == 5 + #error "SERIAL_PORT_2 must be -1 or from 1 to 5. Please update your configuration." #else - #error "SERIAL_PORT_2 must be from -1 to 5. Please update your configuration." + #error "SERIAL_PORT_2 must be -1 or from 1 to 3. Please update your configuration." #endif - #define NUM_SERIAL 2 -#else - #define NUM_SERIAL 1 #endif -#ifdef DGUS_SERIAL - #if DGUS_SERIAL_PORT == 0 - #error "DGUS_SERIAL_PORT cannot be 0. (Port 0 does not exist.) Please update your configuration." - #elif DGUS_SERIAL_PORT == SERIAL_PORT - #error "DGUS_SERIAL_PORT must be different than SERIAL_PORT. Please update your configuration." - #elif defined(SERIAL_PORT_2) && DGUS_SERIAL_PORT == SERIAL_PORT_2 - #error "DGUS_SERIAL_PORT must be different than SERIAL_PORT_2. Please update your configuration." - #elif DGUS_SERIAL_PORT == -1 - #define DGUS_SERIAL UsbSerial - #elif DGUS_SERIAL_PORT == 1 - #define DGUS_SERIAL MSerial1 - #elif DGUS_SERIAL_PORT == 2 - #define DGUS_SERIAL MSerial2 - #elif DGUS_SERIAL_PORT == 3 - #define DGUS_SERIAL MSerial3 - #elif DGUS_SERIAL_PORT == 4 - #define DGUS_SERIAL MSerial4 - #elif DGUS_SERIAL_PORT == 5 - #define DGUS_SERIAL MSerial5 +#ifdef LCD_SERIAL_PORT + #if LCD_SERIAL_PORT == -1 + #define LCD_SERIAL UsbSerial + #elif WITHIN(LCD_SERIAL_PORT, 1, NUM_UARTS) + #define LCD_SERIAL MSERIAL(LCD_SERIAL_PORT) + #elif NUM_UARTS == 5 + #error "LCD_SERIAL_PORT must be -1 or from 1 to 5. Please update your configuration." #else - #error "DGUS_SERIAL_PORT must be from -1 to 5. Please update your configuration." + #error "LCD_SERIAL_PORT must be -1 or from 1 to 3. Please update your configuration." #endif #endif - // Set interrupt grouping for this MCU void HAL_init(); #define HAL_IDLETASK 1 diff --git a/Marlin/src/HAL/STM32F1/MarlinSerial.cpp b/Marlin/src/HAL/STM32F1/MarlinSerial.cpp new file mode 100644 index 0000000000..ebf11cb429 --- /dev/null +++ b/Marlin/src/HAL/STM32F1/MarlinSerial.cpp @@ -0,0 +1,193 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#ifdef __STM32F1__ + +#include "../../inc/MarlinConfig.h" +#include "MarlinSerial.h" +#include + +// Copied from ~/.platformio/packages/framework-arduinoststm32-maple/STM32F1/system/libmaple/usart_private.h +// Changed to handle Emergency Parser +static inline __always_inline void my_usart_irq(ring_buffer *rb, ring_buffer *wb, usart_reg_map *regs, MarlinSerial &serial) { + /* Handle RXNEIE and TXEIE interrupts. + * RXNE signifies availability of a byte in DR. + * + * See table 198 (sec 27.4, p809) in STM document RM0008 rev 15. + * We enable RXNEIE. + */ + uint32_t srflags = regs->SR, cr1its = regs->CR1; + + if ((cr1its & USART_CR1_RXNEIE) && (srflags & USART_SR_RXNE)) { + if (srflags & USART_SR_FE || srflags & USART_SR_PE ) { + // framing error or parity error + regs->DR; // Read and throw away the data, which also clears FE and PE + } + else { + uint8_t c = (uint8)regs->DR; + #ifdef USART_SAFE_INSERT + // If the buffer is full and the user defines USART_SAFE_INSERT, + // ignore new bytes. + rb_safe_insert(rb, c); + #else + // By default, push bytes around in the ring buffer. + rb_push_insert(rb, c); + #endif + #if ENABLED(EMERGENCY_PARSER) + if (serial.emergency_parser_enabled()) + emergency_parser.update(serial.emergency_state, c); + #endif + } + } + else if (srflags & USART_SR_ORE) { + // overrun and empty data, just do a dummy read to clear ORE + // and prevent a raise condition where a continous interrupt stream (due to ORE set) occurs + // (see chapter "Overrun error" ) in STM32 reference manual + regs->DR; + } + + // TXE signifies readiness to send a byte to DR. + if ((cr1its & USART_CR1_TXEIE) && (srflags & USART_SR_TXE)) { + if (!rb_is_empty(wb)) + regs->DR=rb_remove(wb); + else + regs->CR1 &= ~((uint32)USART_CR1_TXEIE); // disable TXEIE + } +} + +// Not every MarlinSerial port should handle emergency parsing. +// It would not make sense to parse GCode from TMC responses, for example. +constexpr bool serial_handles_emergency(int port) { + return false + #ifdef SERIAL_PORT + || (SERIAL_PORT) == port + #endif + #ifdef SERIAL_PORT_2 + || (SERIAL_PORT_2) == port + #endif + #ifdef LCD_SERIAL_PORT + || (LCD_SERIAL_PORT) == port + #endif + ; +} + +#define DEFINE_HWSERIAL_MARLIN(name, n) \ + MarlinSerial name(USART##n, \ + BOARD_USART##n##_TX_PIN, \ + BOARD_USART##n##_RX_PIN, \ + serial_handles_emergency(n)); \ + extern "C" void __irq_usart##n(void) { \ + my_usart_irq(USART##n->rb, USART##n->wb, USART##n##_BASE, MSerial##n); \ + } + +#define DEFINE_HWSERIAL_UART_MARLIN(name, n) \ + MarlinSerial name(UART##n, \ + BOARD_USART##n##_TX_PIN, \ + BOARD_USART##n##_RX_PIN, \ + serial_handles_emergency(n)); \ + extern "C" void __irq_usart##n(void) { \ + my_usart_irq(UART##n->rb, UART##n->wb, UART##n##_BASE, MSerial##n); \ + } + +// Instantiate all UARTs even if they are not needed +// This avoids a bunch of logic to figure out every serial +// port which may be in use on the system. +DEFINE_HWSERIAL_MARLIN(MSerial1, 1); +DEFINE_HWSERIAL_MARLIN(MSerial2, 2); +DEFINE_HWSERIAL_MARLIN(MSerial3, 3); +#if EITHER(STM32_HIGH_DENSITY, STM32_XL_DENSITY) + DEFINE_HWSERIAL_UART_MARLIN(MSerial4, 4); + DEFINE_HWSERIAL_UART_MARLIN(MSerial5, 5); +#endif + +// Check the type of each serial port by passing it to a template function. +// HardwareSerial is known to sometimes hang the controller when an error occurs, +// so this case will fail the static assert. All other classes are assumed to be ok. +template +constexpr bool IsSerialClassAllowed(const T&) { return true; } +constexpr bool IsSerialClassAllowed(const HardwareSerial&) { return false; } + +#define CHECK_CFG_SERIAL(A) static_assert(IsSerialClassAllowed(A), STRINGIFY(A) " is defined incorrectly"); +#define CHECK_AXIS_SERIAL(A) static_assert(IsSerialClassAllowed(A##_HARDWARE_SERIAL), STRINGIFY(A) "_HARDWARE_SERIAL must be defined in the form MSerial1, rather than Serial1"); + +// If you encounter this error, replace SerialX with MSerialX, for example MSerial3. + +// Non-TMC ports were already validated in HAL.h, so do not require verbose error messages. +#ifdef MYSERIAL0 + CHECK_CFG_SERIAL(MYSERIAL0); +#endif +#ifdef MYSERIAL1 + CHECK_CFG_SERIAL(MYSERIAL1); +#endif +#ifdef LCD_SERIAL + CHECK_CFG_SERIAL(LCD_SERIAL); +#endif +#if AXIS_HAS_HW_SERIAL(X) + CHECK_AXIS_SERIAL(X); +#endif +#if AXIS_HAS_HW_SERIAL(X2) + CHECK_AXIS_SERIAL(X2); +#endif +#if AXIS_HAS_HW_SERIAL(Y) + CHECK_AXIS_SERIAL(Y); +#endif +#if AXIS_HAS_HW_SERIAL(Y2) + CHECK_AXIS_SERIAL(Y2); +#endif +#if AXIS_HAS_HW_SERIAL(Z) + CHECK_AXIS_SERIAL(Z); +#endif +#if AXIS_HAS_HW_SERIAL(Z2) + CHECK_AXIS_SERIAL(Z2); +#endif +#if AXIS_HAS_HW_SERIAL(Z3) + CHECK_AXIS_SERIAL(Z3); +#endif +#if AXIS_HAS_HW_SERIAL(Z4) + CHECK_AXIS_SERIAL(Z4); +#endif +#if AXIS_HAS_HW_SERIAL(E0) + CHECK_AXIS_SERIAL(E0); +#endif +#if AXIS_HAS_HW_SERIAL(E1) + CHECK_AXIS_SERIAL(E1); +#endif +#if AXIS_HAS_HW_SERIAL(E2) + CHECK_AXIS_SERIAL(E2); +#endif +#if AXIS_HAS_HW_SERIAL(E3) + CHECK_AXIS_SERIAL(E3); +#endif +#if AXIS_HAS_HW_SERIAL(E4) + CHECK_AXIS_SERIAL(E4); +#endif +#if AXIS_HAS_HW_SERIAL(E5) + CHECK_AXIS_SERIAL(E5); +#endif +#if AXIS_HAS_HW_SERIAL(E6) + CHECK_AXIS_SERIAL(E6); +#endif +#if AXIS_HAS_HW_SERIAL(E7) + CHECK_AXIS_SERIAL(E7); +#endif + +#endif // __STM32F1__ diff --git a/Marlin/src/HAL/STM32F1/MarlinSerial.h b/Marlin/src/HAL/STM32F1/MarlinSerial.h new file mode 100644 index 0000000000..6aa94b64ff --- /dev/null +++ b/Marlin/src/HAL/STM32F1/MarlinSerial.h @@ -0,0 +1,71 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#include +#include +#include + +#include "../../inc/MarlinConfigPre.h" +#if ENABLED(EMERGENCY_PARSER) + #include "../../feature/e_parser.h" +#endif + +// Increase priority of serial interrupts, to reduce overflow errors +#define UART_IRQ_PRIO 1 + +class MarlinSerial : public HardwareSerial { +public: + #if ENABLED(EMERGENCY_PARSER) + const bool ep_enabled; + EmergencyParser::State emergency_state; + inline bool emergency_parser_enabled() { return ep_enabled; } + #endif + + MarlinSerial(struct usart_dev *usart_device, uint8 tx_pin, uint8 rx_pin, bool TERN_(EMERGENCY_PARSER, ep_capable)) : + HardwareSerial(usart_device, tx_pin, rx_pin) + #if ENABLED(EMERGENCY_PARSER) + , ep_enabled(ep_capable) + , emergency_state(EmergencyParser::State::EP_RESET) + #endif + { } + + #ifdef UART_IRQ_PRIO + // Shadow the parent methods to set IRQ priority after begin() + void begin(uint32 baud) { + MarlinSerial::begin(baud, SERIAL_8N1); + } + + void begin(uint32 baud, uint8_t config) { + HardwareSerial::begin(baud, config); + nvic_irq_set_priority(c_dev()->irq_num, UART_IRQ_PRIO); + } + #endif +}; + +extern MarlinSerial MSerial1; +extern MarlinSerial MSerial2; +extern MarlinSerial MSerial3; +#if EITHER(STM32_HIGH_DENSITY, STM32_XL_DENSITY) + extern MarlinSerial MSerial4; + extern MarlinSerial MSerial5; +#endif diff --git a/Marlin/src/HAL/STM32F1/SPI.cpp b/Marlin/src/HAL/STM32F1/SPI.cpp index 423772dbc9..0452cf6293 100644 --- a/Marlin/src/HAL/STM32F1/SPI.cpp +++ b/Marlin/src/HAL/STM32F1/SPI.cpp @@ -40,6 +40,9 @@ #include #include +#include "../../inc/MarlinConfig.h" +#include "spi_pins.h" + /** Time in ms for DMA receive timeout */ #define DMA_TIMEOUT 100 @@ -710,6 +713,6 @@ static spi_baud_rate determine_baud_rate(spi_dev *dev, uint32_t freq) { return baud_rates[i]; } -SPIClass SPI(1); +SPIClass SPI(SPI_DEVICE); #endif // __STM32F1__ diff --git a/Marlin/src/HAL/STM32F1/SoftwareSerial.cpp b/Marlin/src/HAL/STM32F1/SoftwareSerial.cpp index 3641c9fdf0..993403cf72 100644 --- a/Marlin/src/HAL/STM32F1/SoftwareSerial.cpp +++ b/Marlin/src/HAL/STM32F1/SoftwareSerial.cpp @@ -57,4 +57,4 @@ void SoftwareSerial::stopListening() { listening = false; } -#endif //__STM32F1__ +#endif // __STM32F1__ diff --git a/Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_swspi.cpp b/Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_swspi.cpp index 894abb882a..f88fa88507 100644 --- a/Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_swspi.cpp +++ b/Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_swspi.cpp @@ -20,7 +20,7 @@ #include "../../../inc/MarlinConfig.h" -#if BOTH(HAS_GRAPHICAL_LCD, FORCE_SOFT_SPI) +#if BOTH(HAS_MARLINUI_U8GLIB, FORCE_SOFT_SPI) #include "../HAL.h" #include @@ -161,5 +161,5 @@ uint8_t u8g_com_HAL_STM32F1_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, return 1; } -#endif // HAS_GRAPHICAL_LCD +#endif // HAS_MARLINUI_U8GLIB #endif // STM32F1 diff --git a/Marlin/src/HAL/STM32F1/eeprom_spi_w25q.cpp b/Marlin/src/HAL/STM32F1/eeprom_spi_w25q.cpp index 4da921075a..aab4593bfe 100644 --- a/Marlin/src/HAL/STM32F1/eeprom_spi_w25q.cpp +++ b/Marlin/src/HAL/STM32F1/eeprom_spi_w25q.cpp @@ -9,7 +9,7 @@ U5 W25Q64BV, 16K SERIAL EEPROM: #if ENABLED(SPI_EEPROM_W25Q) #include "../../libs/W25Qxx.h" -W25QXXFlash W25QXX; +//W25QXXFlash W25QXX; uint8_t spi_eeprom[MARLIN_EEPROM_SIZE]; diff --git a/Marlin/src/HAL/STM32F1/eeprom_wired.cpp b/Marlin/src/HAL/STM32F1/eeprom_wired.cpp index f4bb2f6b7c..b4699d00dc 100644 --- a/Marlin/src/HAL/STM32F1/eeprom_wired.cpp +++ b/Marlin/src/HAL/STM32F1/eeprom_wired.cpp @@ -36,12 +36,7 @@ #endif size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } -bool PersistentStore::access_finish() { - #if ENABLED(EEPROM_W25Q) - eeprom_hw_deinit(); - #endif - return true; - } +bool PersistentStore::access_finish() { return true; } bool PersistentStore::access_start() { eeprom_init(); diff --git a/Marlin/src/HAL/STM32F1/inc/SanityCheck.h b/Marlin/src/HAL/STM32F1/inc/SanityCheck.h index c0cb486952..9d5026fbab 100644 --- a/Marlin/src/HAL/STM32F1/inc/SanityCheck.h +++ b/Marlin/src/HAL/STM32F1/inc/SanityCheck.h @@ -25,10 +25,6 @@ * Test STM32F1-specific configuration values for errors at compile-time. */ -#if ENABLED(EMERGENCY_PARSER) - #error "EMERGENCY_PARSER is not yet implemented for STM32F1. Disable EMERGENCY_PARSER to continue." -#endif - #if ENABLED(FAST_PWM_FAN) || SPINDLE_LASER_FREQUENCY #error "Features requiring Hardware PWM (FAST_PWM_FAN, SPINDLE_LASER_FREQUENCY) are not yet supported on STM32F1." #endif diff --git a/Marlin/src/HAL/STM32F1/msc_sd.cpp b/Marlin/src/HAL/STM32F1/msc_sd.cpp index ab5530174e..6a4652e467 100644 --- a/Marlin/src/HAL/STM32F1/msc_sd.cpp +++ b/Marlin/src/HAL/STM32F1/msc_sd.cpp @@ -21,7 +21,7 @@ #define PRODUCT_ID 0x29 USBMassStorage MarlinMSC; -USBCompositeSerial MarlinCompositeSerial; +MarlinUSBCompositeSerial MarlinCompositeSerial; #include "../../inc/MarlinConfig.h" @@ -38,6 +38,17 @@ USBCompositeSerial MarlinCompositeSerial; #endif +#if ENABLED(EMERGENCY_PARSER) + void (*real_rx_callback)(void); + + void my_rx_callback(void) { + real_rx_callback(); + int len = MarlinCompositeSerial.available(); + while (len-- > 0) // >0 because available() may return a negative value + emergency_parser.update(MarlinCompositeSerial.emergency_state, MarlinCompositeSerial.peek()); + } +#endif + void MSC_SD_init() { USBComposite.setProductId(PRODUCT_ID); // Just set MarlinCompositeSerial enabled to true @@ -59,6 +70,11 @@ void MSC_SD_init() { // Register composite Serial MarlinCompositeSerial.registerComponent(); USBComposite.begin(); + #if ENABLED(EMERGENCY_PARSER) + //rx is usbSerialPart.endpoints[2] + real_rx_callback = usbSerialPart.endpoints[2].callback; + usbSerialPart.endpoints[2].callback = my_rx_callback; + #endif } #endif // USE_USB_COMPOSITE diff --git a/Marlin/src/HAL/STM32F1/msc_sd.h b/Marlin/src/HAL/STM32F1/msc_sd.h index 8715888f47..1e4e4c44b1 100644 --- a/Marlin/src/HAL/STM32F1/msc_sd.h +++ b/Marlin/src/HAL/STM32F1/msc_sd.h @@ -17,7 +17,26 @@ #include +#include "../../inc/MarlinConfigPre.h" +#if ENABLED(EMERGENCY_PARSER) + #include "../../feature/e_parser.h" +#endif + +class MarlinUSBCompositeSerial : public USBCompositeSerial { +public: + MarlinUSBCompositeSerial() : USBCompositeSerial() + #if ENABLED(EMERGENCY_PARSER) + , emergency_state(EmergencyParser::State::EP_RESET) + #endif + { } + + #if ENABLED(EMERGENCY_PARSER) + EmergencyParser::State emergency_state; + inline bool emergency_parser_enabled() { return true; } + #endif +}; + extern USBMassStorage MarlinMSC; -extern USBCompositeSerial MarlinCompositeSerial; +extern MarlinUSBCompositeSerial MarlinCompositeSerial; void MSC_SD_init(); diff --git a/Marlin/src/HAL/STM32F1/onboard_sd.cpp b/Marlin/src/HAL/STM32F1/onboard_sd.cpp index df24b98502..dfb7291bb3 100644 --- a/Marlin/src/HAL/STM32F1/onboard_sd.cpp +++ b/Marlin/src/HAL/STM32F1/onboard_sd.cpp @@ -9,7 +9,6 @@ * No restriction on use. You can use, modify and redistribute it for * personal, non-profit or commercial products UNDER YOUR RESPONSIBILITY. * Redistributions of source code must retain the above copyright notice. - * */ #include "../../inc/MarlinConfig.h" @@ -23,23 +22,23 @@ #include "fastio.h" #if HAS_SHARED_MEDIA - #ifndef ON_BOARD_SPI_DEVICE - #define ON_BOARD_SPI_DEVICE SPI_DEVICE + #ifndef ONBOARD_SPI_DEVICE + #define ONBOARD_SPI_DEVICE SPI_DEVICE #endif #define ONBOARD_SD_SPI SPI #else - SPIClass OnBoardSPI(ON_BOARD_SPI_DEVICE); - #define ONBOARD_SD_SPI OnBoardSPI + SPIClass OnboardSPI(ONBOARD_SPI_DEVICE); + #define ONBOARD_SD_SPI OnboardSPI #endif -#if ON_BOARD_SPI_DEVICE == 1 +#if ONBOARD_SPI_DEVICE == 1 #define SPI_CLOCK_MAX SPI_BAUD_PCLK_DIV_4 #else #define SPI_CLOCK_MAX SPI_BAUD_PCLK_DIV_2 #endif -#define CS_LOW() WRITE(ONBOARD_SD_CS_PIN, LOW) /* Set OnBoardSPI cs low */ -#define CS_HIGH() WRITE(ONBOARD_SD_CS_PIN, HIGH) /* Set OnBoardSPI cs high */ +#define CS_LOW() WRITE(ONBOARD_SD_CS_PIN, LOW) /* Set OnboardSPI cs low */ +#define CS_HIGH() WRITE(ONBOARD_SD_CS_PIN, HIGH) /* Set OnboardSPI cs high */ #define FCLK_FAST() ONBOARD_SD_SPI.setClockDivider(SPI_CLOCK_MAX) #define FCLK_SLOW() ONBOARD_SD_SPI.setClockDivider(SPI_BAUD_PCLK_DIV_256) @@ -154,7 +153,7 @@ static int select() { /* 1:OK, 0:Timeout */ /*-----------------------------------------------------------------------*/ static void power_on() { /* Enable SSP module and attach it to I/O pads */ - ONBOARD_SD_SPI.setModule(ON_BOARD_SPI_DEVICE); + ONBOARD_SD_SPI.setModule(ONBOARD_SPI_DEVICE); ONBOARD_SD_SPI.begin(); ONBOARD_SD_SPI.setBitOrder(MSBFIRST); ONBOARD_SD_SPI.setDataMode(SPI_MODE0); diff --git a/Marlin/src/HAL/STM32F1/sdio.cpp b/Marlin/src/HAL/STM32F1/sdio.cpp index 0e8a745810..ffa6db1206 100644 --- a/Marlin/src/HAL/STM32F1/sdio.cpp +++ b/Marlin/src/HAL/STM32F1/sdio.cpp @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfig.h" // Allow pins/pins.h to set density -#if defined(STM32_HIGH_DENSITY) || defined(STM32_XL_DENSITY) +#if EITHER(STM32_HIGH_DENSITY, STM32_XL_DENSITY) #include "sdio.h" @@ -108,7 +108,7 @@ bool SDIO_ReadBlock_DMA(uint32_t blockAddress, uint8_t *data) { SDIO_CLEAR_FLAG(SDIO_ICR_CMD_FLAGS | SDIO_ICR_DATA_FLAGS); dma_disable(SDIO_DMA_DEV, SDIO_DMA_CHANNEL); return false; - } + } //Wait for DMA transaction to complete while ((DMA2_BASE->ISR & (DMA_ISR_TEIF4|DMA_ISR_TCIF4)) == 0 ) { /* wait */ } diff --git a/Marlin/src/HAL/STM32F1/tft/tft_fsmc.cpp b/Marlin/src/HAL/STM32F1/tft/tft_fsmc.cpp index 62cadb85af..008301d9bc 100644 --- a/Marlin/src/HAL/STM32F1/tft/tft_fsmc.cpp +++ b/Marlin/src/HAL/STM32F1/tft/tft_fsmc.cpp @@ -89,6 +89,16 @@ void TFT_FSMC::Init() { uint8_t cs = FSMC_CS_PIN, rs = FSMC_RS_PIN; uint32_t controllerAddress; + #if PIN_EXISTS(TFT_BACKLIGHT) + OUT_WRITE(TFT_BACKLIGHT_PIN, DISABLED(DELAYED_BACKLIGHT_INIT)); + #endif + + #if ENABLED(LCD_USE_DMA_FSMC) + dma_init(FSMC_DMA_DEV); + dma_disable(FSMC_DMA_DEV, FSMC_DMA_CHANNEL); + dma_set_priority(FSMC_DMA_DEV, FSMC_DMA_CHANNEL, DMA_PRIORITY_MEDIUM); + #endif + #if PIN_EXISTS(TFT_RESET) OUT_WRITE(TFT_RESET_PIN, HIGH); delay(100); @@ -149,7 +159,6 @@ void TFT_FSMC::Init() { default: return; } - rcc_clk_enable(RCC_DMA2); rcc_clk_enable(RCC_FSMC); gpio_set_mode(GPIOD, 14, GPIO_AF_OUTPUT_PP); // FSMC_D00 @@ -202,6 +211,8 @@ uint32_t TFT_FSMC::GetID() { id = ReadID(LCD_READ_ID); if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF) id = ReadID(LCD_READ_ID4); + if ((id & 0xFF00) == 0 && (id & 0xFF) != 0) + id = ReadID(LCD_READ_ID4); return id; } diff --git a/Marlin/src/HAL/STM32_F4_F7/HAL.h b/Marlin/src/HAL/STM32_F4_F7/HAL.h index 5601400c5a..88e48f0fa0 100644 --- a/Marlin/src/HAL/STM32_F4_F7/HAL.h +++ b/Marlin/src/HAL/STM32_F4_F7/HAL.h @@ -46,24 +46,16 @@ // Serial override //extern HalSerial usb_serial; +#define _MSERIAL(X) SerialUART##X +#define MSERIAL(X) _MSERIAL(X) +#define SerialUART0 Serial1 + #if defined(STM32F4) && SERIAL_PORT == 0 #error "SERIAL_PORT cannot be 0. (Port 0 does not exist.) Please update your configuration." #elif SERIAL_PORT == -1 #define MYSERIAL0 SerialUSB -#elif SERIAL_PORT == 0 - #define MYSERIAL0 Serial1 -#elif SERIAL_PORT == 1 - #define MYSERIAL0 SerialUART1 -#elif SERIAL_PORT == 2 - #define MYSERIAL0 SerialUART2 -#elif SERIAL_PORT == 3 - #define MYSERIAL0 SerialUART3 -#elif SERIAL_PORT == 4 - #define MYSERIAL0 SerialUART4 -#elif SERIAL_PORT == 5 - #define MYSERIAL0 SerialUART5 -#elif SERIAL_PORT == 6 - #define MYSERIAL0 SerialUART6 +#elif WITHIN(SERIAL_PORT, 0, 6) + #define MYSERIAL0 MSERIAL(SERIAL_PORT) #else #error "SERIAL_PORT must be from -1 to 6. Please update your configuration." #endif @@ -71,57 +63,24 @@ #ifdef SERIAL_PORT_2 #if defined(STM32F4) && SERIAL_PORT_2 == 0 #error "SERIAL_PORT_2 cannot be 0. (Port 0 does not exist.) Please update your configuration." - #elif SERIAL_PORT_2 == SERIAL_PORT - #error "SERIAL_PORT_2 must be different than SERIAL_PORT. Please update your configuration." #elif SERIAL_PORT_2 == -1 #define MYSERIAL1 SerialUSB - #elif SERIAL_PORT_2 == 0 - #define MYSERIAL1 Serial1 - #elif SERIAL_PORT_2 == 1 - #define MYSERIAL1 SerialUART1 - #elif SERIAL_PORT_2 == 2 - #define MYSERIAL1 SerialUART2 - #elif SERIAL_PORT_2 == 3 - #define MYSERIAL1 SerialUART3 - #elif SERIAL_PORT_2 == 4 - #define MYSERIAL1 SerialUART4 - #elif SERIAL_PORT_2 == 5 - #define MYSERIAL1 SerialUART5 - #elif SERIAL_PORT_2 == 6 - #define MYSERIAL1 SerialUART6 + #elif WITHIN(SERIAL_PORT_2, 0, 6) + #define MYSERIAL1 MSERIAL(SERIAL_PORT_2) #else #error "SERIAL_PORT_2 must be from -1 to 6. Please update your configuration." #endif - #define NUM_SERIAL 2 -#else - #define NUM_SERIAL 1 #endif -#ifdef DGUS_SERIAL_PORT - #if defined(STM32F4) && DGUS_SERIAL_PORT == 0 - #error "DGUS_SERIAL_PORT cannot be 0. (Port 0 does not exist.) Please update your configuration." - #elif DGUS_SERIAL_PORT == SERIAL_PORT - #error "DGUS_SERIAL_PORT must be different than SERIAL_PORT. Please update your configuration." - #elif defined(SERIAL_PORT_2) && DGUS_SERIAL_PORT == SERIAL_PORT_2 - #error "DGUS_SERIAL_PORT must be different than SERIAL_PORT_2. Please update your configuration." - #elif DGUS_SERIAL_PORT == -1 - #define DGUS_SERIAL SerialUSB - #elif DGUS_SERIAL_PORT == 0 - #define DGUS_SERIAL Serial1 - #elif DGUS_SERIAL_PORT == 1 - #define DGUS_SERIAL SerialUART1 - #elif DGUS_SERIAL_PORT == 2 - #define DGUS_SERIAL SerialUART2 - #elif DGUS_SERIAL_PORT == 3 - #define DGUS_SERIAL SerialUART3 - #elif DGUS_SERIAL_PORT == 4 - #define DGUS_SERIAL SerialUART4 - #elif DGUS_SERIAL_PORT == 5 - #define DGUS_SERIAL SerialUART5 - #elif DGUS_SERIAL_PORT == 6 - #define DGUS_SERIAL SerialUART6 +#ifdef LCD_SERIAL_PORT + #if defined(STM32F4) && LCD_SERIAL_PORT == 0 + #error "LCD_SERIAL_PORT cannot be 0. (Port 0 does not exist.) Please update your configuration." + #elif LCD_SERIAL_PORT == -1 + #define LCD_SERIAL SerialUSB + #elif WITHIN(LCD_SERIAL_PORT, 0, 6) + #define LCD_SERIAL MSERIAL(LCD_SERIAL_PORT) #else - #error "DGUS_SERIAL_PORT must be from -1 to 6. Please update your configuration." + #error "LCD_SERIAL_PORT must be from -1 to 6. Please update your configuration." #endif #endif diff --git a/Marlin/src/HAL/STM32_F4_F7/HAL_SPI.cpp b/Marlin/src/HAL/STM32_F4_F7/HAL_SPI.cpp index 6fe81819ab..ebd0b4cee7 100644 --- a/Marlin/src/HAL/STM32_F4_F7/HAL_SPI.cpp +++ b/Marlin/src/HAL/STM32_F4_F7/HAL_SPI.cpp @@ -72,7 +72,7 @@ static SPISettings spiConfig; */ void spiBegin() { #if !defined(SS_PIN) || SS_PIN < 0 - #error SS_PIN not defined! + #error "SS_PIN not defined!" #endif OUT_WRITE(SS_PIN, HIGH); diff --git a/Marlin/src/HAL/STM32_F4_F7/STM32F7/TMC2660.cpp b/Marlin/src/HAL/STM32_F4_F7/STM32F7/TMC2660.cpp index 4d116f440b..df3d40f159 100644 --- a/Marlin/src/HAL/STM32_F4_F7/STM32F7/TMC2660.cpp +++ b/Marlin/src/HAL/STM32_F4_F7/STM32F7/TMC2660.cpp @@ -22,7 +22,6 @@ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN * THE SOFTWARE. - * */ #if defined(STM32GENERIC) && defined(STM32F7) @@ -662,7 +661,6 @@ boolean TMC26XStepper::isEnabled() { return !!(chopper_config_register & T_OFF_P /** * reads a value from the TMC26X status register. The value is not obtained directly but can then * be read by the various status routines. - * */ void TMC26XStepper::readStatus(char read_value) { uint32_t old_driver_configuration_register_value = driver_configuration_register_value; diff --git a/Marlin/src/HAL/STM32_F4_F7/STM32F7/TMC2660.h b/Marlin/src/HAL/STM32_F4_F7/STM32F7/TMC2660.h index f1d0133a3b..208c3bc7e0 100644 --- a/Marlin/src/HAL/STM32_F4_F7/STM32F7/TMC2660.h +++ b/Marlin/src/HAL/STM32_F4_F7/STM32F7/TMC2660.h @@ -22,7 +22,6 @@ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN * THE SOFTWARE. - * */ #pragma once diff --git a/Marlin/src/HAL/TEENSY31_32/HAL.h b/Marlin/src/HAL/TEENSY31_32/HAL.h index 890930f7f8..31ceb8b87c 100644 --- a/Marlin/src/HAL/TEENSY31_32/HAL.h +++ b/Marlin/src/HAL/TEENSY31_32/HAL.h @@ -44,21 +44,19 @@ //#undef MOTHERBOARD //#define MOTHERBOARD BOARD_TEENSY31_32 -#define IS_32BIT_TEENSY defined(__MK20DX256__) -#define IS_TEENSY32 defined(__MK20DX256__) +#ifdef __MK20DX256__ + #define IS_32BIT_TEENSY 1 + #define IS_TEENSY32 1 +#endif -#define NUM_SERIAL 1 +#define _MSERIAL(X) Serial##X +#define MSERIAL(X) _MSERIAL(X) +#define Serial0 Serial #if SERIAL_PORT == -1 #define MYSERIAL0 SerialUSB -#elif SERIAL_PORT == 0 - #define MYSERIAL0 Serial -#elif SERIAL_PORT == 1 - #define MYSERIAL0 Serial1 -#elif SERIAL_PORT == 2 - #define MYSERIAL0 Serial2 -#elif SERIAL_PORT == 3 - #define MYSERIAL0 Serial3 +#elif WITHIN(SERIAL_PORT, 0, 3) + #define MYSERIAL0 MSERIAL(SERIAL_PORT) #endif #define HAL_SERVO_LIB libServo diff --git a/Marlin/src/HAL/TEENSY35_36/HAL.h b/Marlin/src/HAL/TEENSY35_36/HAL.h index 5442ae2d3b..11f0fb941e 100644 --- a/Marlin/src/HAL/TEENSY35_36/HAL.h +++ b/Marlin/src/HAL/TEENSY35_36/HAL.h @@ -45,22 +45,23 @@ // Defines // ------------------------ -#define IS_32BIT_TEENSY (defined(__MK64FX512__) || defined(__MK66FX1M0__)) -#define IS_TEENSY35 defined(__MK64FX512__) -#define IS_TEENSY36 defined(__MK66FX1M0__) +#ifdef __MK64FX512__ + #define IS_32BIT_TEENSY 1 + #define IS_TEENSY35 1 +#endif +#ifdef __MK66FX1M0__ + #define IS_32BIT_TEENSY 1 + #define IS_TEENSY36 1 +#endif -#define NUM_SERIAL 1 +#define _MSERIAL(X) Serial##X +#define MSERIAL(X) _MSERIAL(X) +#define Serial0 Serial #if SERIAL_PORT == -1 #define MYSERIAL0 SerialUSB -#elif SERIAL_PORT == 0 - #define MYSERIAL0 Serial -#elif SERIAL_PORT == 1 - #define MYSERIAL0 Serial1 -#elif SERIAL_PORT == 2 - #define MYSERIAL0 Serial2 -#elif SERIAL_PORT == 3 - #define MYSERIAL0 Serial3 +#elif WITHIN(SERIAL_PORT, 0, 3) + #define MYSERIAL0 MSERIAL(SERIAL_PORT) #endif #define HAL_SERVO_LIB libServo diff --git a/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp b/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp index 0b1ae4afa4..812aa90c83 100644 --- a/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp +++ b/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp @@ -31,7 +31,7 @@ static SPISettings spiConfig; void spiBegin() { #if !PIN_EXISTS(SS) - #error SS_PIN not defined! + #error "SS_PIN not defined!" #endif OUT_WRITE(SS_PIN, HIGH); SET_OUTPUT(SCK_PIN); diff --git a/Marlin/src/HAL/TEENSY35_36/timers.h b/Marlin/src/HAL/TEENSY35_36/timers.h index 68060d0e1c..ad6629f40d 100644 --- a/Marlin/src/HAL/TEENSY35_36/timers.h +++ b/Marlin/src/HAL/TEENSY35_36/timers.h @@ -16,6 +16,7 @@ * * You should have received a copy of the GNU General Public License * along with this program. If not, see . + * */ #pragma once diff --git a/Marlin/src/HAL/TEENSY40_41/HAL.cpp b/Marlin/src/HAL/TEENSY40_41/HAL.cpp new file mode 100644 index 0000000000..f5d37f5fc4 --- /dev/null +++ b/Marlin/src/HAL/TEENSY40_41/HAL.cpp @@ -0,0 +1,167 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * Description: HAL for Teensy40 (IMXRT1062) + */ + +#ifdef __IMXRT1062__ + +#include "HAL.h" +#include "../shared/Delay.h" +#include "timers.h" + +#include + +uint16_t HAL_adc_result, HAL_adc_select; + +static const uint8_t pin2sc1a[] = { + 0x07, // 0/A0 AD_B1_02 + 0x08, // 1/A1 AD_B1_03 + 0x0C, // 2/A2 AD_B1_07 + 0x0B, // 3/A3 AD_B1_06 + 0x06, // 4/A4 AD_B1_01 + 0x05, // 5/A5 AD_B1_00 + 0x0F, // 6/A6 AD_B1_10 + 0x00, // 7/A7 AD_B1_11 + 0x0D, // 8/A8 AD_B1_08 + 0x0E, // 9/A9 AD_B1_09 + 0x01, // 24/A10 AD_B0_12 + 0x02, // 25/A11 AD_B0_13 + 0x83, // 26/A12 AD_B1_14 - only on ADC2, 3 + 0x84, // 27/A13 AD_B1_15 - only on ADC2, 4 + 0x07, // 14/A0 AD_B1_02 + 0x08, // 15/A1 AD_B1_03 + 0x0C, // 16/A2 AD_B1_07 + 0x0B, // 17/A3 AD_B1_06 + 0x06, // 18/A4 AD_B1_01 + 0x05, // 19/A5 AD_B1_00 + 0x0F, // 20/A6 AD_B1_10 + 0x00, // 21/A7 AD_B1_11 + 0x0D, // 22/A8 AD_B1_08 + 0x0E, // 23/A9 AD_B1_09 + 0x01, // 24/A10 AD_B0_12 + 0x02, // 25/A11 AD_B0_13 + 0x83, // 26/A12 AD_B1_14 - only on ADC2, 3 + 0x84, // 27/A13 AD_B1_15 - only on ADC2, 4 + #ifdef ARDUINO_TEENSY41 + 0xFF, // 28 + 0xFF, // 29 + 0xFF, // 30 + 0xFF, // 31 + 0xFF, // 32 + 0xFF, // 33 + 0xFF, // 34 + 0xFF, // 35 + 0xFF, // 36 + 0xFF, // 37 + 0x81, // 38/A14 AD_B1_12 - only on ADC2, 1 + 0x82, // 39/A15 AD_B1_13 - only on ADC2, 2 + 0x09, // 40/A16 AD_B1_04 + 0x0A, // 41/A17 AD_B1_05 + #endif +}; + +/* +// disable interrupts +void cli() { noInterrupts(); } + +// enable interrupts +void sei() { interrupts(); } +*/ + +void HAL_adc_init() { + analog_init(); + while (ADC1_GC & ADC_GC_CAL) ; + while (ADC2_GC & ADC_GC_CAL) ; +} + +void HAL_clear_reset_source() { + uint32_t reset_source = SRC_SRSR; + SRC_SRSR = reset_source; + } + +uint8_t HAL_get_reset_source() { + switch (SRC_SRSR & 0xFF) { + case 1: return RST_POWER_ON; break; + case 2: return RST_SOFTWARE; break; + case 4: return RST_EXTERNAL; break; + // case 8: return RST_BROWN_OUT; break; + case 16: return RST_WATCHDOG; break; + case 64: return RST_JTAG; break; + // case 128: return RST_OVERTEMP; break; + } + return 0; +} + +#define __bss_end _ebss + +extern "C" { + extern char __bss_end; + extern char __heap_start; + extern void* __brkval; + + // Doesn't work on Teensy 4.x + uint32_t freeMemory() { + uint32_t free_memory; + if ((uint32_t)__brkval == 0) + free_memory = ((uint32_t)&free_memory) - ((uint32_t)&__bss_end); + else + free_memory = ((uint32_t)&free_memory) - ((uint32_t)__brkval); + return free_memory; + } +} + +void HAL_adc_start_conversion(const uint8_t adc_pin) { + const uint16_t pin = pin2sc1a[adc_pin]; + if (pin == 0xFF) { + HAL_adc_select = -1; // Digital only + } + else if (pin & 0x80) { + HAL_adc_select = 1; + ADC2_HC0 = pin & 0x7F; + } + else { + HAL_adc_select = 0; + ADC1_HC0 = pin; + } +} + +uint16_t HAL_adc_get_result() { + switch (HAL_adc_select) { + case 0: + while (!(ADC1_HS & ADC_HS_COCO0)) ; // wait + return ADC1_R0; + case 1: + while (!(ADC2_HS & ADC_HS_COCO0)) ; // wait + return ADC2_R0; + } + return 0; +} + +bool is_output(uint8_t pin) { + const struct digital_pin_bitband_and_config_table_struct *p; + p = digital_pin_to_info_PGM + pin; + return (*(p->reg + 1) & p->mask); +} + +#endif // __IMXRT1062__ diff --git a/Marlin/src/HAL/TEENSY40_41/HAL.h b/Marlin/src/HAL/TEENSY40_41/HAL.h new file mode 100644 index 0000000000..b3b0144d13 --- /dev/null +++ b/Marlin/src/HAL/TEENSY40_41/HAL.h @@ -0,0 +1,147 @@ +/** + * Marlin 3D Printer Firmware + * + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com + * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * 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 + +/** + * Description: HAL for Teensy 4.0 and Teensy 4.1 + */ + +#define CPU_32_BIT + +#include "../shared/Marduino.h" +#include "../shared/math_32bit.h" +#include "../shared/HAL_SPI.h" + +#include "fastio.h" +#include "watchdog.h" + +#include +#include + +//#define ST7920_DELAY_1 DELAY_NS(600) +//#define ST7920_DELAY_2 DELAY_NS(750) +//#define ST7920_DELAY_3 DELAY_NS(750) + +// ------------------------ +// Defines +// ------------------------ + +#ifdef __IMXRT1062__ + #define IS_32BIT_TEENSY 1 + #define IS_TEENSY41 1 +#endif + +#define _MSERIAL(X) Serial##X +#define MSERIAL(X) _MSERIAL(X) +#define Serial0 Serial + +#if SERIAL_PORT == -1 + #define MYSERIAL0 SerialUSB +#elif WITHIN(SERIAL_PORT, 0, 8) + #define MYSERIAL0 MSERIAL(SERIAL_PORT) +#else + #error "The required SERIAL_PORT must be from -1 to 8. Please update your configuration." +#endif + +#ifdef SERIAL_PORT_2 + #if SERIAL_PORT_2 == -1 + #define MYSERIAL1 usbSerial + #elif WITHIN(SERIAL_PORT_2, 0, 8) + #define MYSERIAL1 MSERIAL(SERIAL_PORT_2) + #else + #error "SERIAL_PORT_2 must be from -1 to 8. Please update your configuration." + #endif +#endif + +#define HAL_SERVO_LIB libServo + +typedef int8_t pin_t; + +#ifndef analogInputToDigitalPin + #define analogInputToDigitalPin(p) ((p < 12u) ? (p) + 54u : -1) +#endif + +#define CRITICAL_SECTION_START() uint32_t primask = __get_primask(); __disable_irq() +#define CRITICAL_SECTION_END() if (!primask) __enable_irq() +#define ISRS_ENABLED() (!__get_primask()) +#define ENABLE_ISRS() __enable_irq() +#define DISABLE_ISRS() __disable_irq() + +#undef sq +#define sq(x) ((x)*(x)) + +#ifndef strncpy_P + #define strncpy_P(dest, src, num) strncpy((dest), (src), (num)) +#endif + +// Don't place string constants in PROGMEM +#undef PSTR +#define PSTR(str) ({static const char *data = (str); &data[0];}) + +// Fix bug in pgm_read_ptr +#undef pgm_read_ptr +#define pgm_read_ptr(addr) (*((void**)(addr))) +// Add type-checking to pgm_read_word +#undef pgm_read_word +#define pgm_read_word(addr) (*((uint16_t*)(addr))) + +// Enable hooks into idle and setup for HAL +#define HAL_IDLETASK 1 +FORCE_INLINE void HAL_idletask() {} +FORCE_INLINE void HAL_init() {} + +// Clear reset reason +void HAL_clear_reset_source(); + +// Reset reason +uint8_t HAL_get_reset_source(); + +FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); } + +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wunused-function" +extern "C" { + uint32_t freeMemory(); +} +#pragma GCC diagnostic pop + +// ADC + +void HAL_adc_init(); + +#define HAL_ADC_VREF 3.3 +#define HAL_ADC_RESOLUTION 10 +#define HAL_ADC_FILTERED // turn off ADC oversampling +#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) +#define HAL_READ_ADC() HAL_adc_get_result() +#define HAL_ADC_READY() true + +#define HAL_ANALOG_SELECT(pin) + +void HAL_adc_start_conversion(const uint8_t adc_pin); +uint16_t HAL_adc_get_result(); + +#define GET_PIN_MAP_PIN(index) index +#define GET_PIN_MAP_INDEX(pin) pin +#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) + +bool is_output(uint8_t pin); diff --git a/Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp b/Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp new file mode 100644 index 0000000000..9ccbb3a1f4 --- /dev/null +++ b/Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp @@ -0,0 +1,138 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#ifdef __IMXRT1062__ + +#include "HAL.h" +#include +#include +#include "spi_pins.h" +#include "../../core/macros.h" + +static SPISettings spiConfig; + +// ------------------------ +// Public functions +// ------------------------ + +#if ENABLED(SOFTWARE_SPI) + // ------------------------ + // Software SPI + // ------------------------ + #error "Software SPI not supported for Teensy 4. Use Hardware SPI." +#else + +// ------------------------ +// Hardware SPI +// ------------------------ + +void spiBegin() { + #ifndef SS_PIN + #error "SS_PIN is not defined!" + #endif + + OUT_WRITE(SS_PIN, HIGH); + + //SET_OUTPUT(SCK_PIN); + //SET_INPUT(MISO_PIN); + //SET_OUTPUT(MOSI_PIN); + + #if 0 && DISABLED(SOFTWARE_SPI) + // set SS high - may be chip select for another SPI device + #if SET_SPI_SS_HIGH + WRITE(SS_PIN, HIGH); + #endif + // set a default rate + spiInit(SPI_HALF_SPEED); // 1 + #endif +} + +void spiInit(uint8_t spiRate) { + // Use Marlin data-rates + uint32_t clock; + switch (spiRate) { + case SPI_FULL_SPEED: clock = 10000000; break; + case SPI_HALF_SPEED: clock = 5000000; break; + case SPI_QUARTER_SPEED: clock = 2500000; break; + case SPI_EIGHTH_SPEED: clock = 1250000; break; + case SPI_SPEED_5: clock = 625000; break; + case SPI_SPEED_6: clock = 312500; break; + default: + clock = 4000000; // Default from the SPI libarary + } + spiConfig = SPISettings(clock, MSBFIRST, SPI_MODE0); + SPI.begin(); +} + +uint8_t spiRec() { + SPI.beginTransaction(spiConfig); + uint8_t returnByte = SPI.transfer(0xFF); + SPI.endTransaction(); + return returnByte; + //SPDR = 0xFF; + //while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ } + //return SPDR; +} + +void spiRead(uint8_t* buf, uint16_t nbyte) { + SPI.beginTransaction(spiConfig); + SPI.transfer(buf, nbyte); + SPI.endTransaction(); + //if (nbyte-- == 0) return; + // SPDR = 0xFF; + //for (uint16_t i = 0; i < nbyte; i++) { + // while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ } + // buf[i] = SPDR; + // SPDR = 0xFF; + //} + //while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ } + //buf[nbyte] = SPDR; +} + +void spiSend(uint8_t b) { + SPI.beginTransaction(spiConfig); + SPI.transfer(b); + SPI.endTransaction(); + //SPDR = b; + //while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ } +} + +void spiSendBlock(uint8_t token, const uint8_t* buf) { + SPI.beginTransaction(spiConfig); + SPDR = token; + for (uint16_t i = 0; i < 512; i += 2) { + while (!TEST(SPSR, SPIF)) { /* nada */ }; + SPDR = buf[i]; + while (!TEST(SPSR, SPIF)) { /* nada */ }; + SPDR = buf[i + 1]; + } + while (!TEST(SPSR, SPIF)) { /* nada */ }; + SPI.endTransaction(); +} + +// Begin SPI transaction, set clock, bit order, data mode +void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode) { + spiConfig = SPISettings(spiClock, bitOrder, dataMode); + SPI.beginTransaction(spiConfig); +} + +#endif // SOFTWARE_SPI +#endif // __IMXRT1062__ diff --git a/Marlin/src/HAL/TEENSY40_41/Servo.cpp b/Marlin/src/HAL/TEENSY40_41/Servo.cpp new file mode 100644 index 0000000000..e3d0d03449 --- /dev/null +++ b/Marlin/src/HAL/TEENSY40_41/Servo.cpp @@ -0,0 +1,57 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#ifdef __IMXRT1062__ + +#include "../../inc/MarlinConfig.h" + +#if HAS_SERVOS + +#include "Servo.h" + +int8_t libServo::attach(const int inPin) { + if (inPin > 0) servoPin = inPin; + return super::attach(servoPin); +} + +int8_t libServo::attach(const int inPin, const int inMin, const int inMax) { + if (inPin > 0) servoPin = inPin; + return super::attach(servoPin, inMin, inMax); +} + +void libServo::move(const int value) { + constexpr uint16_t servo_delay[] = SERVO_DELAY; + static_assert(COUNT(servo_delay) == NUM_SERVOS, "SERVO_DELAY must be an array NUM_SERVOS long."); + if (attach(0) >= 0) { + write(value); + safe_delay(servo_delay[servoIndex]); + TERN_(DEACTIVATE_SERVOS_AFTER_MOVE, detach()); + } +} + +void libServo::detach() { + // PWMServo library does not have detach() function + //super::detach(); +} + +#endif // HAS_SERVOS + +#endif // __IMXRT1062__ diff --git a/Marlin/src/HAL/TEENSY40_41/Servo.h b/Marlin/src/HAL/TEENSY40_41/Servo.h new file mode 100644 index 0000000000..ce910ed8a8 --- /dev/null +++ b/Marlin/src/HAL/TEENSY40_41/Servo.h @@ -0,0 +1,39 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#include + +// Inherit and expand on core Servo library +class libServo : public PWMServo { + public: + int8_t attach(const int pin); + int8_t attach(const int pin, const int min, const int max); + void move(const int value); + void detach(void); + private: + typedef PWMServo super; + uint8_t servoPin; + uint16_t min_ticks; + uint16_t max_ticks; + uint8_t servoIndex; // Index into the channel data for this servo +}; diff --git a/Marlin/src/HAL/TEENSY40_41/eeprom.cpp b/Marlin/src/HAL/TEENSY40_41/eeprom.cpp new file mode 100644 index 0000000000..5491e04fbc --- /dev/null +++ b/Marlin/src/HAL/TEENSY40_41/eeprom.cpp @@ -0,0 +1,77 @@ +/** + * Marlin 3D Printer Firmware + * + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com + * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * Copyright (c) 2016 Victor Perez victor_pv@hotmail.com + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#ifdef __IMXRT1062__ + +#include "../../inc/MarlinConfig.h" + +#if USE_WIRED_EEPROM + +/** + * PersistentStore for Arduino-style EEPROM interface + * with implementations supplied by the framework. + */ + +#include "../shared/eeprom_api.h" +#include + +#ifndef MARLIN_EEPROM_SIZE + #define MARLIN_EEPROM_SIZE size_t(E2END + 1) +#endif +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } + +bool PersistentStore::access_start() { return true; } +bool PersistentStore::access_finish() { return true; } + +bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { + while (size--) { + uint8_t * const p = (uint8_t * const)pos; + uint8_t v = *value; + // EEPROM has only ~100,000 write cycles, + // so only write bytes that have changed! + if (v != eeprom_read_byte(p)) { + eeprom_write_byte(p, v); + if (eeprom_read_byte(p) != v) { + SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE); + return true; + } + } + crc16(crc, &v, 1); + pos++; + value++; + } + return false; +} + +bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) { + do { + uint8_t c = eeprom_read_byte((uint8_t*)pos); + if (writing) *value = c; + crc16(crc, &c, 1); + pos++; + value++; + } while (--size); + return false; +} + +#endif // USE_WIRED_EEPROM +#endif // __IMXRT1062__ diff --git a/Marlin/src/HAL/TEENSY40_41/endstop_interrupts.h b/Marlin/src/HAL/TEENSY40_41/endstop_interrupts.h new file mode 100644 index 0000000000..92e22efc0f --- /dev/null +++ b/Marlin/src/HAL/TEENSY40_41/endstop_interrupts.h @@ -0,0 +1,66 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * Endstop Interrupts + * + * Without endstop interrupts the endstop pins must be polled continually in + * the temperature-ISR via endstops.update(), most of the time finding no change. + * With this feature endstops.update() is called only when we know that at + * least one endstop has changed state, saving valuable CPU cycles. + * + * This feature only works when all used endstop pins can generate an 'external interrupt'. + * + * Test whether pins issue interrupts on your board by flashing 'pin_interrupt_test.ino'. + * (Located in Marlin/buildroot/share/pin_interrupt_test/pin_interrupt_test.ino) + */ + +#include "../../module/endstops.h" + +// One ISR for all EXT-Interrupts +void endstop_ISR() { endstops.update(); } + +/** + * Endstop interrupts for Due based targets. + * On Due, all pins support external interrupt capability. + */ +void setup_endstop_interrupts() { + #define _ATTACH(P) attachInterrupt(digitalPinToInterrupt(P), endstop_ISR, CHANGE) + TERN_(HAS_X_MAX, _ATTACH(X_MAX_PIN)); + TERN_(HAS_X_MIN, _ATTACH(X_MIN_PIN)); + TERN_(HAS_Y_MAX, _ATTACH(Y_MAX_PIN)); + TERN_(HAS_Y_MIN, _ATTACH(Y_MIN_PIN)); + TERN_(HAS_Z_MAX, _ATTACH(Z_MAX_PIN)); + TERN_(HAS_Z_MIN, _ATTACH(Z_MIN_PIN)); + TERN_(HAS_X2_MAX, _ATTACH(X2_MAX_PIN)); + TERN_(HAS_X2_MIN, _ATTACH(X2_MIN_PIN)); + TERN_(HAS_Y2_MAX, _ATTACH(Y2_MAX_PIN)); + TERN_(HAS_Y2_MIN, _ATTACH(Y2_MIN_PIN)); + TERN_(HAS_Z2_MAX, _ATTACH(Z2_MAX_PIN)); + TERN_(HAS_Z2_MIN, _ATTACH(Z2_MIN_PIN)); + TERN_(HAS_Z3_MAX, _ATTACH(Z3_MAX_PIN)); + TERN_(HAS_Z3_MIN, _ATTACH(Z3_MIN_PIN)); + TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN)); + TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN)); + TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN)); +} diff --git a/Marlin/src/HAL/TEENSY40_41/fastio.h b/Marlin/src/HAL/TEENSY40_41/fastio.h new file mode 100644 index 0000000000..19b8114509 --- /dev/null +++ b/Marlin/src/HAL/TEENSY40_41/fastio.h @@ -0,0 +1,58 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * Copyright (c) 2017 Victor Perez + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * Fast I/O interfaces for Teensy 4 + * These use GPIO functions instead of Direct Port Manipulation, as on AVR. + */ + +#ifndef PWM + #define PWM OUTPUT +#endif + +#define READ(IO) digitalRead(IO) +#define WRITE(IO,V) digitalWrite(IO,V) + +#define _GET_MODE(IO) !is_output(IO) +#define _SET_MODE(IO,M) pinMode(IO, M) +#define _SET_OUTPUT(IO) pinMode(IO, OUTPUT) /*!< Output Push Pull Mode & GPIO_NOPULL */ + +#define OUT_WRITE(IO,V) do{ _SET_OUTPUT(IO); WRITE(IO,V); }while(0) + +#define SET_INPUT(IO) _SET_MODE(IO, INPUT) /*!< Input Floating Mode */ +#define SET_INPUT_PULLUP(IO) _SET_MODE(IO, INPUT_PULLUP) /*!< Input with Pull-up activation */ +#define SET_INPUT_PULLDOWN(IO) _SET_MODE(IO, INPUT_PULLDOWN) /*!< Input with Pull-down activation */ +#define SET_OUTPUT(IO) OUT_WRITE(IO, LOW) +#define SET_PWM(IO) _SET_MODE(IO, PWM) + +#define TOGGLE(IO) OUT_WRITE(IO, !READ(IO)) + +#define IS_INPUT(IO) !is_output(IO) +#define IS_OUTPUT(IO) is_output(IO) + +#define PWM_PIN(P) digitalPinHasPWM(P) + +// digitalRead/Write wrappers +#define extDigitalRead(IO) digitalRead(IO) +#define extDigitalWrite(IO,V) digitalWrite(IO,V) diff --git a/Marlin/src/HAL/TEENSY40_41/inc/Conditionals_LCD.h b/Marlin/src/HAL/TEENSY40_41/inc/Conditionals_LCD.h new file mode 100644 index 0000000000..6a8540927b --- /dev/null +++ b/Marlin/src/HAL/TEENSY40_41/inc/Conditionals_LCD.h @@ -0,0 +1,26 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#if HAS_SPI_TFT || HAS_FSMC_TFT + #error "Sorry! TFT displays are not available for HAL/TEENSY40_41." +#endif diff --git a/Marlin/src/HAL/TEENSY40_41/inc/Conditionals_adv.h b/Marlin/src/HAL/TEENSY40_41/inc/Conditionals_adv.h new file mode 100644 index 0000000000..5f1c4b1601 --- /dev/null +++ b/Marlin/src/HAL/TEENSY40_41/inc/Conditionals_adv.h @@ -0,0 +1,22 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once diff --git a/Marlin/src/HAL/TEENSY40_41/inc/Conditionals_post.h b/Marlin/src/HAL/TEENSY40_41/inc/Conditionals_post.h new file mode 100644 index 0000000000..998f1dcc0d --- /dev/null +++ b/Marlin/src/HAL/TEENSY40_41/inc/Conditionals_post.h @@ -0,0 +1,26 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#if USE_FALLBACK_EEPROM + #define USE_WIRED_EEPROM 1 +#endif diff --git a/Marlin/src/HAL/TEENSY40_41/inc/SanityCheck.h b/Marlin/src/HAL/TEENSY40_41/inc/SanityCheck.h new file mode 100644 index 0000000000..fbfe7b0fc3 --- /dev/null +++ b/Marlin/src/HAL/TEENSY40_41/inc/SanityCheck.h @@ -0,0 +1,38 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * Test TEENSY41 specific configuration values for errors at compile-time. + */ + +#if ENABLED(EMERGENCY_PARSER) + #error "EMERGENCY_PARSER is not yet implemented for Teensy 4.0/4.1. Disable EMERGENCY_PARSER to continue." +#endif + +#if ENABLED(FAST_PWM_FAN) || SPINDLE_LASER_FREQUENCY + #error "Features requiring Hardware PWM (FAST_PWM_FAN, SPINDLE_LASER_FREQUENCY) are not yet supported on Teensy 4.0/4.1." +#endif + +#if HAS_TMC_SW_SERIAL + #error "TMC220x Software Serial is not supported on this platform." +#endif diff --git a/Marlin/src/HAL/TEENSY40_41/pinsDebug.h b/Marlin/src/HAL/TEENSY40_41/pinsDebug.h new file mode 100644 index 0000000000..890f668650 --- /dev/null +++ b/Marlin/src/HAL/TEENSY40_41/pinsDebug.h @@ -0,0 +1,146 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * 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 + +#warning "PINS_DEBUGGING is not fully supported for Teensy 4.0 / 4.1 so 'M43' may cause hangs." + +#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS + +#define digitalRead_mod(p) extDigitalRead(p) // AVR digitalRead disabled PWM before it read the pin +#define PRINT_PORT(p) +#define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) +#define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%02d"), p); SERIAL_ECHO(buffer); }while(0) +#define GET_ARRAY_PIN(p) pin_array[p].pin +#define GET_ARRAY_IS_DIGITAL(p) pin_array[p].is_digital +#define VALID_PIN(pin) (pin >= 0 && pin < (int8_t)NUMBER_PINS_TOTAL ? 1 : 0) +#define DIGITAL_PIN_TO_ANALOG_PIN(p) int(p - analogInputToDigitalPin(0)) +#define IS_ANALOG(P) ((P) >= analogInputToDigitalPin(0) && (P) <= analogInputToDigitalPin(13)) || ((P) >= analogInputToDigitalPin(14) && (P) <= analogInputToDigitalPin(17)) +#define pwm_status(pin) HAL_pwm_status(pin) +#define GET_PINMODE(PIN) (VALID_PIN(pin) && IS_OUTPUT(pin)) +#define MULTI_NAME_PAD 16 // space needed to be pretty if not first name assigned to a pin + +struct pwm_pin_info_struct { + uint8_t type; // 0=no pwm, 1=flexpwm, 2=quad + uint8_t module; // 0-3, 0-3 + uint8_t channel; // 0=X, 1=A, 2=B + uint8_t muxval; // +}; + +#define M(a, b) ((((a) - 1) << 4) | (b)) + +const struct pwm_pin_info_struct pwm_pin_info[] = { + {1, M(1, 1), 0, 4}, // FlexPWM1_1_X 0 // AD_B0_03 + {1, M(1, 0), 0, 4}, // FlexPWM1_0_X 1 // AD_B0_02 + {1, M(4, 2), 1, 1}, // FlexPWM4_2_A 2 // EMC_04 + {1, M(4, 2), 2, 1}, // FlexPWM4_2_B 3 // EMC_05 + {1, M(2, 0), 1, 1}, // FlexPWM2_0_A 4 // EMC_06 + {1, M(2, 1), 1, 1}, // FlexPWM2_1_A 5 // EMC_08 + {1, M(2, 2), 1, 2}, // FlexPWM2_2_A 6 // B0_10 + {1, M(1, 3), 2, 6}, // FlexPWM1_3_B 7 // B1_01 + {1, M(1, 3), 1, 6}, // FlexPWM1_3_A 8 // B1_00 + {1, M(2, 2), 2, 2}, // FlexPWM2_2_B 9 // B0_11 + {2, M(1, 0), 0, 1}, // QuadTimer1_0 10 // B0_00 + {2, M(1, 2), 0, 1}, // QuadTimer1_2 11 // B0_02 + {2, M(1, 1), 0, 1}, // QuadTimer1_1 12 // B0_01 + {2, M(2, 0), 0, 1}, // QuadTimer2_0 13 // B0_03 + {2, M(3, 2), 0, 1}, // QuadTimer3_2 14 // AD_B1_02 + {2, M(3, 3), 0, 1}, // QuadTimer3_3 15 // AD_B1_03 + {0, M(1, 0), 0, 0}, + {0, M(1, 0), 0, 0}, + {2, M(3, 1), 0, 1}, // QuadTimer3_1 18 // AD_B1_01 + {2, M(3, 0), 0, 1}, // QuadTimer3_0 19 // AD_B1_00 + {0, M(1, 0), 0, 0}, + {0, M(1, 0), 0, 0}, + {1, M(4, 0), 1, 1}, // FlexPWM4_0_A 22 // AD_B1_08 + {1, M(4, 1), 1, 1}, // FlexPWM4_1_A 23 // AD_B1_09 + {1, M(1, 2), 0, 4}, // FlexPWM1_2_X 24 // AD_B0_12 + {1, M(1, 3), 0, 4}, // FlexPWM1_3_X 25 // AD_B0_13 + {0, M(1, 0), 0, 0}, + {0, M(1, 0), 0, 0}, + {1, M(3, 1), 2, 1}, // FlexPWM3_1_B 28 // EMC_32 + {1, M(3, 1), 1, 1}, // FlexPWM3_1_A 29 // EMC_31 + {0, M(1, 0), 0, 0}, + {0, M(1, 0), 0, 0}, + {0, M(1, 0), 0, 0}, + {1, M(2, 0), 2, 1}, // FlexPWM2_0_B 33 // EMC_07 + #ifdef ARDUINO_TEENSY40 + {1, M(1, 1), 2, 1}, // FlexPWM1_1_B 34 // SD_B0_03 + {1, M(1, 1), 1, 1}, // FlexPWM1_1_A 35 // SD_B0_02 + {1, M(1, 0), 2, 1}, // FlexPWM1_0_B 36 // SD_B0_01 + {1, M(1, 0), 1, 1}, // FlexPWM1_0_A 37 // SD_B0_00 + {1, M(1, 2), 2, 1}, // FlexPWM1_2_B 38 // SD_B0_05 + {1, M(1, 2), 1, 1}, // FlexPWM1_2_A 39 // SD_B0_04 + #endif + #ifdef ARDUINO_TEENSY41 + {0, M(1, 0), 0, 0}, + {0, M(1, 0), 0, 0}, + {1, M(2, 3), 1, 6}, // FlexPWM2_3_A 36 // B1_00 + {1, M(2, 3), 2, 6}, // FlexPWM2_3_B 37 // B1_01 + {0, M(1, 0), 0, 0}, + {0, M(1, 0), 0, 0}, + {0, M(1, 0), 0, 0}, + {0, M(1, 0), 0, 0}, + {1, M(1, 1), 2, 1}, // FlexPWM1_1_B 42 // SD_B0_03 + {1, M(1, 1), 1, 1}, // FlexPWM1_1_A 43 // SD_B0_02 + {1, M(1, 0), 2, 1}, // FlexPWM1_0_B 44 // SD_B0_01 + {1, M(1, 0), 1, 1}, // FlexPWM1_0_A 45 // SD_B0_00 + {1, M(1, 2), 2, 1}, // FlexPWM1_2_B 46 // SD_B0_05 + {1, M(1, 2), 1, 1}, // FlexPWM1_2_A 47 // SD_B0_04 + {0, M(1, 0), 0, 0}, // duplicate FlexPWM1_0_B + {0, M(1, 0), 0, 0}, // duplicate FlexPWM1_2_A + {0, M(1, 0), 0, 0}, // duplicate FlexPWM1_2_B + {1, M(3, 3), 2, 1}, // FlexPWM3_3_B 51 // EMC_22 + {0, M(1, 0), 0, 0}, // duplicate FlexPWM1_1_B + {0, M(1, 0), 0, 0}, // duplicate FlexPWM1_1_A + {1, M(3, 0), 1, 1}, // FlexPWM3_0_A 53 // EMC_29 + #endif +}; + +void HAL_print_analog_pin(char buffer[], int8_t pin) { + if (pin <= 23) sprintf_P(buffer, PSTR("(A%2d) "), int(pin - 14)); + else if (pin <= 41) sprintf_P(buffer, PSTR("(A%2d) "), int(pin - 24)); +} + +void HAL_analog_pin_state(char buffer[], int8_t pin) { + if (pin <= 23) sprintf_P(buffer, PSTR("Analog in =% 5d"), analogRead(pin - 14)); + else if (pin <= 41) sprintf_P(buffer, PSTR("Analog in =% 5d"), analogRead(pin - 24)); +} + +#define PWM_PRINT(V) do{ sprintf_P(buffer, PSTR("PWM: %4d"), V); SERIAL_ECHO(buffer); }while(0) + +/** + * Print a pin's PWM status. + * Return true if it's currently a PWM pin. + */ +bool HAL_pwm_status(int8_t pin) { + char buffer[20]; // for the sprintf statements + const struct pwm_pin_info_struct *info; + + if (pin >= CORE_NUM_DIGITAL) return 0; + info = pwm_pin_info + pin; + + if (info->type == 0) return 0; + + /* TODO decode pwm value from timers */ + // for now just indicate if output is set as pwm + PWM_PRINT(*(portConfigRegister(pin)) == info->muxval); + return (*(portConfigRegister(pin)) == info->muxval); +} + +static void pwm_details(uint8_t pin) { /* TODO */ } diff --git a/Marlin/src/HAL/TEENSY40_41/spi_pins.h b/Marlin/src/HAL/TEENSY40_41/spi_pins.h new file mode 100644 index 0000000000..276d4f456a --- /dev/null +++ b/Marlin/src/HAL/TEENSY40_41/spi_pins.h @@ -0,0 +1,27 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#define SCK_PIN 13 +#define MISO_PIN 12 +#define MOSI_PIN 11 +#define SS_PIN 20 // SDSS // A.28, A.29, B.21, C.26, C.29 diff --git a/Marlin/src/HAL/TEENSY40_41/timers.cpp b/Marlin/src/HAL/TEENSY40_41/timers.cpp new file mode 100644 index 0000000000..15f5185a6b --- /dev/null +++ b/Marlin/src/HAL/TEENSY40_41/timers.cpp @@ -0,0 +1,114 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * Teensy4.0/4.1 (__IMXRT1062__) + */ + +#ifdef __IMXRT1062__ + +#include "../../inc/MarlinConfig.h" + +void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { + switch (timer_num) { + case 0: + CCM_CSCMR1 &= ~CCM_CSCMR1_PERCLK_CLK_SEL; // turn off 24mhz mode + CCM_CCGR1 |= CCM_CCGR1_GPT1_BUS(CCM_CCGR_ON); + + GPT1_CR = 0; // disable timer + GPT1_SR = 0x3F; // clear all prior status + GPT1_PR = GPT1_TIMER_PRESCALE - 1; + GPT1_CR |= GPT_CR_CLKSRC(1); //clock selection #1 (peripheral clock = 150 MHz) + GPT1_CR |= GPT_CR_ENMOD; //reset count to zero before enabling + GPT1_CR |= GPT_CR_OM1(1); // toggle mode + GPT1_OCR1 = (GPT1_TIMER_RATE / frequency) -1; // Initial compare value + GPT1_IR = GPT_IR_OF1IE; // Compare3 value + GPT1_CR |= GPT_CR_EN; //enable GPT2 counting at 150 MHz + + OUT_WRITE(15, HIGH); + attachInterruptVector(IRQ_GPT1, &stepTC_Handler); + NVIC_SET_PRIORITY(IRQ_GPT1, 16); + break; + case 1: + CCM_CSCMR1 &= ~CCM_CSCMR1_PERCLK_CLK_SEL; // turn off 24mhz mode + CCM_CCGR0 |= CCM_CCGR0_GPT2_BUS(CCM_CCGR_ON); + + GPT2_CR = 0; // disable timer + GPT2_SR = 0x3F; // clear all prior status + GPT2_PR = GPT2_TIMER_PRESCALE - 1; + GPT2_CR |= GPT_CR_CLKSRC(1); //clock selection #1 (peripheral clock = 150 MHz) + GPT2_CR |= GPT_CR_ENMOD; //reset count to zero before enabling + GPT2_CR |= GPT_CR_OM1(1); // toggle mode + GPT2_OCR1 = (GPT2_TIMER_RATE / frequency) -1; // Initial compare value + GPT2_IR = GPT_IR_OF1IE; // Compare3 value + GPT2_CR |= GPT_CR_EN; //enable GPT2 counting at 150 MHz + + OUT_WRITE(14, HIGH); + attachInterruptVector(IRQ_GPT2, &tempTC_Handler); + NVIC_SET_PRIORITY(IRQ_GPT2, 32); + break; + } +} + +void HAL_timer_enable_interrupt(const uint8_t timer_num) { + switch (timer_num) { + case 0: + NVIC_ENABLE_IRQ(IRQ_GPT1); + break; + case 1: + NVIC_ENABLE_IRQ(IRQ_GPT2); + break; + } +} + +void HAL_timer_disable_interrupt(const uint8_t timer_num) { + switch (timer_num) { + case 0: NVIC_DISABLE_IRQ(IRQ_GPT1); break; + case 1: NVIC_DISABLE_IRQ(IRQ_GPT2); break; + } + + // We NEED memory barriers to ensure Interrupts are actually disabled! + // ( https://dzone.com/articles/nvic-disabling-interrupts-on-arm-cortex-m-and-the ) + asm volatile("dsb"); +} + +bool HAL_timer_interrupt_enabled(const uint8_t timer_num) { + switch (timer_num) { + case 0: return (NVIC_IS_ENABLED(IRQ_GPT1)); + case 1: return (NVIC_IS_ENABLED(IRQ_GPT2)); + } + return false; +} + +void HAL_timer_isr_prologue(const uint8_t timer_num) { + switch (timer_num) { + case 0: + GPT1_SR = GPT_IR_OF1IE; // clear OF3 bit + break; + case 1: + GPT2_SR = GPT_IR_OF1IE; // clear OF3 bit + break; + } + asm volatile("dsb"); +} + +#endif // __IMXRT1062__ diff --git a/Marlin/src/HAL/TEENSY40_41/timers.h b/Marlin/src/HAL/TEENSY40_41/timers.h new file mode 100644 index 0000000000..81891c366b --- /dev/null +++ b/Marlin/src/HAL/TEENSY40_41/timers.h @@ -0,0 +1,120 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com + * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * 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 + +/** + * Description: HAL for + * Teensy4.0/4.1 (__IMXRT1062__) + */ + +#include + +// ------------------------ +// Defines +// ------------------------ + +#define FORCE_INLINE __attribute__((always_inline)) inline + +typedef uint32_t hal_timer_t; +#define HAL_TIMER_TYPE_MAX 0xFFFFFFFE + +#define GPT_TIMER_RATE F_BUS_ACTUAL // 150MHz + +#define GPT1_TIMER_PRESCALE 2 +#define GPT2_TIMER_PRESCALE 10 + +#define GPT1_TIMER_RATE (GPT_TIMER_RATE / GPT1_TIMER_PRESCALE) // 75MHz +#define GPT2_TIMER_RATE (GPT_TIMER_RATE / GPT2_TIMER_PRESCALE) // 15MHz + +#ifndef STEP_TIMER_NUM + #define STEP_TIMER_NUM 0 // Timer Index for Stepper +#endif +#ifndef PULSE_TIMER_NUM + #define PULSE_TIMER_NUM STEP_TIMER_NUM +#endif +#ifndef TEMP_TIMER_NUM + #define TEMP_TIMER_NUM 1 // Timer Index for Temperature +#endif + +#define TEMP_TIMER_RATE 1000000 +#define TEMP_TIMER_FREQUENCY 1000 + +#define STEPPER_TIMER_RATE GPT1_TIMER_RATE +#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) +#define STEPPER_TIMER_PRESCALE ((GPT_TIMER_RATE / 1000000) / STEPPER_TIMER_TICKS_PER_US) + +#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer +#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE +#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US + +#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(STEP_TIMER_NUM) +#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(STEP_TIMER_NUM) +#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(STEP_TIMER_NUM) + +#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM) +#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM) + +#ifndef HAL_STEP_TIMER_ISR + #define HAL_STEP_TIMER_ISR() extern "C" void stepTC_Handler() // GPT1_Handler() +#endif +#ifndef HAL_TEMP_TIMER_ISR + #define HAL_TEMP_TIMER_ISR() extern "C" void tempTC_Handler() // GPT2_Handler() +#endif + +extern "C" void stepTC_Handler(); +extern "C" void tempTC_Handler(); + +void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency); + +FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t compare) { + switch (timer_num) { + case 0: + GPT1_OCR1 = compare - 1; + break; + case 1: + GPT2_OCR1 = compare - 1; + break; + } +} + +FORCE_INLINE static hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) { + switch (timer_num) { + case 0: return GPT1_OCR1; + case 1: return GPT2_OCR1; + } + return 0; +} + +FORCE_INLINE static hal_timer_t HAL_timer_get_count(const uint8_t timer_num) { + switch (timer_num) { + case 0: return GPT1_CNT; + case 1: return GPT2_CNT; + } + return 0; +} + +void HAL_timer_enable_interrupt(const uint8_t timer_num); +void HAL_timer_disable_interrupt(const uint8_t timer_num); +bool HAL_timer_interrupt_enabled(const uint8_t timer_num); + +void HAL_timer_isr_prologue(const uint8_t timer_num); +//void HAL_timer_isr_epilogue(const uint8_t timer_num) {} +#define HAL_timer_isr_epilogue(TIMER_NUM) diff --git a/Marlin/src/HAL/TEENSY40_41/watchdog.cpp b/Marlin/src/HAL/TEENSY40_41/watchdog.cpp new file mode 100644 index 0000000000..4253944f2b --- /dev/null +++ b/Marlin/src/HAL/TEENSY40_41/watchdog.cpp @@ -0,0 +1,52 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#ifdef __IMXRT1062__ + +#include "../../inc/MarlinConfig.h" + +#if ENABLED(USE_WATCHDOG) + +#include "watchdog.h" + +// 4 seconds timeout +#define WDTO 4 //seconds + +uint8_t timeoutval = (WDTO - 0.5f) / 0.5f; + +void watchdog_init() { + + CCM_CCGR3 |= CCM_CCGR3_WDOG1(3); // enable WDOG1 clocks + WDOG1_WMCR = 0; // disable power down PDE + WDOG1_WCR |= WDOG_WCR_SRS | WDOG_WCR_WT(timeoutval); + WDOG1_WCR |= WDOG_WCR_WDE | WDOG_WCR_WDT | WDOG_WCR_SRE; + +} + +void HAL_watchdog_refresh() { + // Watchdog refresh sequence + WDOG1_WSR = 0x5555; + WDOG1_WSR = 0xAAAA; +} + +#endif // USE_WATCHDOG + +#endif // __IMXRT1062__ diff --git a/Marlin/src/HAL/TEENSY40_41/watchdog.h b/Marlin/src/HAL/TEENSY40_41/watchdog.h new file mode 100644 index 0000000000..f10ecb5aef --- /dev/null +++ b/Marlin/src/HAL/TEENSY40_41/watchdog.h @@ -0,0 +1,30 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * Watchdog for Teensy4.0/4.1 (__IMXRT1062__) + */ + +void watchdog_init(); + +void HAL_watchdog_refresh(); diff --git a/Marlin/src/HAL/platforms.h b/Marlin/src/HAL/platforms.h index d4cec64267..ef17d19170 100644 --- a/Marlin/src/HAL/platforms.h +++ b/Marlin/src/HAL/platforms.h @@ -31,6 +31,8 @@ #define HAL_PATH(PATH, NAME) XSTR(PATH/TEENSY31_32/NAME) #elif defined(__MK64FX512__) || defined(__MK66FX1M0__) #define HAL_PATH(PATH, NAME) XSTR(PATH/TEENSY35_36/NAME) +#elif defined(__IMXRT1062__) + #define HAL_PATH(PATH, NAME) XSTR(PATH/TEENSY40_41/NAME) #elif defined(TARGET_LPC1768) #define HAL_PATH(PATH, NAME) XSTR(PATH/LPC1768/NAME) #elif defined(__STM32F1__) || defined(TARGET_STM32F1) diff --git a/Marlin/src/HAL/shared/HAL_ST7920.h b/Marlin/src/HAL/shared/HAL_ST7920.h index 05e8a1f2c5..4e362f96ba 100644 --- a/Marlin/src/HAL/shared/HAL_ST7920.h +++ b/Marlin/src/HAL/shared/HAL_ST7920.h @@ -27,7 +27,7 @@ * (bypassing U8G), it will allow the LIGHTWEIGHT_UI to operate. */ -#if BOTH(HAS_GRAPHICAL_LCD, LIGHTWEIGHT_UI) +#if BOTH(HAS_MARLINUI_U8GLIB, LIGHTWEIGHT_UI) void ST7920_cs(); void ST7920_ncs(); void ST7920_set_cmd(); diff --git a/Marlin/src/HAL/shared/backtrace/unwmemaccess.cpp b/Marlin/src/HAL/shared/backtrace/unwmemaccess.cpp index 8cf31cadf5..4b085f90ce 100644 --- a/Marlin/src/HAL/shared/backtrace/unwmemaccess.cpp +++ b/Marlin/src/HAL/shared/backtrace/unwmemaccess.cpp @@ -20,124 +20,139 @@ /* Validate address */ #ifdef ARDUINO_ARCH_SAM -// For DUE, valid address ranges are -// SRAM (0x20070000 - 0x20088000) (96kb) -// FLASH (0x00080000 - 0x00100000) (512kb) -// -#define START_SRAM_ADDR 0x20070000 -#define END_SRAM_ADDR 0x20088000 -#define START_FLASH_ADDR 0x00080000 -#define END_FLASH_ADDR 0x00100000 -#endif - -#ifdef TARGET_LPC1768 -// For LPC1769: -// SRAM (0x10000000 - 0x10008000) (32kb) -// FLASH (0x00000000 - 0x00080000) (512kb) -// -#define START_SRAM_ADDR 0x10000000 -#define END_SRAM_ADDR 0x10008000 -#define START_FLASH_ADDR 0x00000000 -#define END_FLASH_ADDR 0x00080000 -#endif - -#if 0 -// For STM32F103CBT6 -// SRAM (0x20000000 - 0x20005000) (20kb) -// FLASH (0x00000000 - 0x00020000) (128kb) -// -#define START_SRAM_ADDR 0x20000000 -#define END_SRAM_ADDR 0x20005000 -#define START_FLASH_ADDR 0x00000000 -#define END_FLASH_ADDR 0x00020000 -#endif -#if defined(__STM32F1__) || defined(STM32F1xx) || defined(STM32F0xx) -// For STM32F103ZET6/STM32F103VET6/STM32F0xx -// SRAM (0x20000000 - 0x20010000) (64kb) -// FLASH (0x00000000 - 0x00080000) (512kb) -// -#define START_SRAM_ADDR 0x20000000 -#define END_SRAM_ADDR 0x20010000 -#define START_FLASH_ADDR 0x00000000 -#define END_FLASH_ADDR 0x00080000 -#endif - -#if defined(STM32F4) || defined(STM32F4xx) -// For STM32F407VET -// SRAM (0x20000000 - 0x20030000) (192kb) -// FLASH (0x08000000 - 0x08080000) (512kb) -// -#define START_SRAM_ADDR 0x20000000 -#define END_SRAM_ADDR 0x20030000 -#define START_FLASH_ADDR 0x08000000 -#define END_FLASH_ADDR 0x08080000 -#endif - -#if MB(THE_BORG) -// For STM32F765 in BORG -// SRAM (0x20000000 - 0x20080000) (512kb) -// FLASH (0x08000000 - 0x08100000) (1024kb) -// -#define START_SRAM_ADDR 0x20000000 -#define END_SRAM_ADDR 0x20080000 -#define START_FLASH_ADDR 0x08000000 -#define END_FLASH_ADDR 0x08100000 -#endif + // For DUE, valid address ranges are + // SRAM (0x20070000 - 0x20088000) (96kb) + // FLASH (0x00080000 - 0x00100000) (512kb) + // + #define START_SRAM_ADDR 0x20070000 + #define END_SRAM_ADDR 0x20088000 + #define START_FLASH_ADDR 0x00080000 + #define END_FLASH_ADDR 0x00100000 + +#elif defined(TARGET_LPC1768) + + // For LPC1769: + // SRAM (0x10000000 - 0x10008000) (32kb) + // FLASH (0x00000000 - 0x00080000) (512kb) + // + #define START_SRAM_ADDR 0x10000000 + #define END_SRAM_ADDR 0x10008000 + #define START_FLASH_ADDR 0x00000000 + #define END_FLASH_ADDR 0x00080000 + +#elif 0 + + // For STM32F103CBT6 + // SRAM (0x20000000 - 0x20005000) (20kb) + // FLASH (0x00000000 - 0x00020000) (128kb) + // + #define START_SRAM_ADDR 0x20000000 + #define END_SRAM_ADDR 0x20005000 + #define START_FLASH_ADDR 0x00000000 + #define END_FLASH_ADDR 0x00020000 + +#elif defined(__STM32F1__) || defined(STM32F1xx) || defined(STM32F0xx) + + // For STM32F103ZET6/STM32F103VET6/STM32F0xx + // SRAM (0x20000000 - 0x20010000) (64kb) + // FLASH (0x00000000 - 0x00080000) (512kb) + // + #define START_SRAM_ADDR 0x20000000 + #define END_SRAM_ADDR 0x20010000 + #define START_FLASH_ADDR 0x00000000 + #define END_FLASH_ADDR 0x00080000 + +#elif defined(STM32F4) || defined(STM32F4xx) + + // For STM32F407VET + // SRAM (0x20000000 - 0x20030000) (192kb) + // FLASH (0x08000000 - 0x08080000) (512kb) + // + #define START_SRAM_ADDR 0x20000000 + #define END_SRAM_ADDR 0x20030000 + #define START_FLASH_ADDR 0x08000000 + #define END_FLASH_ADDR 0x08080000 + +#elif MB(THE_BORG) + + // For STM32F765 in BORG + // SRAM (0x20000000 - 0x20080000) (512kb) + // FLASH (0x08000000 - 0x08100000) (1024kb) + // + #define START_SRAM_ADDR 0x20000000 + #define END_SRAM_ADDR 0x20080000 + #define START_FLASH_ADDR 0x08000000 + #define END_FLASH_ADDR 0x08100000 + +#elif MB(REMRAM_V1) + + // For STM32F765VI in RemRam v1 + // SRAM (0x20000000 - 0x20080000) (512kb) + // FLASH (0x08000000 - 0x08200000) (2048kb) + // + #define START_SRAM_ADDR 0x20000000 + #define END_SRAM_ADDR 0x20080000 + #define START_FLASH_ADDR 0x08000000 + #define END_FLASH_ADDR 0x08200000 + +#elif defined(__MK20DX256__) + + // For MK20DX256 in TEENSY 3.1 or TEENSY 3.2 + // SRAM (0x1FFF8000 - 0x20008000) (64kb) + // FLASH (0x00000000 - 0x00040000) (256kb) + // + #define START_SRAM_ADDR 0x1FFF8000 + #define END_SRAM_ADDR 0x20008000 + #define START_FLASH_ADDR 0x00000000 + #define END_FLASH_ADDR 0x00040000 + +#elif defined(__MK64FX512__) + + // For MK64FX512 in TEENSY 3.5 + // SRAM (0x1FFF0000 - 0x20020000) (192kb) + // FLASH (0x00000000 - 0x00080000) (512kb) + // + #define START_SRAM_ADDR 0x1FFF0000 + #define END_SRAM_ADDR 0x20020000 + #define START_FLASH_ADDR 0x00000000 + #define END_FLASH_ADDR 0x00080000 + +#elif defined(__MK66FX1M0__) + + // For MK66FX1M0 in TEENSY 3.6 + // SRAM (0x1FFF0000 - 0x20030000) (256kb) + // FLASH (0x00000000 - 0x00140000) (1.25Mb) + // + #define START_SRAM_ADDR 0x1FFF0000 + #define END_SRAM_ADDR 0x20030000 + #define START_FLASH_ADDR 0x00000000 + #define END_FLASH_ADDR 0x00140000 + +#elif defined(__IMXRT1062__) + + // For IMXRT1062 in TEENSY 4.0/4/1 + // ITCM (rwx): ORIGIN = 0x00000000, LENGTH = 512K + // DTCM (rwx): ORIGIN = 0x20000000, LENGTH = 512K + // RAM (rwx): ORIGIN = 0x20200000, LENGTH = 512K + // FLASH (rwx): ORIGIN = 0x60000000, LENGTH = 1984K + // + #define START_SRAM_ADDR 0x00000000 + #define END_SRAM_ADDR 0x20280000 + #define START_FLASH_ADDR 0x60000000 + #define END_FLASH_ADDR 0x601F0000 + +#elif defined(__SAMD51P20A__) + + // For SAMD51x20, valid address ranges are + // SRAM (0x20000000 - 0x20040000) (256kb) + // FLASH (0x00000000 - 0x00100000) (1024kb) + // + #define START_SRAM_ADDR 0x20000000 + #define END_SRAM_ADDR 0x20040000 + #define START_FLASH_ADDR 0x00000000 + #define END_FLASH_ADDR 0x00100000 -#if MB(REMRAM_V1) -// For STM32F765VI in RemRam v1 -// SRAM (0x20000000 - 0x20080000) (512kb) -// FLASH (0x08000000 - 0x08200000) (2048kb) -// -#define START_SRAM_ADDR 0x20000000 -#define END_SRAM_ADDR 0x20080000 -#define START_FLASH_ADDR 0x08000000 -#define END_FLASH_ADDR 0x08200000 -#endif - -#ifdef __MK20DX256__ -// For MK20DX256 in TEENSY 3.1 or TEENSY 3.2 -// SRAM (0x1FFF8000 - 0x20008000) (64kb) -// FLASH (0x00000000 - 0x00040000) (256kb) -// -#define START_SRAM_ADDR 0x1FFF8000 -#define END_SRAM_ADDR 0x20008000 -#define START_FLASH_ADDR 0x00000000 -#define END_FLASH_ADDR 0x00040000 -#endif - -#ifdef __MK64FX512__ -// For MK64FX512 in TEENSY 3.5 -// SRAM (0x1FFF0000 - 0x20020000) (192kb) -// FLASH (0x00000000 - 0x00080000) (512kb) -// -#define START_SRAM_ADDR 0x1FFF0000 -#define END_SRAM_ADDR 0x20020000 -#define START_FLASH_ADDR 0x00000000 -#define END_FLASH_ADDR 0x00080000 -#endif - -#ifdef __MK66FX1M0__ -// For MK66FX1M0 in TEENSY 3.6 -// SRAM (0x1FFF0000 - 0x20030000) (256kb) -// FLASH (0x00000000 - 0x00140000) (1.25Mb) -// -#define START_SRAM_ADDR 0x1FFF0000 -#define END_SRAM_ADDR 0x20030000 -#define START_FLASH_ADDR 0x00000000 -#define END_FLASH_ADDR 0x00140000 -#endif - -#ifdef __SAMD51P20A__ -// For SAMD51x20, valid address ranges are -// SRAM (0x20000000 - 0x20040000) (256kb) -// FLASH (0x00000000 - 0x00100000) (1024kb) -// -#define START_SRAM_ADDR 0x20000000 -#define END_SRAM_ADDR 0x20040000 -#define START_FLASH_ADDR 0x00000000 -#define END_FLASH_ADDR 0x00100000 #endif static bool validate_addr(uint32_t addr) { @@ -177,4 +192,4 @@ bool UnwReadB(const uint32_t a, uint8_t *v) { return true; } -#endif +#endif // __arm__ || __thumb__ diff --git a/Marlin/src/HAL/shared/eeprom_if.h b/Marlin/src/HAL/shared/eeprom_if.h index 44bc0c719c..e44da801df 100644 --- a/Marlin/src/HAL/shared/eeprom_if.h +++ b/Marlin/src/HAL/shared/eeprom_if.h @@ -27,7 +27,3 @@ void eeprom_init(); void eeprom_write_byte(uint8_t *pos, unsigned char value); uint8_t eeprom_read_byte(uint8_t *pos); - -#if ENABLED(EEPROM_W25Q) -void eeprom_hw_deinit(void); -#endif \ No newline at end of file diff --git a/Marlin/src/HAL/shared/servo.cpp b/Marlin/src/HAL/shared/servo.cpp index d69cf2fe2c..cfec6f3017 100644 --- a/Marlin/src/HAL/shared/servo.cpp +++ b/Marlin/src/HAL/shared/servo.cpp @@ -48,7 +48,6 @@ * readMicroseconds() - Get the last-written servo pulse width in microseconds. * attached() - Return true if a servo is attached. * detach() - Stop an attached servo from pulsing its i/o pin. - * */ #include "../../inc/MarlinConfig.h" diff --git a/Marlin/src/HAL/shared/servo.h b/Marlin/src/HAL/shared/servo.h index f9c4784118..6d850da851 100644 --- a/Marlin/src/HAL/shared/servo.h +++ b/Marlin/src/HAL/shared/servo.h @@ -41,7 +41,6 @@ */ /** - * * A servo is activated by creating an instance of the Servo class passing the desired pin to the attach() method. * The servos are pulsed in the background using the value most recently written using the write() method * @@ -71,6 +70,8 @@ #include "../TEENSY31_32/Servo.h" #elif IS_TEENSY35 || IS_TEENSY36 #include "../TEENSY35_36/Servo.h" +#elif IS_TEENSY40 || IS_TEENSY41 + #include "../TEENSY40_41/Servo.h" #elif defined(TARGET_LPC1768) #include "../LPC1768/Servo.h" #elif defined(__STM32F1__) || defined(TARGET_STM32F1) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 29f2783b28..49a38aef2c 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -72,9 +72,9 @@ #endif #if ENABLED(DWIN_CREALITY_LCD) - #include "lcd/dwin/dwin.h" + #include "lcd/dwin/e3v2/dwin.h" #include "lcd/dwin/dwin_lcd.h" - #include "lcd/dwin/rotary_encoder.h" + #include "lcd/dwin/e3v2/rotary_encoder.h" #endif #if ENABLED(IIC_BL24CXX_EEPROM) @@ -796,6 +796,10 @@ void kill(PGM_P const lcd_error/*=nullptr*/, PGM_P const lcd_component/*=nullptr UNUSED(lcd_component); #endif + #if HAS_TFT_LVGL_UI + lv_draw_error_message(lcd_error); + #endif + #ifdef ACTION_ON_KILL host_action_kill(); #endif @@ -863,6 +867,57 @@ void stop() { } } +inline void tmc_standby_setup() { + #if PIN_EXISTS(X_STDBY) + SET_INPUT_PULLDOWN(X_STDBY_PIN); + #endif + #if PIN_EXISTS(X2_STDBY) + SET_INPUT_PULLDOWN(X2_STDBY_PIN); + #endif + #if PIN_EXISTS(Y_STDBY) + SET_INPUT_PULLDOWN(Y_STDBY_PIN); + #endif + #if PIN_EXISTS(Y2_STDBY) + SET_INPUT_PULLDOWN(Y2_STDBY_PIN); + #endif + #if PIN_EXISTS(Z_STDBY) + SET_INPUT_PULLDOWN(Z_STDBY_PIN); + #endif + #if PIN_EXISTS(Z2_STDBY) + SET_INPUT_PULLDOWN(Z2_STDBY_PIN); + #endif + #if PIN_EXISTS(Z3_STDBY) + SET_INPUT_PULLDOWN(Z3_STDBY_PIN); + #endif + #if PIN_EXISTS(Z4_STDBY) + SET_INPUT_PULLDOWN(Z4_STDBY_PIN); + #endif + #if PIN_EXISTS(E0_STDBY) + SET_INPUT_PULLDOWN(E0_STDBY_PIN); + #endif + #if PIN_EXISTS(E1_STDBY) + SET_INPUT_PULLDOWN(E1_STDBY_PIN); + #endif + #if PIN_EXISTS(E2_STDBY) + SET_INPUT_PULLDOWN(E2_STDBY_PIN); + #endif + #if PIN_EXISTS(E3_STDBY) + SET_INPUT_PULLDOWN(E3_STDBY_PIN); + #endif + #if PIN_EXISTS(E4_STDBY) + SET_INPUT_PULLDOWN(E4_STDBY_PIN); + #endif + #if PIN_EXISTS(E5_STDBY) + SET_INPUT_PULLDOWN(E5_STDBY_PIN); + #endif + #if PIN_EXISTS(E6_STDBY) + SET_INPUT_PULLDOWN(E6_STDBY_PIN); + #endif + #if PIN_EXISTS(E7_STDBY) + SET_INPUT_PULLDOWN(E7_STDBY_PIN); + #endif +} + /** * Marlin entry-point: Set up before the program loop * - Set up the kill pin, filament runout, power hold @@ -884,6 +939,8 @@ void stop() { */ void setup() { + tmc_standby_setup(); // TMC Low Power Standby pins must be set early or they're not usable + #if ENABLED(MARLIN_DEV_MODE) auto log_current_ms = [&](PGM_P const msg) { SERIAL_ECHO_START(); @@ -908,16 +965,21 @@ void setup() { #endif #endif - #if NUM_SERIAL > 0 - MYSERIAL0.begin(BAUDRATE); - uint32_t serial_connect_timeout = millis() + 1000UL; - while (!MYSERIAL0 && PENDING(millis(), serial_connect_timeout)) { /*nada*/ } - #if HAS_MULTI_SERIAL - MYSERIAL1.begin(BAUDRATE); - serial_connect_timeout = millis() + 1000UL; - while (!MYSERIAL1 && PENDING(millis(), serial_connect_timeout)) { /*nada*/ } - #endif - SERIAL_ECHO_MSG("start"); + MYSERIAL0.begin(BAUDRATE); + uint32_t serial_connect_timeout = millis() + 1000UL; + while (!MYSERIAL0 && PENDING(millis(), serial_connect_timeout)) { /*nada*/ } + #if HAS_MULTI_SERIAL + MYSERIAL1.begin(BAUDRATE); + serial_connect_timeout = millis() + 1000UL; + while (!MYSERIAL1 && PENDING(millis(), serial_connect_timeout)) { /*nada*/ } + #endif + SERIAL_ECHO_MSG("start"); + + #if BOTH(HAS_TFT_LVGL_UI, USE_WIFI_FUNCTION) + mks_esp_wifi_init(); + WIFISERIAL.begin(WIFI_BAUDRATE); + serial_connect_timeout = millis() + 1000UL; + while (/*!WIFISERIAL && */PENDING(millis(), serial_connect_timeout)) { /*nada*/ } #endif SETUP_RUN(HAL_init()); @@ -977,18 +1039,14 @@ void setup() { SERIAL_CHAR(' '); SERIAL_ECHOLNPGM(SHORT_BUILD_VERSION); SERIAL_EOL(); - #if defined(STRING_DISTRIBUTION_DATE) && defined(STRING_CONFIG_H_AUTHOR) SERIAL_ECHO_MSG( - STR_CONFIGURATION_VER - STRING_DISTRIBUTION_DATE - STR_AUTHOR STRING_CONFIG_H_AUTHOR + " Last Updated: " STRING_DISTRIBUTION_DATE + " | Author: " STRING_CONFIG_H_AUTHOR ); - SERIAL_ECHO_MSG("Compiled: " __DATE__); #endif - - SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR(STR_FREE_MEMORY, freeMemory(), STR_PLANNER_BUFFER_BYTES, (int)sizeof(block_t) * (BLOCK_BUFFER_SIZE)); + SERIAL_ECHO_MSG("Compiled: " __DATE__); + SERIAL_ECHO_MSG(STR_FREE_MEMORY, freeMemory(), STR_PLANNER_BUFFER_BYTES, (int)sizeof(block_t) * (BLOCK_BUFFER_SIZE)); // Set up LEDs early #if HAS_COLOR_LEDS @@ -1014,7 +1072,7 @@ void setup() { DWIN_UpdateLCD(); // Show bootscreen (first image) #else SETUP_RUN(ui.init()); - #if HAS_SPI_LCD && ENABLED(SHOW_BOOTSCREEN) + #if HAS_WIRED_LCD && ENABLED(SHOW_BOOTSCREEN) SETUP_RUN(ui.show_bootscreen()); #endif SETUP_RUN(ui.reset_status()); // Load welcome message early. (Retained if no errors exist.) diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index c880b3d325..beb348845d 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -57,56 +57,58 @@ #define BOARD_K8200 1101 // Velleman K8200 Controller (derived from 3Drag Controller) #define BOARD_K8400 1102 // Velleman K8400 Controller (derived from 3Drag Controller) #define BOARD_K8600 1103 // Velleman K8600 Controller (Vertex Nano) -#define BOARD_BAM_DICE 1104 // 2PrintBeta BAM&DICE with STK drivers -#define BOARD_BAM_DICE_DUE 1105 // 2PrintBeta BAM&DICE Due with STK drivers -#define BOARD_MKS_BASE 1106 // MKS BASE v1.0 -#define BOARD_MKS_BASE_14 1107 // MKS BASE v1.4 with Allegro A4982 stepper drivers -#define BOARD_MKS_BASE_15 1108 // MKS BASE v1.5 with Allegro A4982 stepper drivers -#define BOARD_MKS_BASE_16 1109 // MKS BASE v1.6 with Allegro A4982 stepper drivers -#define BOARD_MKS_BASE_HEROIC 1110 // MKS BASE 1.0 with Heroic HR4982 stepper drivers -#define BOARD_MKS_GEN_13 1111 // MKS GEN v1.3 or 1.4 -#define BOARD_MKS_GEN_L 1112 // MKS GEN L -#define BOARD_KFB_2 1113 // BigTreeTech or BIQU KFB2.0 -#define BOARD_ZRIB_V20 1114 // zrib V2.0 control board (Chinese knock off RAMPS replica) -#define BOARD_FELIX2 1115 // Felix 2.0+ Electronics Board (RAMPS like) -#define BOARD_RIGIDBOARD 1116 // Invent-A-Part RigidBoard -#define BOARD_RIGIDBOARD_V2 1117 // Invent-A-Part RigidBoard V2 -#define BOARD_SAINSMART_2IN1 1118 // Sainsmart 2-in-1 board -#define BOARD_ULTIMAKER 1119 // Ultimaker -#define BOARD_ULTIMAKER_OLD 1120 // Ultimaker (Older electronics. Pre 1.5.4. This is rare) -#define BOARD_AZTEEG_X3 1121 // Azteeg X3 -#define BOARD_AZTEEG_X3_PRO 1122 // Azteeg X3 Pro -#define BOARD_ULTIMAIN_2 1123 // Ultimainboard 2.x (Uses TEMP_SENSOR 20) -#define BOARD_RUMBA 1124 // Rumba -#define BOARD_RUMBA_RAISE3D 1125 // Raise3D N series Rumba derivative -#define BOARD_RL200 1126 // Rapide Lite 200 (v1, low-cost RUMBA clone with drv) -#define BOARD_FORMBOT_TREX2PLUS 1127 // Formbot T-Rex 2 Plus -#define BOARD_FORMBOT_TREX3 1128 // Formbot T-Rex 3 -#define BOARD_FORMBOT_RAPTOR 1129 // Formbot Raptor -#define BOARD_FORMBOT_RAPTOR2 1130 // Formbot Raptor 2 -#define BOARD_BQ_ZUM_MEGA_3D 1131 // bq ZUM Mega 3D -#define BOARD_MAKEBOARD_MINI 1132 // MakeBoard Mini v2.1.2 is a control board sold by MicroMake -#define BOARD_TRIGORILLA_13 1133 // TriGorilla Anycubic version 1.3-based on RAMPS EFB -#define BOARD_TRIGORILLA_14 1134 // ... Ver 1.4 -#define BOARD_TRIGORILLA_14_11 1135 // ... Rev 1.1 (new servo pin order) -#define BOARD_RAMPS_ENDER_4 1136 // Creality: Ender-4, CR-8 -#define BOARD_RAMPS_CREALITY 1137 // Creality: CR10S, CR20, CR-X -#define BOARD_RAMPS_DAGOMA 1138 // Dagoma F5 -#define BOARD_FYSETC_F6_13 1139 // FYSETC F6 1.3 -#define BOARD_FYSETC_F6_14 1140 // FYSETC F6 1.4 -#define BOARD_DUPLICATOR_I3_PLUS 1141 // Wanhao Duplicator i3 Plus -#define BOARD_VORON 1142 // VORON Design -#define BOARD_TRONXY_V3_1_0 1143 // Tronxy TRONXY-V3-1.0 -#define BOARD_Z_BOLT_X_SERIES 1144 // Z-Bolt X Series -#define BOARD_TT_OSCAR 1145 // TT OSCAR -#define BOARD_OVERLORD 1146 // Overlord/Overlord Pro -#define BOARD_HJC2560C_REV1 1147 // ADIMLab Gantry v1 -#define BOARD_HJC2560C_REV2 1148 // ADIMLab Gantry v2 -#define BOARD_TANGO 1149 // BIQU Tango V1 -#define BOARD_MKS_GEN_L_V2 1150 // MKS GEN L V2 -#define BOARD_COPYMASTER_3D 1151 // Copymaster 3D -#define BOARD_ORTUR_4 1152 // Ortur 4 -#define BOARD_TENLOG_D3_HERO 1153 // Tenlog D3 Hero IDEX printer +#define BOARD_K8800 1104 // Velleman K8800 Controller (Vertex Delta) +#define BOARD_BAM_DICE 1105 // 2PrintBeta BAM&DICE with STK drivers +#define BOARD_BAM_DICE_DUE 1106 // 2PrintBeta BAM&DICE Due with STK drivers +#define BOARD_MKS_BASE 1107 // MKS BASE v1.0 +#define BOARD_MKS_BASE_14 1108 // MKS BASE v1.4 with Allegro A4982 stepper drivers +#define BOARD_MKS_BASE_15 1109 // MKS BASE v1.5 with Allegro A4982 stepper drivers +#define BOARD_MKS_BASE_16 1110 // MKS BASE v1.6 with Allegro A4982 stepper drivers +#define BOARD_MKS_BASE_HEROIC 1111 // MKS BASE 1.0 with Heroic HR4982 stepper drivers +#define BOARD_MKS_GEN_13 1112 // MKS GEN v1.3 or 1.4 +#define BOARD_MKS_GEN_L 1113 // MKS GEN L +#define BOARD_KFB_2 1114 // BigTreeTech or BIQU KFB2.0 +#define BOARD_ZRIB_V20 1115 // zrib V2.0 control board (Chinese knock off RAMPS replica) +#define BOARD_FELIX2 1116 // Felix 2.0+ Electronics Board (RAMPS like) +#define BOARD_RIGIDBOARD 1117 // Invent-A-Part RigidBoard +#define BOARD_RIGIDBOARD_V2 1118 // Invent-A-Part RigidBoard V2 +#define BOARD_SAINSMART_2IN1 1119 // Sainsmart 2-in-1 board +#define BOARD_ULTIMAKER 1120 // Ultimaker +#define BOARD_ULTIMAKER_OLD 1121 // Ultimaker (Older electronics. Pre 1.5.4. This is rare) +#define BOARD_AZTEEG_X3 1122 // Azteeg X3 +#define BOARD_AZTEEG_X3_PRO 1123 // Azteeg X3 Pro +#define BOARD_ULTIMAIN_2 1124 // Ultimainboard 2.x (Uses TEMP_SENSOR 20) +#define BOARD_RUMBA 1125 // Rumba +#define BOARD_RUMBA_RAISE3D 1126 // Raise3D N series Rumba derivative +#define BOARD_RL200 1127 // Rapide Lite 200 (v1, low-cost RUMBA clone with drv) +#define BOARD_FORMBOT_TREX2PLUS 1128 // Formbot T-Rex 2 Plus +#define BOARD_FORMBOT_TREX3 1129 // Formbot T-Rex 3 +#define BOARD_FORMBOT_RAPTOR 1130 // Formbot Raptor +#define BOARD_FORMBOT_RAPTOR2 1131 // Formbot Raptor 2 +#define BOARD_BQ_ZUM_MEGA_3D 1132 // bq ZUM Mega 3D +#define BOARD_MAKEBOARD_MINI 1133 // MakeBoard Mini v2.1.2 is a control board sold by MicroMake +#define BOARD_TRIGORILLA_13 1134 // TriGorilla Anycubic version 1.3-based on RAMPS EFB +#define BOARD_TRIGORILLA_14 1135 // ... Ver 1.4 +#define BOARD_TRIGORILLA_14_11 1136 // ... Rev 1.1 (new servo pin order) +#define BOARD_RAMPS_ENDER_4 1137 // Creality: Ender-4, CR-8 +#define BOARD_RAMPS_CREALITY 1138 // Creality: CR10S, CR20, CR-X +#define BOARD_RAMPS_DAGOMA 1139 // Dagoma F5 +#define BOARD_FYSETC_F6_13 1140 // FYSETC F6 1.3 +#define BOARD_FYSETC_F6_14 1141 // FYSETC F6 1.4 +#define BOARD_DUPLICATOR_I3_PLUS 1142 // Wanhao Duplicator i3 Plus +#define BOARD_VORON 1143 // VORON Design +#define BOARD_TRONXY_V3_1_0 1144 // Tronxy TRONXY-V3-1.0 +#define BOARD_Z_BOLT_X_SERIES 1145 // Z-Bolt X Series +#define BOARD_TT_OSCAR 1146 // TT OSCAR +#define BOARD_OVERLORD 1147 // Overlord/Overlord Pro +#define BOARD_HJC2560C_REV1 1148 // ADIMLab Gantry v1 +#define BOARD_HJC2560C_REV2 1149 // ADIMLab Gantry v2 +#define BOARD_TANGO 1150 // BIQU Tango V1 +#define BOARD_MKS_GEN_L_V2 1151 // MKS GEN L V2 +#define BOARD_MKS_GEN_L_V21 1152 // MKS GEN L V2.1 +#define BOARD_COPYMASTER_3D 1153 // Copymaster 3D +#define BOARD_ORTUR_4 1154 // Ortur 4 +#define BOARD_TENLOG_D3_HERO 1155 // Tenlog D3 Hero IDEX printer // // RAMBo and derivatives @@ -235,6 +237,8 @@ #define BOARD_SMOOTHIEBOARD 2506 // Smoothieboard #define BOARD_TH3D_EZBOARD 2507 // TH3D EZBoard v1.0 #define BOARD_BTT_SKR_V1_4_TURBO 2508 // BigTreeTech SKR v1.4 TURBO (Power outputs: Hotend0, Hotend1, Fan, Bed) +#define BOARD_MKS_SGEN_L_V2 2509 // MKS SGEN_L V2 (Power outputs: Hotend0, Hotend1, Bed, Fan) +#define BOARD_BTT_SKR_E3_TURBO 2510 // BigTreeTech SKR E3 Turbo (Power outputs: Hotend0, Hotend1, Bed, Fan0, Fan1) // // SAM3X8E ARM Cortex M3 @@ -279,42 +283,43 @@ // STM32 ARM Cortex-M3 // -#define BOARD_STM32F103RE 4000 // STM32F103RE Libmaple-based STM32F1 controller -#define BOARD_MALYAN_M200 4001 // STM32C8T6 Libmaple-based STM32F1 controller -#define BOARD_MALYAN_M200_V2 4002 // STM32F070RB Libmaple-based STM32F0 controller -#define BOARD_STM3R_MINI 4003 // STM32F103RE Libmaple-based STM32F1 controller -#define BOARD_GTM32_PRO_VB 4004 // STM32F103VET6 controller -#define BOARD_MORPHEUS 4005 // STM32F103C8 / STM32F103CB Libmaple-based STM32F1 controller -#define BOARD_CHITU3D 4006 // Chitu3D (STM32F103RET6) -#define BOARD_MKS_ROBIN 4007 // MKS Robin (STM32F103ZET6) -#define BOARD_MKS_ROBIN_MINI 4008 // MKS Robin Mini (STM32F103VET6) -#define BOARD_MKS_ROBIN_NANO 4009 // MKS Robin Nano (STM32F103VET6) -#define BOARD_MKS_ROBIN_NANO_V2 4010 // MKS Robin Nano V2 (STM32F103VET6) -#define BOARD_MKS_ROBIN_LITE 4011 // MKS Robin Lite/Lite2 (STM32F103RCT6) -#define BOARD_MKS_ROBIN_LITE3 4012 // MKS Robin Lite3 (STM32F103RCT6) -#define BOARD_MKS_ROBIN_PRO 4013 // MKS Robin Pro (STM32F103ZET6) -#define BOARD_BTT_SKR_MINI_V1_1 4014 // BigTreeTech SKR Mini v1.1 (STM32F103RC) -#define BOARD_BTT_SKR_MINI_E3_V1_0 4015 // BigTreeTech SKR Mini E3 (STM32F103RC) -#define BOARD_BTT_SKR_MINI_E3_V1_2 4016 // BigTreeTech SKR Mini E3 V1.2 (STM32F103RC) -#define BOARD_BTT_SKR_MINI_E3_V2_0 4017 // BigTreeTech SKR Mini E3 V2.0 (STM32F103RC) -#define BOARD_BTT_SKR_E3_DIP 4018 // BigTreeTech SKR E3 DIP V1.0 (STM32F103RC / STM32F103RE) -#define BOARD_JGAURORA_A5S_A1 4019 // JGAurora A5S A1 (STM32F103ZET6) -#define BOARD_FYSETC_AIO_II 4020 // FYSETC AIO_II -#define BOARD_FYSETC_CHEETAH 4021 // FYSETC Cheetah -#define BOARD_FYSETC_CHEETAH_V12 4022 // FYSETC Cheetah V1.2 -#define BOARD_LONGER3D_LK 4023 // Alfawise U20/U20+/U30 (Longer3D LK1/2) / STM32F103VET6 -#define BOARD_GTM32_MINI 4024 // STM32F103VET6 controller -#define BOARD_GTM32_MINI_A30 4025 // STM32F103VET6 controller -#define BOARD_GTM32_REV_B 4026 // STM32F103VET6 controller -#define BOARD_MKS_ROBIN_E3D 4027 // MKS Robin E3D (STM32F103RCT6) -#define BOARD_MKS_ROBIN_E3 4028 // MKS Robin E3 (STM32F103RCT6) -#define BOARD_MALYAN_M300 4029 // STM32F070-based delta -#define BOARD_CCROBOT_MEEB_3DP 4030 // ccrobot-online.com MEEB_3DP (STM32F103RC) -#define BOARD_CHITU3D_V5 4031 // Chitu3D TronXY X5SA V5 Board -#define BOARD_CHITU3D_V6 4032 // Chitu3D TronXY X5SA V5 Board -#define BOARD_CREALITY_V4 4033 // Creality v4.x (STM32F103RE) -#define BOARD_CREALITY_V427 4034 // Creality v4.2.7 (STM32F103RE) -#define BOARD_TRIGORILLA_PRO 4035 // Trigorilla Pro (STM32F103ZET6) +#define BOARD_MALYAN_M200_V2 4000 // STM32F070CB STM32F0 controller +#define BOARD_MALYAN_M300 4001 // STM32F070-based delta +#define BOARD_STM32F103RE 4002 // STM32F103RE Libmaple-based STM32F1 controller +#define BOARD_MALYAN_M200 4003 // STM32C8T6 Libmaple-based STM32F1 controller +#define BOARD_STM3R_MINI 4004 // STM32F103RE Libmaple-based STM32F1 controller +#define BOARD_GTM32_PRO_VB 4005 // STM32F103VET6 controller +#define BOARD_GTM32_MINI 4006 // STM32F103VET6 controller +#define BOARD_GTM32_MINI_A30 4007 // STM32F103VET6 controller +#define BOARD_GTM32_REV_B 4008 // STM32F103VET6 controller +#define BOARD_MORPHEUS 4009 // STM32F103C8 / STM32F103CB Libmaple-based STM32F1 controller +#define BOARD_CHITU3D 4010 // Chitu3D (STM32F103RET6) +#define BOARD_MKS_ROBIN 4011 // MKS Robin (STM32F103ZET6) +#define BOARD_MKS_ROBIN_MINI 4012 // MKS Robin Mini (STM32F103VET6) +#define BOARD_MKS_ROBIN_NANO 4013 // MKS Robin Nano (STM32F103VET6) +#define BOARD_MKS_ROBIN_NANO_V2 4014 // MKS Robin Nano V2 (STM32F103VET6) +#define BOARD_MKS_ROBIN_LITE 4015 // MKS Robin Lite/Lite2 (STM32F103RCT6) +#define BOARD_MKS_ROBIN_LITE3 4016 // MKS Robin Lite3 (STM32F103RCT6) +#define BOARD_MKS_ROBIN_PRO 4017 // MKS Robin Pro (STM32F103ZET6) +#define BOARD_MKS_ROBIN_E3 4018 // MKS Robin E3 (STM32F103RCT6) +#define BOARD_MKS_ROBIN_E3D 4019 // MKS Robin E3D (STM32F103RCT6) +#define BOARD_MKS_ROBIN_E3P 4020 // MKS Robin E3p (STM32F103VET6) +#define BOARD_BTT_SKR_MINI_V1_1 4021 // BigTreeTech SKR Mini v1.1 (STM32F103RC) +#define BOARD_BTT_SKR_MINI_E3_V1_0 4022 // BigTreeTech SKR Mini E3 (STM32F103RC) +#define BOARD_BTT_SKR_MINI_E3_V1_2 4023 // BigTreeTech SKR Mini E3 V1.2 (STM32F103RC) +#define BOARD_BTT_SKR_MINI_E3_V2_0 4024 // BigTreeTech SKR Mini E3 V2.0 (STM32F103RC) +#define BOARD_BTT_SKR_E3_DIP 4025 // BigTreeTech SKR E3 DIP V1.0 (STM32F103RC / STM32F103RE) +#define BOARD_JGAURORA_A5S_A1 4026 // JGAurora A5S A1 (STM32F103ZET6) +#define BOARD_FYSETC_AIO_II 4027 // FYSETC AIO_II +#define BOARD_FYSETC_CHEETAH 4028 // FYSETC Cheetah +#define BOARD_FYSETC_CHEETAH_V12 4029 // FYSETC Cheetah V1.2 +#define BOARD_LONGER3D_LK 4030 // Alfawise U20/U20+/U30 (Longer3D LK1/2) / STM32F103VET6 +#define BOARD_CCROBOT_MEEB_3DP 4031 // ccrobot-online.com MEEB_3DP (STM32F103RC) +#define BOARD_CHITU3D_V5 4032 // Chitu3D TronXY X5SA V5 Board +#define BOARD_CHITU3D_V6 4033 // Chitu3D TronXY X5SA V5 Board +#define BOARD_CREALITY_V4 4034 // Creality v4.x (STM32F103RE) +#define BOARD_CREALITY_V427 4035 // Creality v4.2.7 (STM32F103RE) +#define BOARD_TRIGORILLA_PRO 4036 // Trigorilla Pro (STM32F103ZET6) // // ARM Cortex-M4F @@ -355,10 +360,13 @@ #define BOARD_THE_BORG 5000 // THE-BORG (Power outputs: Hotend0, Hotend1, Bed, Fan) #define BOARD_REMRAM_V1 5001 // RemRam v1 +#define BOARD_TEENSY41 5002 // Teensy 4.1 +#define BOARD_T41U5XBB 5003 // T41U5XBB Teensy 4.1 breakout board // // Espressif ESP32 WiFi // + #define BOARD_ESPRESSIF_ESP32 6000 // Generic ESP32 #define BOARD_MRR_ESPA 6001 // MRR ESPA board based on ESP32 (native pins only) #define BOARD_MRR_ESPE 6002 // MRR ESPE board based on ESP32 (with I2S stepper stream) @@ -367,11 +375,13 @@ // // SAMD51 ARM Cortex M4 // + #define BOARD_AGCM4_RAMPS_144 6100 // RAMPS 1.4.4 // // Custom board // + #define BOARD_CUSTOM 9998 // Custom pins definition for development and/or rare boards // diff --git a/Marlin/src/core/language.h b/Marlin/src/core/language.h index f0ddbdd6d0..a644ab2fc8 100644 --- a/Marlin/src/core/language.h +++ b/Marlin/src/core/language.h @@ -108,8 +108,6 @@ #define STR_BROWNOUT_RESET " Brown out Reset" #define STR_WATCHDOG_RESET " Watchdog Reset" #define STR_SOFTWARE_RESET " Software Reset" -#define STR_AUTHOR " | Author: " -#define STR_CONFIGURATION_VER " Last Updated: " #define STR_FREE_MEMORY " Free Memory: " #define STR_PLANNER_BUFFER_BYTES " PlannerBufferBytes: " #define STR_OK "ok" @@ -120,13 +118,13 @@ #define STR_ERR_CHECKSUM_MISMATCH "checksum mismatch, Last Line: " #define STR_ERR_NO_CHECKSUM "No Checksum with line number, Last Line: " #define STR_FILE_PRINTED "Done printing file" +#define STR_NO_MEDIA "No media" #define STR_BEGIN_FILE_LIST "Begin file list" #define STR_END_FILE_LIST "End file list" #define STR_INVALID_EXTRUDER "Invalid extruder" #define STR_INVALID_E_STEPPER "Invalid E stepper" #define STR_E_STEPPER_NOT_SPECIFIED "E stepper not specified" #define STR_INVALID_SOLENOID "Invalid solenoid" -#define STR_M115_REPORT "FIRMWARE_NAME:Marlin " DETAILED_BUILD_VERSION " (" __DATE__ " " __TIME__ ") SOURCE_CODE_URL:" SOURCE_CODE_URL " PROTOCOL_VERSION:" PROTOCOL_VERSION " MACHINE_TYPE:" MACHINE_NAME " EXTRUDER_COUNT:" STRINGIFY(EXTRUDERS) " UUID:" MACHINE_UUID #define STR_COUNT_X " Count X:" #define STR_COUNT_A " Count A:" #define STR_WATCHDOG_FIRED "Watchdog timeout. Reset required." @@ -305,7 +303,7 @@ #define LCD_STR_C STR_C #define LCD_STR_E STR_E -#if HAS_CHARACTER_LCD +#if HAS_MARLINUI_HD44780 // Custom characters defined in the first 8 characters of the LCD #define LCD_STR_BEDTEMP "\x00" // Print only as a char. This will have 'unexpected' results when used in a string! @@ -350,7 +348,6 @@ * However, internal to Marlin E0/T0 is the first tool, and * most board silkscreens say "E0." Zero-based labels will * make these indexes consistent but this defies expectation. - * */ #if ENABLED(NUMBER_TOOLS_FROM_0) #define LCD_FIRST_TOOL 0 diff --git a/Marlin/src/core/utility.cpp b/Marlin/src/core/utility.cpp index 295657fa64..f999568167 100644 --- a/Marlin/src/core/utility.cpp +++ b/Marlin/src/core/utility.cpp @@ -57,10 +57,11 @@ void safe_delay(millis_t ms) { void log_machine_info() { SERIAL_ECHOLNPGM("Machine Type: " - TERN_(DELTA, "Delta") - TERN_(IS_SCARA, "SCARA") - TERN_(IS_CORE, "Core") - TERN_(IS_CARTESIAN, "Cartesian") + TERN_(DELTA, "Delta") + TERN_(IS_SCARA, "SCARA") + TERN_(IS_CORE, "Core") + TERN_(MARKFORGED_XY, "MarkForged") + TERN_(IS_CARTESIAN, "Cartesian") ); SERIAL_ECHOLNPGM("Probe: " diff --git a/Marlin/src/feature/bedlevel/ubl/ubl.cpp b/Marlin/src/feature/bedlevel/ubl/ubl.cpp index 809caecf49..087fdf42b2 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl.cpp @@ -48,7 +48,7 @@ void unified_bed_leveling::report_current_mesh() { if (!leveling_is_valid()) return; - SERIAL_ECHO_MSG(" G29 I99"); + SERIAL_ECHO_MSG(" G29 I999"); GRID_LOOP(x, y) if (!isnan(z_values[x][y])) { SERIAL_ECHO_START(); diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index d13a8c3dc4..dc91b7d6b1 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -736,6 +736,7 @@ uint8_t count = GRID_MAX_POINTS; mesh_index_pair best; + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(best.pos, ExtUI::MESH_START)); do { if (do_ubl_mesh_map) display_map(g29_map_type); @@ -775,6 +776,8 @@ } while (best.pos.x >= 0 && --count); + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(best.pos, ExtUI::MESH_FINISH)); + // Release UI during stow to allow for PAUSE_BEFORE_DEPLOY_STOW TERN_(HAS_LCD_MENU, ui.release()); probe.stow(); @@ -994,6 +997,10 @@ if (do_ubl_mesh_map) display_map(g29_map_type); // Display the current point + #if IS_TFTGLCD_PANEL + ui.ubl_plot(lpos.x, lpos.y); // update plot screen + #endif + ui.refresh(); float new_z = z_values[lpos.x][lpos.y]; diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp index 63559e0bb8..010b5951be 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp @@ -236,9 +236,7 @@ } /** - * * Generic case of a line crossing both X and Y Mesh lines. - * */ xy_int8_t cnt = (istart - iend).ABS(); diff --git a/Marlin/src/feature/binary_stream.h b/Marlin/src/feature/binary_stream.h index 10dea10d47..32ebcce2f6 100644 --- a/Marlin/src/feature/binary_stream.h +++ b/Marlin/src/feature/binary_stream.h @@ -441,9 +441,9 @@ public: } void dispatch() { - switch(static_cast(packet.header.protocol())) { + switch (static_cast(packet.header.protocol())) { case Protocol::CONTROL: - switch(static_cast(packet.header.type())) { + switch (static_cast(packet.header.type())) { case ProtocolControl::CLOSE: // revert back to ASCII mode card.flag.binary_mode = false; break; diff --git a/Marlin/src/feature/dac/dac_dac084s085.cpp b/Marlin/src/feature/dac/dac_dac084s085.cpp index a07dc071dd..82d17fa28f 100644 --- a/Marlin/src/feature/dac/dac_dac084s085.cpp +++ b/Marlin/src/feature/dac/dac_dac084s085.cpp @@ -21,7 +21,7 @@ void dac084s085::begin() { // All SPI chip-select HIGH SET_OUTPUT(DAC0_SYNC); - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER SET_OUTPUT(DAC1_SYNC); #endif cshigh(); @@ -38,7 +38,7 @@ void dac084s085::begin() { spiSend(SPI_CHAN_DAC, externalDac_buf, COUNT(externalDac_buf)); WRITE(DAC0_SYNC, HIGH); - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER //init Piggy DAC DELAY_US(2); WRITE(DAC1_SYNC, LOW); @@ -86,7 +86,7 @@ void dac084s085::setValue(const uint8_t channel, const uint8_t value) { void dac084s085::cshigh() { WRITE(DAC0_SYNC, HIGH); - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER WRITE(DAC1_SYNC, HIGH); #endif WRITE(SPI_EEPROM1_CS, HIGH); diff --git a/Marlin/src/feature/encoder_i2c.cpp b/Marlin/src/feature/encoder_i2c.cpp index f67d50a6e0..8a3e959e07 100644 --- a/Marlin/src/feature/encoder_i2c.cpp +++ b/Marlin/src/feature/encoder_i2c.cpp @@ -816,7 +816,6 @@ int8_t I2CPositionEncodersMgr::parse() { * Y Report on Y axis encoder, if present. * Z Report on Z axis encoder, if present. * E Report on E axis encoder, if present. - * */ void I2CPositionEncodersMgr::M860() { if (parse()) return; @@ -846,7 +845,6 @@ void I2CPositionEncodersMgr::M860() { * Y Report on Y axis encoder, if present. * Z Report on Z axis encoder, if present. * E Report on E axis encoder, if present. - * */ void I2CPositionEncodersMgr::M861() { if (parse()) return; @@ -875,7 +873,6 @@ void I2CPositionEncodersMgr::M861() { * Y Report on Y axis encoder, if present. * Z Report on Z axis encoder, if present. * E Report on E axis encoder, if present. - * */ void I2CPositionEncodersMgr::M862() { if (parse()) return; @@ -905,7 +902,6 @@ void I2CPositionEncodersMgr::M862() { * Y Report on Y axis encoder, if present. * Z Report on Z axis encoder, if present. * E Report on E axis encoder, if present. - * */ void I2CPositionEncodersMgr::M863() { if (parse()) return; diff --git a/Marlin/src/feature/fwretract.cpp b/Marlin/src/feature/fwretract.cpp index c0e4db0a45..e5c52562a9 100644 --- a/Marlin/src/feature/fwretract.cpp +++ b/Marlin/src/feature/fwretract.cpp @@ -42,7 +42,7 @@ FWRetract fwretract; // Single instance - this calls the constructor // private: -#if EXTRUDERS > 1 +#if HAS_MULTI_EXTRUDER bool FWRetract::retracted_swap[EXTRUDERS]; // Which extruders are swap-retracted #endif @@ -73,9 +73,7 @@ void FWRetract::reset() { LOOP_L_N(i, EXTRUDERS) { retracted[i] = false; - #if EXTRUDERS > 1 - retracted_swap[i] = false; - #endif + TERN_(HAS_MULTI_EXTRUDER, retracted_swap[i] = false); current_retract[i] = 0.0; } } @@ -92,7 +90,7 @@ void FWRetract::reset() { * included in the G-code. Use M207 Z0 to to prevent double hop. */ void FWRetract::retract(const bool retracting - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER , bool swapping/*=false*/ #endif ) { @@ -100,7 +98,7 @@ void FWRetract::retract(const bool retracting if (retracted[active_extruder] == retracting) return; // Prevent two swap-retract or recovers in a row - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER // Allow G10 S1 only after G11 if (swapping && retracted_swap[active_extruder] == retracting) return; // G11 priority to recover the long retract if activated @@ -117,7 +115,7 @@ void FWRetract::retract(const bool retracting ); LOOP_L_N(i, EXTRUDERS) { SERIAL_ECHOLNPAIR("retracted[", i, "] ", retracted[i]); - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER SERIAL_ECHOLNPAIR("retracted_swap[", i, "] ", retracted_swap[i]); #endif } @@ -180,7 +178,7 @@ void FWRetract::retract(const bool retracting retracted[active_extruder] = retracting; // Active extruder now retracted / recovered // If swap retract/recover update the retracted_swap flag too - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER if (swapping) retracted_swap[active_extruder] = retracting; #endif @@ -190,7 +188,7 @@ void FWRetract::retract(const bool retracting SERIAL_ECHOLNPAIR("active_extruder ", active_extruder); LOOP_L_N(i, EXTRUDERS) { SERIAL_ECHOLNPAIR("retracted[", i, "] ", retracted[i]); - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER SERIAL_ECHOLNPAIR("retracted_swap[", i, "] ", retracted_swap[i]); #endif } diff --git a/Marlin/src/feature/fwretract.h b/Marlin/src/feature/fwretract.h index 3d68736429..134851965d 100644 --- a/Marlin/src/feature/fwretract.h +++ b/Marlin/src/feature/fwretract.h @@ -42,7 +42,7 @@ typedef struct { class FWRetract { private: - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER static bool retracted_swap[EXTRUDERS]; // Which extruders are swap-retracted #endif @@ -75,7 +75,7 @@ public: } static void retract(const bool retracting - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER , bool swapping = false #endif ); diff --git a/Marlin/src/feature/host_actions.cpp b/Marlin/src/feature/host_actions.cpp index 9539c82b64..3012639220 100644 --- a/Marlin/src/feature/host_actions.cpp +++ b/Marlin/src/feature/host_actions.cpp @@ -62,6 +62,9 @@ void host_action(PGM_P const pstr, const bool eol) { #ifdef ACTION_ON_CANCEL void host_action_cancel() { host_action(PSTR(ACTION_ON_CANCEL)); } #endif +#ifdef ACTION_ON_START + void host_action_start() { host_action(PSTR(ACTION_ON_START)); } +#endif #if ENABLED(HOST_PROMPT_SUPPORT) diff --git a/Marlin/src/feature/host_actions.h b/Marlin/src/feature/host_actions.h index a6ad2c0485..09eeed23e2 100644 --- a/Marlin/src/feature/host_actions.h +++ b/Marlin/src/feature/host_actions.h @@ -44,6 +44,9 @@ void host_action(PGM_P const pstr, const bool eol=true); #ifdef ACTION_ON_CANCEL void host_action_cancel(); #endif +#ifdef ACTION_ON_START + void host_action_start(); +#endif #if ENABLED(HOST_PROMPT_SUPPORT) diff --git a/Marlin/src/feature/joystick.h b/Marlin/src/feature/joystick.h index ca46834578..1d25a30cc2 100644 --- a/Marlin/src/feature/joystick.h +++ b/Marlin/src/feature/joystick.h @@ -30,8 +30,6 @@ #include "../core/macros.h" #include "../module/temperature.h" -//#define JOYSTICK_DEBUG - class Joystick { friend class Temperature; private: diff --git a/Marlin/src/feature/leds/leds.cpp b/Marlin/src/feature/leds/leds.cpp index 01bca80926..ef9099fb20 100644 --- a/Marlin/src/feature/leds/leds.cpp +++ b/Marlin/src/feature/leds/leds.cpp @@ -183,8 +183,18 @@ void LEDLights::set_color(const LEDColor &incol : neo2.Color(incol.r, incol.g, incol.b, incol.w); neo2.set_brightness(incol.i); neo2.set_color(neocolor); + + #if ENABLED(LED_CONTROL_MENU) + // Don't update the color when OFF + lights_on = !incol.is_off(); + if (lights_on) color = incol; + #endif } + #if ENABLED(LED_CONTROL_MENU) + void LEDLights2::toggle() { if (lights_on) set_off(); else update(); } + #endif + #endif // NEOPIXEL2_SEPARATE #endif // HAS_COLOR_LEDS diff --git a/Marlin/src/feature/leds/leds.h b/Marlin/src/feature/leds/leds.h index a13f960a3b..055ea0df37 100644 --- a/Marlin/src/feature/leds/leds.h +++ b/Marlin/src/feature/leds/leds.h @@ -240,7 +240,7 @@ extern LEDLights leds; static inline void set_violet() { set_color(LEDColorViolet()); } #endif - #if ENABLED(LED_CONTROL_MENU) + #if ENABLED(NEOPIXEL2_SEPARATE) static LEDColor color; // last non-off color static bool lights_on; // the last set color was "on" static void toggle(); // swap "off" with color diff --git a/Marlin/src/feature/leds/neopixel.h b/Marlin/src/feature/leds/neopixel.h index 81a0a8b1c6..42046fa563 100644 --- a/Marlin/src/feature/leds/neopixel.h +++ b/Marlin/src/feature/leds/neopixel.h @@ -110,7 +110,7 @@ public: #if CONJOINED_NEOPIXEL adaneo2.show(); #else - adaneo1.setPin(NEOPIXEL2_PIN); + TERN(NEOPIXEL2_SEPARATE,,adaneo1.setPin(NEOPIXEL2_PIN)); adaneo1.show(); adaneo1.setPin(NEOPIXEL_PIN); #endif @@ -133,7 +133,7 @@ extern Marlin_NeoPixel neo; // Neo pixel channel 2 #if ENABLED(NEOPIXEL2_SEPARATE) - + #if NEOPIXEL2_TYPE == NEO_RGB || NEOPIXEL2_TYPE == NEO_RBG || NEOPIXEL2_TYPE == NEO_GRB || NEOPIXEL2_TYPE == NEO_GBR || NEOPIXEL2_TYPE == NEO_BRG || NEOPIXEL2_TYPE == NEO_BGR #define NEOPIXEL2_IS_RGB 1 #else @@ -161,7 +161,10 @@ extern Marlin_NeoPixel neo; static inline void begin() { adaneo.begin(); } static inline void set_pixel_color(const uint16_t n, const uint32_t c) { adaneo.setPixelColor(n, c); } static inline void set_brightness(const uint8_t b) { adaneo.setBrightness(b); } - static inline void show() { adaneo.show(); } + static inline void show() { + adaneo.show(); + adaneo.setPin(NEOPIXEL2_PIN); + } // Accessors static inline uint16_t pixels() { return adaneo.numPixels();} diff --git a/Marlin/src/feature/mixing.cpp b/Marlin/src/feature/mixing.cpp index 7de4eb79ea..b002e9808a 100644 --- a/Marlin/src/feature/mixing.cpp +++ b/Marlin/src/feature/mixing.cpp @@ -180,7 +180,12 @@ void Mixer::refresh_collector(const float proportion/*=1.0*/, const uint8_t t/*= } void Mixer::update_gradient_for_planner_z() { - update_gradient_for_z(planner.get_axis_position_mm(Z_AXIS)); + #if ENABLED(DELTA) + get_cartesian_from_steppers(); + update_gradient_for_z(cartes.z); + #else + update_gradient_for_z(planner.get_axis_position_mm(Z_AXIS)); + #endif } #endif // GRADIENT_MIX diff --git a/Marlin/src/feature/mmu2/mmu2.cpp b/Marlin/src/feature/mmu2/mmu2.cpp index 35f2db45a9..37a2404c33 100644 --- a/Marlin/src/feature/mmu2/mmu2.cpp +++ b/Marlin/src/feature/mmu2/mmu2.cpp @@ -54,6 +54,8 @@ MMU2 mmu2; #define MMU_CMD_TIMEOUT 45000UL // 45s timeout for mmu commands (except P0) #define MMU_P0_TIMEOUT 3000UL // Timeout for P0 command: 3seconds +#define MMU2_COMMAND(S) tx_str_P(PSTR(S "\n")) + #if ENABLED(MMU_EXTRUDER_SENSOR) uint8_t mmu_idl_sens = 0; static bool mmu_loading_flag = false; @@ -152,7 +154,7 @@ void MMU2::reset() { safe_delay(20); WRITE(MMU2_RST_PIN, HIGH); #else - tx_str_P(PSTR("X0\n")); // Send soft reset + MMU2_COMMAND("X0"); // Send soft reset #endif } @@ -175,9 +177,7 @@ void MMU2::mmu_loop() { DEBUG_ECHOLNPGM("MMU => 'start'"); DEBUG_ECHOLNPGM("MMU <= 'S1'"); - // send "read version" request - tx_str_P(PSTR("S1\n")); - + MMU2_COMMAND("S1"); // Read Version state = -2; } else if (millis() > 3000000) { @@ -192,7 +192,7 @@ void MMU2::mmu_loop() { DEBUG_ECHOLNPAIR("MMU => ", version, "\nMMU <= 'S2'"); - tx_str_P(PSTR("S2\n")); // read build number + MMU2_COMMAND("S2"); // Read Build Number state = -3; } break; @@ -208,13 +208,13 @@ void MMU2::mmu_loop() { #if ENABLED(MMU2_MODE_12V) DEBUG_ECHOLNPGM("MMU <= 'M1'"); - tx_str_P(PSTR("M1\n")); // switch to stealth mode + MMU2_COMMAND("M1"); // Stealth Mode state = -5; #else DEBUG_ECHOLNPGM("MMU <= 'P0'"); - tx_str_P(PSTR("P0\n")); // read finda + MMU2_COMMAND("P0"); // Read FINDA state = -4; #endif } @@ -228,7 +228,7 @@ void MMU2::mmu_loop() { DEBUG_ECHOLNPGM("MMU <= 'P0'"); - tx_str_P(PSTR("P0\n")); // read finda + MMU2_COMMAND("P0"); // Read FINDA state = -4; } break; @@ -266,14 +266,14 @@ void MMU2::mmu_loop() { else if (cmd == MMU_CMD_C0) { // continue loading DEBUG_ECHOLNPGM("MMU <= 'C0'"); - tx_str_P(PSTR("C0\n")); + MMU2_COMMAND("C0"); state = 3; // wait for response } else if (cmd == MMU_CMD_U0) { // unload current DEBUG_ECHOLNPGM("MMU <= 'U0'"); - tx_str_P(PSTR("U0\n")); + MMU2_COMMAND("U0"); state = 3; // wait for response } else if (WITHIN(cmd, MMU_CMD_E0, MMU_CMD_E4)) { @@ -286,7 +286,7 @@ void MMU2::mmu_loop() { else if (cmd == MMU_CMD_R0) { // recover after eject DEBUG_ECHOLNPGM("MMU <= 'R0'"); - tx_str_P(PSTR("R0\n")); + MMU2_COMMAND("R0"); state = 3; // wait for response } else if (WITHIN(cmd, MMU_CMD_F0, MMU_CMD_F4)) { @@ -303,8 +303,7 @@ void MMU2::mmu_loop() { cmd = MMU_CMD_NONE; } else if (ELAPSED(millis(), prev_P0_request + 300)) { - // read FINDA - tx_str_P(PSTR("P0\n")); + MMU2_COMMAND("P0"); // Read FINDA state = 2; // wait for response } @@ -332,19 +331,32 @@ void MMU2::mmu_loop() { #if ENABLED(MMU_EXTRUDER_SENSOR) if (mmu_idl_sens) { if (FILAMENT_PRESENT() && mmu_loading_flag) { - DEBUG_ECHOLNPGM("MMU <= 'A'\n"); - tx_str_P(PSTR("A\n")); // send 'abort' request + DEBUG_ECHOLNPGM("MMU <= 'A'"); + MMU2_COMMAND("A"); // send 'abort' request mmu_idl_sens = 0; - DEBUG_ECHOLNPGM("MMU IDLER_SENSOR = 0 - ABORT\n"); + DEBUG_ECHOLNPGM("MMU IDLER_SENSOR = 0 - ABORT"); } } #endif if (rx_ok()) { - DEBUG_ECHOLNPGM("MMU => 'ok'"); - ready = true; - state = 1; - last_cmd = MMU_CMD_NONE; + // response to C0 mmu command in PRUSA_MMU2_S_MODE + bool can_reset = true; + if (ENABLED(PRUSA_MMU2_S_MODE) && last_cmd == MMU_CMD_C0) { + if (!mmu2s_triggered) { + can_reset = false; + // MMU ok received but filament sensor not triggered, retrying... + DEBUG_ECHOLNPGM("MMU => 'ok' (filament not present in gears)"); + DEBUG_ECHOLNPGM("MMU <= 'C0' (keep trying)"); + MMU2_COMMAND("C0"); + } + } + if (can_reset) { + DEBUG_ECHOLNPGM("MMU => 'ok'"); + ready = true; + state = 1; + last_cmd = MMU_CMD_NONE; + } } else if (ELAPSED(millis(), prev_request + MMU_CMD_TIMEOUT)) { // resend request after timeout @@ -698,13 +710,11 @@ void MMU2::tool_change(const uint8_t index) { } /** - * * Handle special T?/Tx/Tc commands * * T? Gcode to extrude shouldn't have to follow, load to extruder wheels is done automatically * Tx Same as T?, except nozzle doesn't have to be preheated. Tc must be placed after extruder nozzle is preheated to finish filament load. * Tc Load to nozzle after filament was prepared by Tx and extruder nozzle is already heated. - * */ void MMU2::tool_change(const char* special) { if (!enabled) return; @@ -826,8 +836,7 @@ void MMU2::manage_response(const bool move_axes, const bool turn_off_nozzle) { if (move_axes && all_axes_homed()) { LCD_MESSAGEPGM(MSG_MMU2_RESUMING); - BUZZ(200, 404); - BUZZ(200, 404); + BUZZ(198, 404); BUZZ(4, 0); BUZZ(198, 404); // Move XY to starting position, then Z do_blocking_move_to_xy(resume_position, feedRate_t(NOZZLE_PARK_XY_FEEDRATE)); @@ -836,8 +845,7 @@ void MMU2::manage_response(const bool move_axes, const bool turn_off_nozzle) { do_blocking_move_to_z(resume_position.z, feedRate_t(NOZZLE_PARK_Z_FEEDRATE)); } else { - BUZZ(200, 404); - BUZZ(200, 404); + BUZZ(198, 404); BUZZ(4, 0); BUZZ(198, 404); LCD_MESSAGEPGM(MSG_MMU2_RESUMING); } } @@ -862,9 +870,18 @@ void MMU2::filament_runout() { void MMU2::check_filament() { const bool present = FILAMENT_PRESENT(); - if (present && !mmu2s_triggered) { - DEBUG_ECHOLNPGM("MMU <= 'A'"); - tx_str_P(PSTR("A\n")); + if (cmd == MMU_CMD_NONE && last_cmd == MMU_CMD_C0) { + if (present && !mmu2s_triggered) { + DEBUG_ECHOLNPGM("MMU <= 'A'"); + tx_str_P(PSTR("A\n")); + } + // Slowly spin the extruder during C0 + else { + while (planner.movesplanned() < 3) { + current_position.e += 0.25; + line_to_current_position(MMM_TO_MMS(120)); + } + } } mmu2s_triggered = present; } @@ -903,9 +920,7 @@ void MMU2::filament_runout() { } /** - * * Switch material and load to nozzle - * */ bool MMU2::load_filament_to_nozzle(const uint8_t index) { diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index a7ed93425c..f8a7d83260 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -29,6 +29,8 @@ #if ENABLED(ADVANCED_PAUSE_FEATURE) +//#define DEBUG_PAUSE_RESUME + #include "../MarlinCore.h" #include "../gcode/gcode.h" #include "../module/motion.h" @@ -62,6 +64,9 @@ #include "../libs/nozzle.h" #include "pause.h" +#define DEBUG_OUT ENABLED(DEBUG_PAUSE_RESUME) +#include "../core/debug_out.h" + // private: static xyze_pos_t resume_position; @@ -120,25 +125,32 @@ fil_change_settings_t fc_settings[EXTRUDERS]; * Returns 'true' if heating was completed, 'false' for abort */ static bool ensure_safe_temperature(const bool wait=true, const PauseMode mode=PAUSE_MODE_SAME) { + DEBUG_SECTION(est, "ensure_safe_temperature", true); + DEBUG_ECHOLNPAIR("... wait:", int(wait), " mode:", int(mode)); - #if ENABLED(PREVENT_COLD_EXTRUSION) - if (!DEBUGGING(DRYRUN) && thermalManager.targetTooColdToExtrude(active_extruder)) { - SERIAL_ECHO_MSG(STR_ERR_HOTEND_TOO_COLD); - return false; - } - #endif + if (!DEBUGGING(DRYRUN) && thermalManager.targetTooColdToExtrude(active_extruder)) + thermalManager.setTargetHotend(thermalManager.extrude_min_temp, active_extruder); #if HAS_LCD_MENU lcd_pause_show_message(PAUSE_MESSAGE_HEATING, mode); - #else - UNUSED(mode); #endif + UNUSED(mode); if (wait) return thermalManager.wait_for_hotend(active_extruder); - while (ABS(thermalManager.degHotend(active_extruder) - thermalManager.degTargetHotend(active_extruder)) > TEMP_WINDOW) + wait_for_heatup = true; // Allow interruption by Emergency Parser M108 + while (wait_for_heatup && ABS(thermalManager.degHotend(active_extruder) - thermalManager.degTargetHotend(active_extruder)) > TEMP_WINDOW) idle(); + wait_for_heatup = false; + + #if ENABLED(PREVENT_COLD_EXTRUSION) + // A user can cancel wait-for-heating with M108 + if (!DEBUGGING(DRYRUN) && thermalManager.targetTooColdToExtrude(active_extruder)) { + SERIAL_ECHO_MSG(STR_ERR_HOTEND_TOO_COLD); + return false; + } + #endif return true; } @@ -160,7 +172,10 @@ bool load_filament(const float &slow_load_length/*=0*/, const float &fast_load_l const PauseMode mode/*=PAUSE_MODE_PAUSE_PRINT*/ DXC_ARGS ) { - TERN(HAS_LCD_MENU,,UNUSED(show_lcd)); + DEBUG_SECTION(lf, "load_filament", true); + DEBUG_ECHOLNPAIR("... slowlen:", slow_load_length, " fastlen:", fast_load_length, " purgelen:", purge_length, " maxbeep:", int(max_beep_count), " showlcd:", int(show_lcd), " pauseforuser:", int(pause_for_user), " pausemode:", int(mode) DXC_SAY); + + UNUSED(show_lcd); if (!ensure_safe_temperature(false, mode)) { #if HAS_LCD_MENU @@ -292,7 +307,14 @@ bool unload_filament(const float &unload_length, const bool show_lcd/*=false*/, , const float &mix_multiplier/*=1.0*/ #endif ) { - TERN(HAS_LCD_MENU,,UNUSED(show_lcd)); + DEBUG_SECTION(uf, "unload_filament", true); + DEBUG_ECHOLNPAIR("... unloadlen:", unload_length, " showlcd:", int(show_lcd), " mode:", int(mode) + #if BOTH(FILAMENT_UNLOAD_ALL_EXTRUDERS, MIXING_EXTRUDER) + , " mixmult:", mix_multiplier + #endif + ); + + UNUSED(show_lcd); #if !BOTH(FILAMENT_UNLOAD_ALL_EXTRUDERS, MIXING_EXTRUDER) constexpr float mix_multiplier = 1.0; @@ -358,7 +380,10 @@ bool unload_filament(const float &unload_length, const bool show_lcd/*=false*/, uint8_t did_pause_print = 0; bool pause_print(const float &retract, const xyz_pos_t &park_point, const float &unload_length/*=0*/, const bool show_lcd/*=false*/ DXC_ARGS) { - TERN(HAS_LCD_MENU,,UNUSED(show_lcd)); + DEBUG_SECTION(pp, "pause_print", true); + DEBUG_ECHOLNPAIR("... park.x:", park_point.x, " y:", park_point.y, " z:", park_point.z, " unloadlen:", unload_length, " showlcd:", int(show_lcd) DXC_SAY); + + UNUSED(show_lcd); if (did_pause_print) return false; // already paused @@ -372,19 +397,6 @@ bool pause_print(const float &retract, const xyz_pos_t &park_point, const float TERN_(HOST_PROMPT_SUPPORT, host_prompt_open(PROMPT_INFO, PSTR("Pause"), DISMISS_STR)); - if (!DEBUGGING(DRYRUN) && unload_length && thermalManager.targetTooColdToExtrude(active_extruder)) { - SERIAL_ECHO_MSG(STR_ERR_HOTEND_TOO_COLD); - - #if HAS_LCD_MENU - if (show_lcd) { // Show status screen - lcd_pause_show_message(PAUSE_MESSAGE_STATUS); - LCD_MESSAGEPGM(MSG_M600_TOO_COLD); - } - #endif - - return false; // unable to reach safe temperature - } - // Indicate that the printer is paused ++did_pause_print; @@ -409,8 +421,10 @@ bool pause_print(const float &retract, const xyz_pos_t &park_point, const float #endif // Initial retract before move to filament change position - if (retract && thermalManager.hotEnoughToExtrude(active_extruder)) + if (retract && thermalManager.hotEnoughToExtrude(active_extruder)) { + DEBUG_ECHOLNPAIR("... retract:", retract); unscaled_e_move(retract, PAUSE_PARK_RETRACT_FEEDRATE); + } // Park the nozzle by moving up by z_lift and then moving to (x_pos, y_pos) if (!axes_should_home()) @@ -449,12 +463,18 @@ bool pause_print(const float &retract, const xyz_pos_t &park_point, const float */ void show_continue_prompt(const bool is_reload) { + DEBUG_SECTION(scp, "pause_print", true); + DEBUG_ECHOLNPAIR("... is_reload:", int(is_reload)); + TERN_(HAS_LCD_MENU, lcd_pause_show_message(is_reload ? PAUSE_MESSAGE_INSERT : PAUSE_MESSAGE_WAITING)); SERIAL_ECHO_START(); serialprintPGM(is_reload ? PSTR(_PMSG(STR_FILAMENT_CHANGE_INSERT) "\n") : PSTR(_PMSG(STR_FILAMENT_CHANGE_WAIT) "\n")); } void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep_count/*=0*/ DXC_ARGS) { + DEBUG_SECTION(wfc, "wait_for_confirmation", true); + DEBUG_ECHOLNPAIR("... is_reload:", is_reload, " maxbeep:", int(max_beep_count) DXC_SAY); + bool nozzle_timed_out = false; show_continue_prompt(is_reload); @@ -464,7 +484,7 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep // Start the heater idle timers const millis_t nozzle_timeout = SEC_TO_MS(PAUSE_PARK_NOZZLE_TIMEOUT); - HOTEND_LOOP() thermalManager.hotend_idle[e].start(nozzle_timeout); + HOTEND_LOOP() thermalManager.heater_idle[e].start(nozzle_timeout); #if ENABLED(DUAL_X_CARRIAGE) const int8_t saved_ext = active_extruder; @@ -483,7 +503,7 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep // If the nozzle has timed out... if (!nozzle_timed_out) - HOTEND_LOOP() nozzle_timed_out |= thermalManager.hotend_idle[e].timed_out; + HOTEND_LOOP() nozzle_timed_out |= thermalManager.heater_idle[e].timed_out; // Wait for the user to press the button to re-heat the nozzle, then // re-heat the nozzle, re-show the continue prompt, restart idle timers, start over @@ -513,7 +533,7 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep // Start the heater idle timers const millis_t nozzle_timeout = SEC_TO_MS(PAUSE_PARK_NOZZLE_TIMEOUT); - HOTEND_LOOP() thermalManager.hotend_idle[e].start(nozzle_timeout); + HOTEND_LOOP() thermalManager.heater_idle[e].start(nozzle_timeout); TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Reheat Done"), CONTINUE_STR)); TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(PSTR("Reheat finished."))); wait_for_user = true; @@ -551,6 +571,9 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep * - Resume the current SD print job, if any */ void resume_print(const float &slow_load_length/*=0*/, const float &fast_load_length/*=0*/, const float &purge_length/*=ADVANCED_PAUSE_PURGE_LENGTH*/, const int8_t max_beep_count/*=0*/, int16_t targetTemp/*=0*/ DXC_ARGS) { + DEBUG_SECTION(rp, "resume_print", true); + DEBUG_ECHOLNPAIR("... slowlen:", slow_load_length, " fastlen:", fast_load_length, " purgelen:", purge_length, " maxbeep:", int(max_beep_count), " targetTemp:", targetTemp DXC_SAY); + /* SERIAL_ECHOLNPAIR( "start of resume_print()\ndual_x_carriage_mode:", dual_x_carriage_mode, @@ -565,15 +588,16 @@ void resume_print(const float &slow_load_length/*=0*/, const float &fast_load_le // Re-enable the heaters if they timed out bool nozzle_timed_out = false; HOTEND_LOOP() { - nozzle_timed_out |= thermalManager.hotend_idle[e].timed_out; + nozzle_timed_out |= thermalManager.heater_idle[e].timed_out; thermalManager.reset_hotend_idle_timer(e); } - if (targetTemp > thermalManager.degTargetHotend(active_extruder)) + if (targetTemp > thermalManager.degTargetHotend(active_extruder)) { thermalManager.setTargetHotend(targetTemp, active_extruder); + } - if (nozzle_timed_out || thermalManager.hotEnoughToExtrude(active_extruder)) // Load the new filament - load_filament(slow_load_length, fast_load_length, purge_length, max_beep_count, true, nozzle_timed_out, PAUSE_MODE_SAME DXC_PASS); + // Load the new filament + load_filament(slow_load_length, fast_load_length, purge_length, max_beep_count, true, nozzle_timed_out, PAUSE_MODE_SAME DXC_PASS); if (targetTemp > 0) { thermalManager.setTargetHotend(targetTemp, active_extruder); diff --git a/Marlin/src/feature/pause.h b/Marlin/src/feature/pause.h index d8a676afa4..016b0ce3f7 100644 --- a/Marlin/src/feature/pause.h +++ b/Marlin/src/feature/pause.h @@ -77,10 +77,12 @@ extern uint8_t did_pause_print; #define DXC_PARAMS , const int8_t DXC_ext=-1 #define DXC_ARGS , const int8_t DXC_ext #define DXC_PASS , DXC_ext + #define DXC_SAY , " dxc:", int(DXC_ext) #else #define DXC_PARAMS #define DXC_ARGS #define DXC_PASS + #define DXC_SAY #endif bool pause_print(const float &retract, const xyz_pos_t &park_point, const float &unload_length=0, const bool show_lcd=false DXC_PARAMS); diff --git a/Marlin/src/feature/power_monitor.cpp b/Marlin/src/feature/power_monitor.cpp index bf5ac748a8..af31d156fc 100644 --- a/Marlin/src/feature/power_monitor.cpp +++ b/Marlin/src/feature/power_monitor.cpp @@ -44,7 +44,7 @@ uint8_t PowerMonitor::display_item; PowerMonitor power_monitor; // Single instance - this calls the constructor -#if HAS_GRAPHICAL_LCD +#if HAS_MARLINUI_U8GLIB #if ENABLED(POWER_MONITOR_CURRENT) void PowerMonitor::draw_current() { @@ -70,6 +70,6 @@ PowerMonitor power_monitor; // Single instance - this calls the constructor } #endif -#endif // HAS_GRAPHICAL_LCD +#endif // HAS_MARLINUI_U8GLIB #endif // HAS_POWER_MONITOR diff --git a/Marlin/src/feature/power_monitor.h b/Marlin/src/feature/power_monitor.h index ca52ed74c6..a0eaf353f4 100644 --- a/Marlin/src/feature/power_monitor.h +++ b/Marlin/src/feature/power_monitor.h @@ -88,8 +88,10 @@ public: FORCE_INLINE static float getPower() { return getAmps() * getVolts(); } #endif - #if HAS_SPI_LCD - FORCE_INLINE static bool display_enabled() { return flags != 0x00; } + #if HAS_WIRED_LCD + #if HAS_MARLINUI_U8GLIB && DISABLED(LIGHTWEIGHT_UI) + FORCE_INLINE static bool display_enabled() { return flags != 0x00; } + #endif #if ENABLED(POWER_MONITOR_CURRENT) static void draw_current(); FORCE_INLINE static bool current_display_enabled() { return TEST(flags, PM_DISP_BIT_I); } diff --git a/Marlin/src/feature/powerloss.cpp b/Marlin/src/feature/powerloss.cpp index 06296dd215..e4bc605bb5 100644 --- a/Marlin/src/feature/powerloss.cpp +++ b/Marlin/src/feature/powerloss.cpp @@ -112,8 +112,7 @@ void PrintJobRecovery::check() { if (card.isMounted()) { load(); if (!valid()) return cancel(); - queue.inject_P(PSTR("M1000 S")); - TERN_(DWIN_CREALITY_LCD, dwin_flag = true); + queue.inject_P(PSTR("M1000S")); } } @@ -186,13 +185,13 @@ void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=0*/ TERN_(HAS_POSITION_SHIFT, info.position_shift = position_shift); info.feedrate = uint16_t(feedrate_mm_s * 60.0f); - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER info.active_extruder = active_extruder; #endif #if DISABLED(NO_VOLUMETRICS) info.volumetric_enabled = parser.volumetric_enabled; - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER for (int8_t e = 0; e < EXTRUDERS; e++) info.filament_size[e] = planner.filament_size[e]; #else if (parser.volumetric_enabled) info.filament_size[0] = planner.filament_size[active_extruder]; @@ -227,6 +226,10 @@ void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=0*/ // Elapsed print job time info.print_job_elapsed = print_job_timer.duration(); + // Misc. Marlin flags + info.flag.dryrun = !!(marlin_debug_flags & MARLIN_DEBUG_DRYRUN); + info.flag.allow_cold_extrusion = TERN0(PREVENT_COLD_EXTRUSION, thermalManager.allow_cold_extrude); + write(); } } @@ -326,6 +329,12 @@ void PrintJobRecovery::resume() { const uint32_t resume_sdpos = info.sdpos; // Get here before the stepper ISR overwrites it + // Apply the dry-run flag if enabled + if (info.flag.dryrun) marlin_debug_flags |= MARLIN_DEBUG_DRYRUN; + + // Restore cold extrusion permission + TERN_(PREVENT_COLD_EXTRUSION, thermalManager.allow_cold_extrude = info.flag.allow_cold_extrusion); + #if HAS_LEVELING // Make sure leveling is off before any G92 and G28 gcode.process_subcommands_now_P(PSTR("M420 S0 Z0")); @@ -337,7 +346,7 @@ void PrintJobRecovery::resume() { // If Z homing goes to max, just reset E and home all gcode.process_subcommands_now_P(PSTR( "G92.9 E0\n" - "G28R0" TERN_(MARLIN_DEV_MODE, "S") + "G28R0" )); #else // "G92.9 E0 ..." @@ -358,8 +367,9 @@ void PrintJobRecovery::resume() { gcode.process_subcommands_now_P(PSTR( "G28R0" // No raise during G28 - TERN_(MARLIN_DEV_MODE, "S") // Simulated Homing - TERN_(IS_CARTESIAN, "XY") // Don't home Z on Cartesian + #if IS_CARTESIAN && DISABLED(POWER_LOSS_RECOVER_ZHOME) + "XY" // Don't home Z on Cartesian unless overridden + #endif )); #endif @@ -367,9 +377,15 @@ void PrintJobRecovery::resume() { // Pretend that all axes are homed set_all_homed(); + #if ENABLED(POWER_LOSS_RECOVER_ZHOME) + // Z has been homed so restore Z to ZsavedPos + POWER_LOSS_ZRAISE + sprintf_P(cmd, PSTR("G1 F500 Z%s"), dtostrf(info.current_position.z + POWER_LOSS_ZRAISE, 1, 3, str_1)); + gcode.process_subcommands_now(cmd); + #endif + // Recover volumetric extrusion state #if DISABLED(NO_VOLUMETRICS) - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER for (int8_t e = 0; e < EXTRUDERS; e++) { sprintf_P(cmd, PSTR("M200 T%i D%s"), e, dtostrf(info.filament_size[e], 1, 3, str_1)); gcode.process_subcommands_now(cmd); @@ -411,7 +427,7 @@ void PrintJobRecovery::resume() { #endif // Select the previously active tool (with no_move) - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER sprintf_P(cmd, PSTR("T%i S"), info.active_extruder); gcode.process_subcommands_now(cmd); #endif @@ -473,7 +489,7 @@ void PrintJobRecovery::resume() { // Move back to the saved Z dtostrf(info.current_position.z, 1, 3, str_1); - #if Z_HOME_DIR > 0 + #if Z_HOME_DIR > 0 || ENABLED(POWER_LOSS_RECOVER_ZHOME) sprintf_P(cmd, PSTR("G1 Z%s F200"), str_1); #else gcode.process_subcommands_now_P(PSTR("G1 Z0 F200")); @@ -498,6 +514,14 @@ void PrintJobRecovery::resume() { LOOP_XYZ(i) update_workspace_offset((AxisEnum)i); #endif + #if ENABLED(DEBUG_POWER_LOSS_RECOVERY) + const uint8_t old_flags = marlin_debug_flags; + marlin_debug_flags |= MARLIN_DEBUG_ECHO; + #endif + + // Continue to apply PLR when a file is resumed! + enable(true); + // Resume the SD file from the last position char *fn = info.sd_filename; extern const char M23_STR[]; @@ -505,6 +529,8 @@ void PrintJobRecovery::resume() { gcode.process_subcommands_now(cmd); sprintf_P(cmd, PSTR("M24 S%ld T%ld"), resume_sdpos, info.print_job_elapsed); gcode.process_subcommands_now(cmd); + + TERN_(DEBUG_POWER_LOSS_RECOVERY, marlin_debug_flags = old_flags); } #if ENABLED(DEBUG_POWER_LOSS_RECOVERY) @@ -543,7 +569,7 @@ void PrintJobRecovery::resume() { DEBUG_ECHOLNPAIR("feedrate: ", info.feedrate); - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER DEBUG_ECHOLNPAIR("active_extruder: ", int(info.active_extruder)); #endif @@ -584,6 +610,8 @@ void PrintJobRecovery::resume() { DEBUG_ECHOLNPAIR("sd_filename: ", info.sd_filename); DEBUG_ECHOLNPAIR("sdpos: ", info.sdpos); DEBUG_ECHOLNPAIR("print_job_elapsed: ", info.print_job_elapsed); + DEBUG_ECHOLNPAIR("dryrun: ", int(info.flag.dryrun)); + DEBUG_ECHOLNPAIR("allow_cold_extrusion: ", int(info.flag.allow_cold_extrusion)); } else DEBUG_ECHOLNPGM("INVALID DATA"); diff --git a/Marlin/src/feature/powerloss.h b/Marlin/src/feature/powerloss.h index 10653493ab..e31b2ec915 100644 --- a/Marlin/src/feature/powerloss.h +++ b/Marlin/src/feature/powerloss.h @@ -58,7 +58,7 @@ typedef struct { uint16_t feedrate; - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER uint8_t active_extruder; #endif @@ -107,6 +107,12 @@ typedef struct { // Job elapsed time millis_t print_job_elapsed; + // Misc. Marlin flags + struct { + bool dryrun:1; // M111 S8 + bool allow_cold_extrusion:1; // M302 P1 + } flag; + uint8_t valid_foot; bool valid() { return valid_head && valid_head == valid_foot; } @@ -173,7 +179,10 @@ class PrintJobRecovery { } #endif - static inline bool valid() { return info.valid(); } + // The referenced file exists + static inline bool interrupted_file_exists() { return card.fileExists(info.sd_filename); } + + static inline bool valid() { return info.valid() && interrupted_file_exists(); } #if ENABLED(DEBUG_POWER_LOSS_RECOVERY) static void debug(PGM_P const prefix); diff --git a/Marlin/src/feature/spindle_laser.h b/Marlin/src/feature/spindle_laser.h index 8240efa2dd..15ff661c73 100644 --- a/Marlin/src/feature/spindle_laser.h +++ b/Marlin/src/feature/spindle_laser.h @@ -224,7 +224,7 @@ public: */ // Force disengage planner power control - static inline void inline_disable() { + static inline void inline_disable() { isReady = false; unitPower = 0; planner.laser_inline.status.isPlanned = false; diff --git a/Marlin/src/feature/tmc_util.h b/Marlin/src/feature/tmc_util.h index 2779ae4ef4..d96939c916 100644 --- a/Marlin/src/feature/tmc_util.h +++ b/Marlin/src/feature/tmc_util.h @@ -105,6 +105,7 @@ class TMCMarlin : public TMC, public TMCStorage { #if HAS_STEALTHCHOP inline void refresh_stepping_mode() { this->en_pwm_mode(this->stored.stealthChop_enabled); } inline bool get_stealthChop_status() { return this->en_pwm_mode(); } + inline bool get_stored_stealthChop_status() { return this->stored.stealthChop_enabled; } #endif #if ENABLED(HYBRID_THRESHOLD) @@ -171,6 +172,7 @@ class TMCMarlin : public TMC220 #if HAS_STEALTHCHOP inline void refresh_stepping_mode() { en_spreadCycle(!this->stored.stealthChop_enabled); } inline bool get_stealthChop_status() { return !this->en_spreadCycle(); } + inline bool get_stored_stealthChop_status() { return this->stored.stealthChop_enabled; } #endif #if ENABLED(HYBRID_THRESHOLD) @@ -216,6 +218,7 @@ class TMCMarlin : public TMC220 #if HAS_STEALTHCHOP inline void refresh_stepping_mode() { en_spreadCycle(!this->stored.stealthChop_enabled); } inline bool get_stealthChop_status() { return !this->en_spreadCycle(); } + inline bool get_stored_stealthChop_status() { return this->stored.stealthChop_enabled; } #endif #if ENABLED(HYBRID_THRESHOLD) diff --git a/Marlin/src/feature/twibus.h b/Marlin/src/feature/twibus.h index 8bc8eb4e74..82aa9aa16a 100644 --- a/Marlin/src/feature/twibus.h +++ b/Marlin/src/feature/twibus.h @@ -48,7 +48,6 @@ typedef void (*twiRequestFunc_t)(); * For more information see * - https://marlinfw.org/docs/gcode/M260.html * - https://marlinfw.org/docs/gcode/M261.html - * */ class TWIBus { private: diff --git a/Marlin/src/gcode/bedlevel/G26.cpp b/Marlin/src/gcode/bedlevel/G26.cpp index cd0dbb13cd..c66d4a7d49 100644 --- a/Marlin/src/gcode/bedlevel/G26.cpp +++ b/Marlin/src/gcode/bedlevel/G26.cpp @@ -359,7 +359,7 @@ inline bool turn_on_heaters() { #if HAS_HEATED_BED if (g26_bed_temp > 25) { - #if HAS_SPI_LCD + #if HAS_WIRED_LCD ui.set_status_P(GET_TEXT(MSG_G26_HEATING_BED), 99); ui.quick_feedback(); TERN_(HAS_LCD_MENU, ui.capture()); @@ -378,7 +378,7 @@ inline bool turn_on_heaters() { #endif // HAS_HEATED_BED // Start heating the active nozzle - #if HAS_SPI_LCD + #if HAS_WIRED_LCD ui.set_status_P(GET_TEXT(MSG_G26_HEATING_NOZZLE), 99); ui.quick_feedback(); #endif @@ -391,7 +391,7 @@ inline bool turn_on_heaters() { #endif )) return G26_ERR; - #if HAS_SPI_LCD + #if HAS_WIRED_LCD ui.reset_status(); ui.quick_feedback(); #endif @@ -446,7 +446,7 @@ inline bool prime_nozzle() { else #endif { - #if HAS_SPI_LCD + #if HAS_WIRED_LCD ui.set_status_P(GET_TEXT(MSG_G26_FIXED_LENGTH), 99); ui.quick_feedback(); #endif diff --git a/Marlin/src/gcode/bedlevel/G35.cpp b/Marlin/src/gcode/bedlevel/G35.cpp index 7595067dbf..926e6e82c5 100755 --- a/Marlin/src/gcode/bedlevel/G35.cpp +++ b/Marlin/src/gcode/bedlevel/G35.cpp @@ -29,6 +29,10 @@ #include "../../module/probe.h" #include "../../feature/bedlevel/bedlevel.h" +#if HAS_MULTI_HOTEND + #include "../../module/tool_change.h" +#endif + #define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE) #include "../../core/debug_out.h" diff --git a/Marlin/src/gcode/bedlevel/abl/G29.cpp b/Marlin/src/gcode/bedlevel/abl/G29.cpp index e7651cc743..e9b6e0e3a6 100644 --- a/Marlin/src/gcode/bedlevel/abl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/abl/G29.cpp @@ -61,7 +61,7 @@ #endif #if ENABLED(DWIN_CREALITY_LCD) - #include "../../../lcd/dwin/dwin.h" + #include "../../../lcd/dwin/e3v2/dwin.h" #endif #if HAS_MULTI_HOTEND @@ -160,7 +160,6 @@ * E By default G29 will engage the Z probe, test the bed, then disengage. * Include "E" to engage/disengage the Z probe for each sample. * There's no extra effect if you have a fixed Z probe. - * */ G29_TYPE GcodeSuite::G29() { diff --git a/Marlin/src/gcode/bedlevel/mbl/G29.cpp b/Marlin/src/gcode/bedlevel/mbl/G29.cpp index 68ac459ebb..5da99386ad 100644 --- a/Marlin/src/gcode/bedlevel/mbl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/mbl/G29.cpp @@ -57,7 +57,6 @@ inline void echo_not_entered(const char c) { SERIAL_CHAR(c); SERIAL_ECHOLNPGM(" * S3 In Jn Zn.nn Manually modify a single point * S4 Zn.nn Set z offset. Positive away from bed, negative closer to bed. * S5 Reset and disable mesh - * */ void GcodeSuite::G29() { diff --git a/Marlin/src/gcode/calibrate/G28.cpp b/Marlin/src/gcode/calibrate/G28.cpp index 0e1f707898..7bc40b2127 100644 --- a/Marlin/src/gcode/calibrate/G28.cpp +++ b/Marlin/src/gcode/calibrate/G28.cpp @@ -47,7 +47,7 @@ #include "../../lcd/ultralcd.h" #if ENABLED(DWIN_CREALITY_LCD) - #include "../../lcd/dwin/dwin.h" + #include "../../lcd/dwin/e3v2/dwin.h" #endif #if HAS_L64XX // set L6470 absolute position registers to counts @@ -192,7 +192,6 @@ * X Home to the X endstop * Y Home to the Y endstop * Z Home to the Z endstop - * */ void GcodeSuite::G28() { DEBUG_SECTION(log_G28, "G28", DEBUGGING(LEVELING)); diff --git a/Marlin/src/gcode/calibrate/G76_M871.cpp b/Marlin/src/gcode/calibrate/G76_M192_M871.cpp similarity index 90% rename from Marlin/src/gcode/calibrate/G76_M871.cpp rename to Marlin/src/gcode/calibrate/G76_M192_M871.cpp index 9870d9fbe5..89393b4582 100644 --- a/Marlin/src/gcode/calibrate/G76_M871.cpp +++ b/Marlin/src/gcode/calibrate/G76_M192_M871.cpp @@ -37,6 +37,17 @@ #include "../../module/probe.h" #include "../../feature/probe_temp_comp.h" +#include "../../lcd/ultralcd.h" +#include "../../MarlinCore.h" // for wait_for_heatup and idle() + +#if ENABLED(PRINTJOB_TIMER_AUTOSTART) + #include "../../module/printcounter.h" +#endif + +#if ENABLED(PRINTER_EVENTS_LEDS) + #include "../../feature/leds/leds.h" +#endif + /** * G76: calibrate probe and/or bed temperature offsets * Notes: @@ -303,17 +314,17 @@ void GcodeSuite::M871() { } else if (parser.seen("BPE")) { if (!parser.seenval('V')) return; - const int16_t val = parser.value_int(); + const int16_t offset_val = parser.value_int(); if (!parser.seenval('I')) return; const int16_t idx = parser.value_int(); const TempSensorID mod = (parser.seen('B') ? TSI_BED : - #if ENABLED(USE_TEMP_EXT_COMPENSATION) - parser.seen('E') ? TSI_EXT : - #endif - TSI_PROBE + #if ENABLED(USE_TEMP_EXT_COMPENSATION) + parser.seen('E') ? TSI_EXT : + #endif + TSI_PROBE ); - if (idx > 0 && temp_comp.set_offset(mod, idx - 1, val)) - SERIAL_ECHOLNPAIR("Set value: ", val); + if (idx > 0 && temp_comp.set_offset(mod, idx - 1, offset_val)) + SERIAL_ECHOLNPAIR("Set value: ", offset_val); else SERIAL_ECHOLNPGM("!Invalid index. Failed to set value (note: value at index 0 is constant)."); @@ -322,4 +333,25 @@ void GcodeSuite::M871() { temp_comp.print_offsets(); } +/** + * M192: Wait for probe temperature sensor to reach a target + * + * Select only one of these flags: + * R - Wait for heating or cooling + * S - Wait only for heating + */ +void GcodeSuite::M192() { + if (DEBUGGING(DRYRUN)) return; + + const bool no_wait_for_cooling = parser.seenval('S'); + if (!no_wait_for_cooling && ! parser.seenval('R')) { + SERIAL_ERROR_MSG("No target temperature set."); + return; + } + + const float target_temp = parser.value_celsius(); + ui.set_status_P(thermalManager.isProbeBelowTemp(target_temp) ? GET_TEXT(MSG_PROBE_HEATING) : GET_TEXT(MSG_PROBE_COOLING)); + thermalManager.wait_for_probe(target_temp, no_wait_for_cooling); +} + #endif // PROBE_TEMP_COMPENSATION diff --git a/Marlin/src/gcode/calibrate/M425.cpp b/Marlin/src/gcode/calibrate/M425.cpp index 3e54186a5f..40441ac08d 100644 --- a/Marlin/src/gcode/calibrate/M425.cpp +++ b/Marlin/src/gcode/calibrate/M425.cpp @@ -56,7 +56,7 @@ void GcodeSuite::M425() { }; LOOP_XYZ(a) { - if (AXIS_CAN_CALIBRATE(a) && parser.seen(XYZ_CHAR(a))) { + if (axis_can_calibrate(a) && parser.seen(XYZ_CHAR(a))) { planner.synchronize(); backlash.distance_mm[a] = parser.has_value() ? parser.value_linear_units() : backlash.get_measurement(AxisEnum(a)); noArgs = false; diff --git a/Marlin/src/gcode/calibrate/M48.cpp b/Marlin/src/gcode/calibrate/M48.cpp index aaf58eed1c..8640dfa391 100644 --- a/Marlin/src/gcode/calibrate/M48.cpp +++ b/Marlin/src/gcode/calibrate/M48.cpp @@ -144,7 +144,7 @@ void GcodeSuite::M48() { float sample_sum = 0.0; LOOP_L_N(n, n_samples) { - #if HAS_SPI_LCD + #if HAS_WIRED_LCD // Display M48 progress in the status bar ui.status_printf_P(0, PSTR(S_FMT ": %d/%d"), GET_TEXT(MSG_M48_POINT), int(n + 1), int(n_samples)); #endif @@ -192,8 +192,8 @@ void GcodeSuite::M48() { // Choose the next position as an offset to chosen test position const xy_pos_t noz_pos = test_position - probe.offset_xy; xy_pos_t next_pos = { - noz_pos.x + cos(RADIANS(angle)) * radius, - noz_pos.y + sin(RADIANS(angle)) * radius + noz_pos.x + float(cos(RADIANS(angle))) * radius, + noz_pos.y + float(sin(RADIANS(angle))) * radius }; #if ENABLED(DELTA) @@ -258,7 +258,7 @@ void GcodeSuite::M48() { SERIAL_ECHOLNPGM("Finished!"); dev_report(verbose_level > 0, mean, sigma, min, max, true); - #if HAS_SPI_LCD + #if HAS_WIRED_LCD // Display M48 results in the status bar char sigma_str[8]; ui.status_printf_P(0, PSTR(S_FMT ": %s"), GET_TEXT(MSG_M48_DEVIATION), dtostrf(sigma, 2, 6, sigma_str)); diff --git a/Marlin/src/gcode/config/M217.cpp b/Marlin/src/gcode/config/M217.cpp index 0d049ede16..b57dec31f3 100644 --- a/Marlin/src/gcode/config/M217.cpp +++ b/Marlin/src/gcode/config/M217.cpp @@ -22,7 +22,7 @@ #include "../../inc/MarlinConfigPre.h" -#if EXTRUDERS > 1 +#if HAS_MULTI_EXTRUDER #include "../gcode.h" #include "../../module/tool_change.h" @@ -170,4 +170,4 @@ void GcodeSuite::M217() { M217_report(); } -#endif // EXTRUDERS > 1 +#endif // HAS_MULTI_EXTRUDER diff --git a/Marlin/src/gcode/config/M302.cpp b/Marlin/src/gcode/config/M302.cpp index 14fbd9f572..afdc6c9e85 100644 --- a/Marlin/src/gcode/config/M302.cpp +++ b/Marlin/src/gcode/config/M302.cpp @@ -37,7 +37,7 @@ * * M302 ; report current cold extrusion state * M302 P0 ; enable cold extrusion checking - * M302 P1 ; disables cold extrusion checking + * M302 P1 ; disable cold extrusion checking * M302 S0 ; always allow extrusion (disables checking) * M302 S170 ; only allow extrusion above 170 * M302 S170 P1 ; set min extrude temp to 170 but leave disabled diff --git a/Marlin/src/gcode/config/M575.cpp b/Marlin/src/gcode/config/M575.cpp index 3aa5844653..44723b7f2f 100644 --- a/Marlin/src/gcode/config/M575.cpp +++ b/Marlin/src/gcode/config/M575.cpp @@ -53,23 +53,10 @@ void GcodeSuite::M575() { case 115200: case 250000: case 500000: case 1000000: { const int8_t port = parser.intval('P', -99); const bool set0 = (port == -99 || port == 0); - if (set0) { - SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR(" Serial " - #if HAS_MULTI_SERIAL - , '0', - #else - "0" - #endif - " baud rate set to ", baud - ); - } + if (set0) SERIAL_ECHO_MSG(" Serial ", '0', " baud rate set to ", baud); #if HAS_MULTI_SERIAL const bool set1 = (port == -99 || port == 1); - if (set1) { - SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR(" Serial ", '1', " baud rate set to ", baud); - } + if (set1) SERIAL_ECHO_MSG(" Serial ", '1', " baud rate set to ", baud); #endif SERIAL_FLUSH(); @@ -85,4 +72,4 @@ void GcodeSuite::M575() { } } -#endif // NUM_SERIAL > 0 && BAUD_RATE_GCODE +#endif // BAUD_RATE_GCODE diff --git a/Marlin/src/gcode/control/M993_M994.cpp b/Marlin/src/gcode/control/M993_M994.cpp index 4e13aa9d77..ff9ff85bf5 100644 --- a/Marlin/src/gcode/control/M993_M994.cpp +++ b/Marlin/src/gcode/control/M993_M994.cpp @@ -41,8 +41,6 @@ void GcodeSuite::M993() { return; } - W25QXXFlash W25QXX; - uint8_t buf[1024]; uint32_t addr = 0; W25QXX.init(SPI_QUARTER_SPEED); @@ -71,14 +69,12 @@ void GcodeSuite::M994() { return; } - W25QXXFlash W25QXX; - uint8_t buf[1024]; uint32_t addr = 0; W25QXX.init(SPI_QUARTER_SPEED); W25QXX.SPI_FLASH_BulkErase(); SERIAL_ECHOPGM("Load SPI Flash"); - while(addr < SPI_FLASH_SIZE) { + while (addr < SPI_FLASH_SIZE) { card.read(buf, COUNT(buf)); W25QXX.SPI_FLASH_BufferWrite(buf, addr, COUNT(buf)); addr += COUNT(buf); diff --git a/Marlin/src/gcode/control/M999.cpp b/Marlin/src/gcode/control/M999.cpp index 53d74322a3..3bd908cad6 100644 --- a/Marlin/src/gcode/control/M999.cpp +++ b/Marlin/src/gcode/control/M999.cpp @@ -34,7 +34,6 @@ * * Sending "M999 S1" will resume printing without flushing the * existing command buffer. - * */ void GcodeSuite::M999() { marlin_state = MF_RUNNING; diff --git a/Marlin/src/gcode/control/T.cpp b/Marlin/src/gcode/control/T.cpp index 46cdfebf11..729f7f2223 100644 --- a/Marlin/src/gcode/control/T.cpp +++ b/Marlin/src/gcode/control/T.cpp @@ -23,7 +23,7 @@ #include "../gcode.h" #include "../../module/tool_change.h" -#if ENABLED(DEBUG_LEVELING_FEATURE) || EXTRUDERS > 1 +#if EITHER(HAS_MULTI_EXTRUDER, DEBUG_LEVELING_FEATURE) #include "../../module/motion.h" #endif diff --git a/Marlin/src/gcode/feature/L6470/M906.cpp b/Marlin/src/gcode/feature/L6470/M906.cpp index cd7fc3dcb5..7bd446a1ab 100644 --- a/Marlin/src/gcode/feature/L6470/M906.cpp +++ b/Marlin/src/gcode/feature/L6470/M906.cpp @@ -33,7 +33,6 @@ #include "../../../core/debug_out.h" /** - * * M906: report or set KVAL_HOLD which sets the maximum effective voltage provided by the * PWMs to the steppers * @@ -56,7 +55,6 @@ * * L6470 is used in the STEP-CLOCK mode. KVAL_HOLD is the only KVAL_xxx * that affects the effective voltage seen by the stepper. - * */ /** diff --git a/Marlin/src/gcode/feature/L6470/M916-918.cpp b/Marlin/src/gcode/feature/L6470/M916-918.cpp index 29efc06dd9..8165b71e44 100644 --- a/Marlin/src/gcode/feature/L6470/M916-918.cpp +++ b/Marlin/src/gcode/feature/L6470/M916-918.cpp @@ -37,7 +37,6 @@ #include "../../../core/debug_out.h" /** - * * M916: increase KVAL_HOLD until get thermal warning * NOTE - on L6474 it is TVAL that is used * @@ -62,7 +61,6 @@ * * D - time (in seconds) to run each setting of KVAL_HOLD/TVAL * optional - defaults to zero (runs each setting once) - * */ /** @@ -187,7 +185,6 @@ void GcodeSuite::M916() { } /** - * * M917: Find minimum current thresholds * * Decrease OCD current until overcurrent error @@ -214,7 +211,6 @@ void GcodeSuite::M916() { * * K - value for KVAL_HOLD (0 - 255) (ignored for L6474) * optional - will report current value from driver if not specified - * */ void GcodeSuite::M917() { @@ -522,7 +518,6 @@ void GcodeSuite::M917() { } /** - * * M918: increase speed until error or max feedrate achieved (as shown in configuration.h)) * * J - select which driver(s) to monitor on multi-driver axis @@ -543,7 +538,6 @@ void GcodeSuite::M917() { * * M - value for microsteps (1 - 128) (optional) * optional - will report current value from driver if not specified - * */ void GcodeSuite::M918() { diff --git a/Marlin/src/gcode/feature/fwretract/G10_G11.cpp b/Marlin/src/gcode/feature/fwretract/G10_G11.cpp index 05f0150360..219502f28a 100644 --- a/Marlin/src/gcode/feature/fwretract/G10_G11.cpp +++ b/Marlin/src/gcode/feature/fwretract/G10_G11.cpp @@ -33,11 +33,11 @@ * TODO: Handle 'G10 P' for tool settings and 'G10 L' for workspace settings */ void GcodeSuite::G10() { - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER const bool rs = parser.boolval('S'); #endif fwretract.retract(true - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER , rs #endif ); diff --git a/Marlin/src/gcode/feature/i2c/M260_M261.cpp b/Marlin/src/gcode/feature/i2c/M260_M261.cpp index 13c2cd1d10..526d9101e1 100644 --- a/Marlin/src/gcode/feature/i2c/M260_M261.cpp +++ b/Marlin/src/gcode/feature/i2c/M260_M261.cpp @@ -42,7 +42,6 @@ * * M260 S1 ; Send the buffered data and reset the buffer * M260 R1 ; Reset the buffer without sending data - * */ void GcodeSuite::M260() { // Set the target address diff --git a/Marlin/src/gcode/feature/mixing/M166.cpp b/Marlin/src/gcode/feature/mixing/M166.cpp index 5f2c4f042a..9e071a47ec 100644 --- a/Marlin/src/gcode/feature/mixing/M166.cpp +++ b/Marlin/src/gcode/feature/mixing/M166.cpp @@ -86,7 +86,14 @@ void GcodeSuite::M166() { echo_zt(mixer.gradient.end_vtool, mixer.gradient.end_z); mixer.update_mix_from_gradient(); - SERIAL_ECHOPAIR(" ; Current Z", planner.get_axis_position_mm(Z_AXIS)); + + SERIAL_ECHOPGM(" ; Current Z"); + #if ENABLED(DELTA) + get_cartesian_from_steppers(); + SERIAL_ECHO(cartes.z); + #else + SERIAL_ECHO(planner.get_axis_position_mm(Z_AXIS)); + #endif echo_mix(); } diff --git a/Marlin/src/gcode/feature/pause/M600.cpp b/Marlin/src/gcode/feature/pause/M600.cpp index 673c7387ef..7c9be54b29 100644 --- a/Marlin/src/gcode/feature/pause/M600.cpp +++ b/Marlin/src/gcode/feature/pause/M600.cpp @@ -29,7 +29,7 @@ #include "../../../module/motion.h" #include "../../../module/printcounter.h" -#if EXTRUDERS > 1 +#if HAS_MULTI_EXTRUDER #include "../../../module/tool_change.h" #endif @@ -45,6 +45,10 @@ #include "../../../feature/mixing.h" #endif +#if HAS_FILAMENT_SENSOR + #include "../../../feature/runout.h" +#endif + /** * M600: Pause for filament change * @@ -101,7 +105,7 @@ void GcodeSuite::M600() { if (!all_axes_known()) home_all_axes(); #endif - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER // Change toolhead if specified const uint8_t active_extruder_before_filament_change = active_extruder; if (active_extruder != target_extruder && TERN1(DUAL_X_CARRIAGE, !dxc_is_duplicating())) @@ -159,7 +163,7 @@ void GcodeSuite::M600() { #endif } - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER // Restore toolhead if it was changed if (active_extruder_before_filament_change != active_extruder) tool_change(active_extruder_before_filament_change, false); diff --git a/Marlin/src/gcode/feature/pause/M603.cpp b/Marlin/src/gcode/feature/pause/M603.cpp index a62b5cd46d..9c3b774bd2 100644 --- a/Marlin/src/gcode/feature/pause/M603.cpp +++ b/Marlin/src/gcode/feature/pause/M603.cpp @@ -29,7 +29,7 @@ #include "../../../module/motion.h" #include "../../../module/printcounter.h" -#if EXTRUDERS > 1 +#if HAS_MULTI_EXTRUDER #include "../../../module/tool_change.h" #endif @@ -39,7 +39,6 @@ * T[toolhead] - Select extruder to configure, active extruder if not specified * U[distance] - Retract distance for removal, for the specified extruder * L[distance] - Extrude distance for insertion, for the specified extruder - * */ void GcodeSuite::M603() { diff --git a/Marlin/src/gcode/feature/pause/M701_M702.cpp b/Marlin/src/gcode/feature/pause/M701_M702.cpp index a02f2368e2..c1f7223142 100644 --- a/Marlin/src/gcode/feature/pause/M701_M702.cpp +++ b/Marlin/src/gcode/feature/pause/M701_M702.cpp @@ -30,7 +30,7 @@ #include "../../../module/temperature.h" #include "../../../feature/pause.h" -#if EXTRUDERS > 1 +#if HAS_MULTI_EXTRUDER #include "../../../module/tool_change.h" #endif @@ -86,7 +86,7 @@ void GcodeSuite::M701() { // Show initial "wait for load" message TERN_(HAS_LCD_MENU, lcd_pause_show_message(PAUSE_MESSAGE_LOAD, PAUSE_MODE_LOAD_FILAMENT, target_extruder)); - #if EXTRUDERS > 1 && DISABLED(PRUSA_MMU2) + #if HAS_MULTI_EXTRUDER && DISABLED(PRUSA_MMU2) // Change toolhead if specified uint8_t active_extruder_before_filament_change = active_extruder; if (active_extruder != target_extruder) @@ -121,7 +121,7 @@ void GcodeSuite::M701() { if (park_point.z > 0) do_blocking_move_to_z(_MAX(current_position.z - park_point.z, 0), feedRate_t(NOZZLE_PARK_Z_FEEDRATE)); - #if EXTRUDERS > 1 && DISABLED(PRUSA_MMU2) + #if HAS_MULTI_EXTRUDER && DISABLED(PRUSA_MMU2) // Restore toolhead if it was changed if (active_extruder_before_filament_change != active_extruder) tool_change(active_extruder_before_filament_change, false); @@ -186,7 +186,7 @@ void GcodeSuite::M702() { // Show initial "wait for unload" message TERN_(HAS_LCD_MENU, lcd_pause_show_message(PAUSE_MESSAGE_UNLOAD, PAUSE_MODE_UNLOAD_FILAMENT, target_extruder)); - #if EXTRUDERS > 1 && DISABLED(PRUSA_MMU2) + #if HAS_MULTI_EXTRUDER && DISABLED(PRUSA_MMU2) // Change toolhead if specified uint8_t active_extruder_before_filament_change = active_extruder; if (active_extruder != target_extruder) @@ -201,7 +201,7 @@ void GcodeSuite::M702() { #if ENABLED(PRUSA_MMU2) mmu2.unload(); #else - #if EXTRUDERS > 1 && ENABLED(FILAMENT_UNLOAD_ALL_EXTRUDERS) + #if BOTH(HAS_MULTI_EXTRUDER, FILAMENT_UNLOAD_ALL_EXTRUDERS) if (!parser.seenval('T')) { HOTEND_LOOP() { if (e != active_extruder) tool_change(e, false); @@ -227,7 +227,7 @@ void GcodeSuite::M702() { if (park_point.z > 0) do_blocking_move_to_z(_MAX(current_position.z - park_point.z, 0), feedRate_t(NOZZLE_PARK_Z_FEEDRATE)); - #if EXTRUDERS > 1 && DISABLED(PRUSA_MMU2) + #if HAS_MULTI_EXTRUDER && DISABLED(PRUSA_MMU2) // Restore toolhead if it was changed if (active_extruder_before_filament_change != active_extruder) tool_change(active_extruder_before_filament_change, false); diff --git a/Marlin/src/gcode/feature/power_monitor/M430.cpp b/Marlin/src/gcode/feature/power_monitor/M430.cpp index a669f0a76b..7639ea962d 100644 --- a/Marlin/src/gcode/feature/power_monitor/M430.cpp +++ b/Marlin/src/gcode/feature/power_monitor/M430.cpp @@ -38,7 +38,7 @@ */ void GcodeSuite::M430() { bool do_report = true; - #if HAS_SPI_LCD + #if HAS_WIRED_LCD #if ENABLED(POWER_MONITOR_CURRENT) if (parser.seen('I')) { power_monitor.set_current_display(parser.value_bool()); do_report = false; } #endif diff --git a/Marlin/src/gcode/feature/powerloss/M1000.cpp b/Marlin/src/gcode/feature/powerloss/M1000.cpp index 58e810e5d0..e9477dd2fb 100644 --- a/Marlin/src/gcode/feature/powerloss/M1000.cpp +++ b/Marlin/src/gcode/feature/powerloss/M1000.cpp @@ -62,6 +62,8 @@ void GcodeSuite::M1000() { if (parser.seen('S')) { #if HAS_LCD_MENU ui.goto_screen(menu_job_recovery); + #elif ENABLED(DWIN_CREALITY_LCD) + recovery.dwin_flag = true; #elif ENABLED(EXTENSIBLE_UI) ExtUI::onPowerLossResume(); #else diff --git a/Marlin/src/gcode/feature/powerloss/M413.cpp b/Marlin/src/gcode/feature/powerloss/M413.cpp index 5a08053e7c..3538ccaa6e 100644 --- a/Marlin/src/gcode/feature/powerloss/M413.cpp +++ b/Marlin/src/gcode/feature/powerloss/M413.cpp @@ -50,6 +50,7 @@ void GcodeSuite::M413() { if (parser.seen("RL")) recovery.load(); if (parser.seen('W')) recovery.save(true); if (parser.seen('P')) recovery.purge(); + if (parser.seen('D')) recovery.debug(PSTR("M413")); #if PIN_EXISTS(POWER_LOSS) if (parser.seen('O')) recovery._outage(); #endif diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index 0bd784c074..ef71140b19 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -875,6 +875,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { #endif #if ENABLED(PROBE_TEMP_COMPENSATION) + case 192: M192(); break; // M192: Wait for probe temp case 871: M871(); break; // M871: Print/reset/clear first layer temperature offset values #endif diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index 23bf2c0ce5..425a857369 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -253,6 +253,7 @@ * M868 - Report or set position encoder module error correction threshold. * M869 - Report position encoder module error. * M871 - Print/reset/clear first layer temperature offset values. (Requires PROBE_TEMP_COMPENSATION) + * M192 - Wait for probe temp (Requires PROBE_TEMP_COMPENSATION) * M876 - Handle Prompt Response. (Requires HOST_PROMPT_SUPPORT and not EMERGENCY_PARSER) * M900 - Get or Set Linear Advance K-factor. (Requires LIN_ADVANCE) * M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given. (Requires at least one _DRIVER_TYPE defined as TMC2130/2160/5130/5160/2208/2209/2660 or L6470) @@ -288,7 +289,6 @@ * "T" Codes * * T0-T3 - Select an extruder (tool) by index: "T F" - * */ #include "../inc/MarlinConfig.h" @@ -660,9 +660,7 @@ private: static void M211(); - #if EXTRUDERS > 1 - static void M217(); - #endif + TERN_(HAS_MULTI_EXTRUDER, static void M217()); TERN_(HAS_HOTEND_OFFSET, static void M218()); @@ -820,7 +818,10 @@ private: FORCE_INLINE static void M869() { I2CPEM.M869(); } #endif - TERN_(PROBE_TEMP_COMPENSATION, static void M871()); + #if ENABLED(PROBE_TEMP_COMPENSATION) + static void M192(); + static void M871(); + #endif TERN_(LIN_ADVANCE, static void M900()); diff --git a/Marlin/src/gcode/host/M115.cpp b/Marlin/src/gcode/host/M115.cpp index cd64c563f9..53c5163bba 100644 --- a/Marlin/src/gcode/host/M115.cpp +++ b/Marlin/src/gcode/host/M115.cpp @@ -42,8 +42,16 @@ * the capability is not present. */ void GcodeSuite::M115() { - - SERIAL_ECHOLNPGM(STR_M115_REPORT); + SERIAL_ECHOLNPGM( + "FIRMWARE_NAME:Marlin " DETAILED_BUILD_VERSION " (" __DATE__ " " __TIME__ ") " + "SOURCE_CODE_URL:" SOURCE_CODE_URL " " + "PROTOCOL_VERSION:" PROTOCOL_VERSION " " + "MACHINE_TYPE:" MACHINE_NAME " " + "EXTRUDER_COUNT:" STRINGIFY(EXTRUDERS) " " + #ifdef MACHINE_UUID + "UUID:" MACHINE_UUID + #endif + ); #if ENABLED(EXTENDED_CAPABILITIES_REPORT) diff --git a/Marlin/src/gcode/host/M360.cpp b/Marlin/src/gcode/host/M360.cpp index 87ca23becd..9970dc4df9 100644 --- a/Marlin/src/gcode/host/M360.cpp +++ b/Marlin/src/gcode/host/M360.cpp @@ -145,10 +145,11 @@ void GcodeSuite::M360() { config_prefix(PSTR("PrinterType")); SERIAL_ECHOLNPGM( - TERN_(DELTA, "Delta") - TERN_(IS_SCARA, "SCARA") - TERN_(IS_CORE, "Core") - TERN_(IS_CARTESIAN, "Cartesian") + TERN_(DELTA, "Delta") + TERN_(IS_SCARA, "SCARA") + TERN_(IS_CORE, "Core") + TERN_(MARKFORGED_XY, "MarkForged") + TERN_(IS_CARTESIAN, "Cartesian") ); // diff --git a/Marlin/src/gcode/motion/G2_G3.cpp b/Marlin/src/gcode/motion/G2_G3.cpp index 59a5346356..61d9f1d3a6 100644 --- a/Marlin/src/gcode/motion/G2_G3.cpp +++ b/Marlin/src/gcode/motion/G2_G3.cpp @@ -115,9 +115,7 @@ void plan_arc( ); // Divide total travel by nominal segment length uint16_t segments = FLOOR(mm_of_travel / seg_length); - if (segments < min_segments) { // Too few segments? - segments = min_segments; // More segments - } + NOLESS(segments, min_segments); // At least some segments seg_length = mm_of_travel / segments; /** diff --git a/Marlin/src/gcode/parser.cpp b/Marlin/src/gcode/parser.cpp index 91a24d1dd0..b3172e7f6b 100644 --- a/Marlin/src/gcode/parser.cpp +++ b/Marlin/src/gcode/parser.cpp @@ -247,7 +247,7 @@ void GCodeParser::parse(char *p) { #if ENABLED(EXPECTED_PRINTER_CHECK) case 16: #endif - case 23: case 28: case 30: case 117: case 118: case 928: + case 23: case 28: case 30: case 33: case 117: case 118: case 928: string_arg = unescape_string(p); return; default: break; diff --git a/Marlin/src/gcode/sd/M20.cpp b/Marlin/src/gcode/sd/M20.cpp index 6d4c55752c..7ac4affdae 100644 --- a/Marlin/src/gcode/sd/M20.cpp +++ b/Marlin/src/gcode/sd/M20.cpp @@ -31,9 +31,13 @@ * M20: List SD card to serial output */ void GcodeSuite::M20() { - SERIAL_ECHOLNPGM(STR_BEGIN_FILE_LIST); - card.ls(); - SERIAL_ECHOLNPGM(STR_END_FILE_LIST); + if (card.flag.mounted) { + SERIAL_ECHOLNPGM(STR_BEGIN_FILE_LIST); + card.ls(); + SERIAL_ECHOLNPGM(STR_END_FILE_LIST); + } + else + SERIAL_ECHO_MSG(STR_NO_MEDIA); } #endif // SDSUPPORT diff --git a/Marlin/src/gcode/sd/M24_M25.cpp b/Marlin/src/gcode/sd/M24_M25.cpp index c27e03862c..bdb37f605c 100644 --- a/Marlin/src/gcode/sd/M24_M25.cpp +++ b/Marlin/src/gcode/sd/M24_M25.cpp @@ -98,7 +98,9 @@ void GcodeSuite::M25() { print_job_timer.pause(); - TERN(DWIN_CREALITY_LCD,,ui.reset_status()); + #if DISABLED(DWIN_CREALITY_LCD) + ui.reset_status(); + #endif #if ENABLED(HOST_ACTION_COMMANDS) TERN_(HOST_PROMPT_SUPPORT, host_prompt_open(PROMPT_PAUSE_RESUME, PSTR("Pause SD"), PSTR("Resume"))); diff --git a/Marlin/src/gcode/sd/M32.cpp b/Marlin/src/gcode/sd/M32.cpp index a6f9fbcd8d..55ec6ea497 100644 --- a/Marlin/src/gcode/sd/M32.cpp +++ b/Marlin/src/gcode/sd/M32.cpp @@ -38,7 +38,6 @@ * M32 !PATH/TO/FILE.GCO# ; Start FILE.GCO * M32 P !PATH/TO/FILE.GCO# ; Start FILE.GCO as a procedure * M32 S60 !PATH/TO/FILE.GCO# ; Start FILE.GCO at byte 60 - * */ void GcodeSuite::M32() { if (IS_SD_PRINTING()) planner.synchronize(); diff --git a/Marlin/src/gcode/sd/M524.cpp b/Marlin/src/gcode/sd/M524.cpp index b27814cc38..089d2e2f0c 100644 --- a/Marlin/src/gcode/sd/M524.cpp +++ b/Marlin/src/gcode/sd/M524.cpp @@ -34,6 +34,8 @@ void GcodeSuite::M524() { if (IS_SD_PRINTING()) card.flag.abort_sd_printing = true; + else if (card.isMounted()) + card.closefile(); } diff --git a/Marlin/src/gcode/temp/M303.cpp b/Marlin/src/gcode/temp/M303.cpp index 3340e4fa49..ccce09b4f1 100644 --- a/Marlin/src/gcode/temp/M303.cpp +++ b/Marlin/src/gcode/temp/M303.cpp @@ -62,7 +62,7 @@ void GcodeSuite::M303() { #define SI TERN(PIDTEMPBED, H_BED, H_E0) #define EI TERN(PIDTEMP, HOTENDS - 1, H_BED) - const heater_ind_t e = (heater_ind_t)parser.intval('E'); + const heater_id_t e = (heater_id_t)parser.intval('E'); if (!WITHIN(e, SI, EI)) { SERIAL_ECHOLNPGM(STR_PID_BAD_EXTRUDER_NUM); TERN_(EXTENSIBLE_UI, ExtUI::onPidTuning(ExtUI::result_t::PID_BAD_EXTRUDER_NUM)); diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 1476bbea4a..d2c939b9b4 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -26,6 +26,7 @@ * Conditionals that need to be set before Configuration_adv.h or pins.h */ +// Kinematics #if ENABLED(MORGAN_SCARA) #define IS_SCARA 1 #define IS_KINEMATIC 1 @@ -35,10 +36,26 @@ #define IS_CARTESIAN 1 #endif +// MKS_LCD12864 is a variant of MKS_MINI_12864 #if ENABLED(MKS_LCD12864) #define MKS_MINI_12864 #endif +/** + * General Flags that may be set below by specific LCDs + * + * DOGLCD : Run a Graphical LCD through U8GLib (with MarlinUI) + * IS_ULTIPANEL : Define LCD_PINS_D5/6/7 for direct-connected "Ultipanel" LCDs + * IS_ULTRA_LCD : Ultra LCD, not necessarily Ultipanel. Used most often with NEWPANEL. + * IS_RRD_SC : Common RRD Smart Controller digital interface pins + * IS_RRD_FG_SC : Common RRD Full Graphical Smart Controller digital interface pins + * U8GLIB_ST7920 : Most common DOGM display SPI interface, supporting a "lightweight" display mode. + * U8GLIB_SH1106 : SH1106 OLED with I2C interface via U8GLib + * IS_U8GLIB_SSD1306 : SSD1306 OLED with I2C interface via U8GLib + * U8GLIB_SSD1309 : SSD1309 OLED with I2C interface via U8GLib + * U8GLIB_ST7565_64128N : ST7565 128x64 LCD with SPI interface via U8GLib + * U8GLIB_LM6059_AF : LM6059 with Hardware SPI via U8GLib + */ #if EITHER(MKS_MINI_12864, ENDER2_STOCKDISPLAY) #define MINIPANEL @@ -48,6 +65,11 @@ #define DOGLCD #define IS_ULTIPANEL +#elif EITHER(DWIN_MARLINUI_PORTRAIT, DWIN_MARLINUI_LANDSCAPE) + + #define IS_DWIN_MARLINUI 1 + #define IS_ULTIPANEL + #elif ENABLED(ZONESTAR_LCD) #define ADC_KEYPAD @@ -85,7 +107,6 @@ #elif ANY(miniVIKI, VIKI2, ELB_FULL_GRAPHIC_CONTROLLER, AZSMZ_12864) - #define IS_ULTRA_LCD #define DOGLCD #define IS_ULTIPANEL @@ -196,6 +217,28 @@ #define LCD_WIDTH 16 #define LCD_HEIGHT 2 +#elif EITHER(TFTGLCD_PANEL_SPI, TFTGLCD_PANEL_I2C) + + #define IS_TFTGLCD_PANEL 1 + #define IS_ULTIPANEL // Note that IS_ULTIPANEL leads to HAS_WIRED_LCD + + #if ENABLED(SDSUPPORT) && DISABLED(LCD_PROGRESS_BAR) + #define LCD_PROGRESS_BAR + #endif + #if ENABLED(TFTGLCD_PANEL_I2C) + #define LCD_USE_I2C_BUZZER // Enable buzzer on LCD for I2C and SPI buses (LiquidTWI2 not required) + #define LCD_I2C_ADDRESS 0x27 // Must be equal to panel's I2C slave addres + #endif + #define STD_ENCODER_PULSES_PER_STEP 2 + #define STD_ENCODER_STEPS_PER_MENU_ITEM 1 + #define LCD_WIDTH 20 // 20 or 24 chars in line + #define LCD_HEIGHT 10 // Character lines + #define LCD_CONTRAST_MIN 127 + #define LCD_CONTRAST_MAX 255 + #define DEFAULT_LCD_CONTRAST 250 + #define CONVERT_TO_EXT_ASCII // Use extended 128-255 symbols from ASCII table. + // At this time present conversion only for cyrillic - bg, ru and uk languages. + // First 7 ASCII symbols in panel font must be replaced with Marlin's special symbols. #endif #if ENABLED(IS_RRD_FG_SC) @@ -234,9 +277,9 @@ // 128x64 I2C OLED LCDs - SSD1306/SSD1309/SH1106 #if ANY(U8GLIB_SSD1306, U8GLIB_SSD1309, U8GLIB_SH1106) - #define HAS_SSD1306_OLED_I2C 1 + #define HAS_U8GLIB_I2C_OLED 1 #endif -#if HAS_SSD1306_OLED_I2C +#if HAS_U8GLIB_I2C_OLED #define IS_ULTRA_LCD #define DOGLCD #endif @@ -402,7 +445,6 @@ #define IS_ULTRA_LCD #define NEWPANEL #endif - #if ENABLED(IS_ULTRA_LCD) #define ULTRA_LCD #endif @@ -436,11 +478,13 @@ #endif #if ENABLED(ULTRA_LCD) - #define HAS_SPI_LCD 1 + #define HAS_WIRED_LCD 1 #if ENABLED(DOGLCD) - #define HAS_GRAPHICAL_LCD 1 + #define HAS_MARLINUI_U8GLIB 1 + #elif IS_TFTGLCD_PANEL + // Neither DOGM nor HD44780. Fully customized interface. #elif DISABLED(HAS_GRAPHICAL_TFT) - #define HAS_CHARACTER_LCD 1 + #define HAS_MARLINUI_HD44780 1 #endif #endif @@ -451,7 +495,7 @@ #define HAS_ADC_BUTTONS 1 #endif -#if HAS_GRAPHICAL_LCD +#if HAS_MARLINUI_U8GLIB #ifndef LCD_PIXEL_WIDTH #define LCD_PIXEL_WIDTH 128 #endif @@ -468,7 +512,6 @@ * HOTENDS - Number of hotends, whether connected or separate * E_STEPPERS - Number of actual E stepper motors * E_MANUAL - Number of E steppers for LCD move options - * */ #if EXTRUDERS == 0 @@ -481,6 +524,8 @@ #undef MK2_MULTIPLEXER #undef PRUSA_MMU2 #undef HOTEND_IDLE_TIMEOUT +#elif EXTRUDERS > 1 + #define HAS_MULTI_EXTRUDER 1 #endif #if ENABLED(SWITCHING_EXTRUDER) // One stepper for every two EXTRUDERS @@ -780,8 +825,3 @@ #ifndef EXTRUDE_MINTEMP #define EXTRUDE_MINTEMP 170 #endif - -// This flag indicates if Neopixel pins are shared or separated -#if EITHER(MULTIPLE_NEOPIXEL_TYPES, NEOPIXEL2_INSERIES) - #define CONJOINED_NEOPIXEL 1 -#endif diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h index 35542f9412..d3f608e0a4 100644 --- a/Marlin/src/inc/Conditionals_adv.h +++ b/Marlin/src/inc/Conditionals_adv.h @@ -56,6 +56,15 @@ #undef SHOW_TEMP_ADC_VALUES #endif +#if TEMP_SENSOR_BED == 0 + #undef THERMAL_PROTECTION_BED + #undef THERMAL_PROTECTION_BED_PERIOD +#endif + +#if TEMP_SENSOR_CHAMBER == 0 + #undef THERMAL_PROTECTION_CHAMBER +#endif + #if ENABLED(MIXING_EXTRUDER) && (ENABLED(RETRACT_SYNC_MIXING) || BOTH(FILAMENT_LOAD_UNLOAD_GCODES, FILAMENT_UNLOAD_ALL_EXTRUDERS)) #define HAS_MIXER_SYNC_CHANNEL 1 #endif @@ -187,6 +196,9 @@ #ifndef ACTION_ON_CANCEL #define ACTION_ON_CANCEL "cancel" #endif + #ifndef ACTION_ON_START + #define ACTION_ON_START "start" + #endif #ifndef ACTION_ON_KILL #define ACTION_ON_KILL "poweroff" #endif @@ -410,3 +422,37 @@ #if ANY(AUTO_BED_LEVELING_UBL, AUTO_BED_LEVELING_LINEAR, Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) #define NEED_LSF 1 #endif + +// Flag the indexed serial ports that are in use +#define ANY_SERIAL_IS(N) (defined(SERIAL_PORT) && SERIAL_PORT == (N)) || (defined(SERIAL_PORT_2) && SERIAL_PORT_2 == (N)) || (defined(LCD_SERIAL_PORT) && LCD_SERIAL_PORT == (N)) +#if ANY_SERIAL_IS(-1) + #define USING_SERIAL_DEFAULT +#endif +#if ANY_SERIAL_IS(0) + #define USING_SERIAL_0 1 +#endif +#if ANY_SERIAL_IS(1) + #define USING_SERIAL_1 1 +#endif +#if ANY_SERIAL_IS(2) + #define USING_SERIAL_2 1 +#endif +#if ANY_SERIAL_IS(3) + #define USING_SERIAL_3 1 +#endif +#if ANY_SERIAL_IS(4) + #define USING_SERIAL_4 1 +#endif +#if ANY_SERIAL_IS(5) + #define USING_SERIAL_5 1 +#endif +#if ANY_SERIAL_IS(6) + #define USING_SERIAL_6 1 +#endif +#if ANY_SERIAL_IS(7) + #define USING_SERIAL_7 1 +#endif +#if ANY_SERIAL_IS(8) + #define USING_SERIAL_8 1 +#endif +#undef ANY_SERIAL_IS diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index f566643bdb..80c42955e9 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -149,15 +149,17 @@ #define CORE_AXIS_2 C_AXIS #endif #define CORESIGN(n) (ANY(COREYX, COREZX, COREZY) ? (-(n)) : (n)) +#elif ENABLED(MARKFORGED_XY) + // Markforged kinematics + #define CORE_AXIS_1 A_AXIS + #define CORE_AXIS_2 B_AXIS + #define NORMAL_AXIS Z_AXIS #endif // Calibration codes only for non-core axes #if EITHER(BACKLASH_GCODE, CALIBRATION_GCODE) - #if IS_CORE - #define X_AXIS_INDEX 0 - #define Y_AXIS_INDEX 1 - #define Z_AXIS_INDEX 2 - #define CAN_CALIBRATE(A,B) (A##_AXIS_INDEX == B##_INDEX) + #if EITHER(IS_CORE, MARKFORGED_XY) + #define CAN_CALIBRATE(A,B) (_AXIS(A) == B) #else #define CAN_CALIBRATE(A,B) 1 #endif @@ -311,11 +313,15 @@ #elif ENABLED(MAKRPANEL) #define _LCD_CONTRAST_INIT 17 #elif ENABLED(MINIPANEL) - #define _LCD_CONTRAST_INIT 150 + #define _LCD_CONTRAST_INIT 150 #elif ENABLED(ZONESTAR_12864OLED) #define _LCD_CONTRAST_MIN 64 #define _LCD_CONTRAST_INIT 128 #define _LCD_CONTRAST_MAX 255 +#elif IS_TFTGLCD_PANEL + #define _LCD_CONTRAST_MIN 0 + #define _LCD_CONTRAST_INIT 250 + #define _LCD_CONTRAST_MAX 255 #endif #ifdef _LCD_CONTRAST_INIT @@ -2332,7 +2338,7 @@ #define FILAMENT_CHANGE_SLOW_LOAD_LENGTH 0 #endif -#if EXTRUDERS > 1 && !defined(TOOLCHANGE_FS_EXTRA_PRIME) +#if HAS_MULTI_EXTRUDER && !defined(TOOLCHANGE_FS_EXTRA_PRIME) #define TOOLCHANGE_FS_EXTRA_PRIME 0 #endif @@ -2451,9 +2457,9 @@ /** * Buzzer/Speaker */ -#if PIN_EXISTS(BEEPER) || EITHER(LCD_USE_I2C_BUZZER, PCA9632_BUZZER) +#if PIN_EXISTS(BEEPER) || ANY(LCD_USE_I2C_BUZZER, PCA9632_BUZZER, IS_TFTGLCD_PANEL) #define HAS_BUZZER 1 - #if NONE(LCD_USE_I2C_BUZZER, PCA9632_BUZZER) + #if PIN_EXISTS(BEEPER) #define USE_BEEPER 1 #endif #endif @@ -2481,7 +2487,7 @@ /** * Make sure DOGLCD_SCK and DOGLCD_MOSI are defined. */ -#if HAS_GRAPHICAL_LCD +#if HAS_MARLINUI_U8GLIB #ifndef DOGLCD_SCK #define DOGLCD_SCK SCK_PIN #endif @@ -2602,17 +2608,17 @@ #define HAS_FOLDER_SORTING 1 #endif -#if HAS_SPI_LCD +#if HAS_WIRED_LCD // Get LCD character width/height, which may be overridden by pins, configs, etc. #ifndef LCD_WIDTH - #if HAS_GRAPHICAL_LCD + #if HAS_MARLINUI_U8GLIB #define LCD_WIDTH 21 #else #define LCD_WIDTH TERN(ULTIPANEL, 20, 16) #endif #endif #ifndef LCD_HEIGHT - #if HAS_GRAPHICAL_LCD + #if HAS_MARLINUI_U8GLIB #define LCD_HEIGHT 5 #else #define LCD_HEIGHT TERN(ULTIPANEL, 4, 2) @@ -2620,6 +2626,10 @@ #endif #endif +#if BUTTONS_EXIST(EN1, EN2, ENC) + #define HAS_ROTARY_ENCODER 1 +#endif + #if !NUM_SERIAL #undef BAUD_RATE_GCODE #elif NUM_SERIAL > 1 diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index da5ddc1c2d..5bd6ef7c78 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -477,6 +477,18 @@ #error "HOME_USING_SPREADCYCLE is now obsolete. Please remove it from Configuration_adv.h." #elif defined(DGUS_LCD) #error "DGUS_LCD is now DGUS_LCD_UI_(ORIGIN|FYSETC|HIPRECY). Please update your configuration." +#elif defined(DGUS_SERIAL_PORT) + #error "DGUS_SERIAL_PORT is now LCD_SERIAL_PORT. Please update your configuration." +#elif defined(DGUS_BAUDRATE) + #error "DGUS_BAUDRATE is now LCD_BAUDRATE. Please update your configuration." +#elif defined(DGUS_STATS_RX_BUFFER_OVERRUNS) + #error "DGUS_STATS_RX_BUFFER_OVERRUNS is now STATS_RX_BUFFER_OVERRUNS. Please update your configuration." +#elif defined(DGUS_SERIAL_PORT) + #error "DGUS_SERIAL_PORT is now LCD_SERIAL_PORT. Please update your configuration." +#elif defined(ANYCUBIC_LCD_SERIAL_PORT) + #error "ANYCUBIC_LCD_SERIAL_PORT is now LCD_SERIAL_PORT. Please update your configuration." +#elif defined(INTERNAL_SERIAL_PORT) + #error "INTERNAL_SERIAL_PORT is now MMU2_SERIAL_PORT. Please update your configuration." #elif defined(X_DUAL_ENDSTOPS_ADJUSTMENT) #error "X_DUAL_ENDSTOPS_ADJUSTMENT is now X2_ENDSTOP_ADJUSTMENT. Please update Configuration_adv.h." #elif defined(Y_DUAL_ENDSTOPS_ADJUSTMENT) @@ -582,12 +594,10 @@ #error "SERIAL_XON_XOFF and SERIAL_STATS_* features not supported on USB-native AVR devices." #endif -#if SERIAL_PORT > 7 - #error "Set SERIAL_PORT to the port on your board. Usually this is 0." -#endif - -#if defined(SERIAL_PORT_2) && NUM_SERIAL < 2 - #error "SERIAL_PORT_2 is not supported for your MOTHERBOARD. Disable it to continue." +#ifndef SERIAL_PORT + #error "SERIAL_PORT must be defined in Configuration.h" +#elif defined(SERIAL_PORT_2) && SERIAL_PORT_2 == SERIAL_PORT + #error "SERIAL_PORT_2 cannot be the same as SERIAL_PORT. Please update your configuration." #endif /** @@ -670,7 +680,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS * LCD Info Screen Style */ #if LCD_INFO_SCREEN_STYLE > 0 - #if HAS_GRAPHICAL_LCD || LCD_WIDTH < 20 || LCD_HEIGHT < 4 + #if HAS_MARLINUI_U8GLIB || LCD_WIDTH < 20 || LCD_HEIGHT < 4 #error "Alternative LCD_INFO_SCREEN_STYLE requires 20x4 Character LCD." #elif LCD_INFO_SCREEN_STYLE > 1 #error "LCD_INFO_SCREEN_STYLE only has options 0 and 1 at this time." @@ -683,17 +693,17 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #if ENABLED(LCD_PROGRESS_BAR) #if NONE(SDSUPPORT, LCD_SET_PROGRESS_MANUALLY) #error "LCD_PROGRESS_BAR requires SDSUPPORT or LCD_SET_PROGRESS_MANUALLY." - #elif !HAS_CHARACTER_LCD - #error "LCD_PROGRESS_BAR requires a character LCD." - #elif HAS_GRAPHICAL_LCD + #elif NONE(HAS_MARLINUI_HD44780, IS_TFTGLCD_PANEL) + #error "LCD_PROGRESS_BAR only applies to HD44780 character LCD and TFTGLCD_PANEL_(SPI|I2C)." + #elif HAS_MARLINUI_U8GLIB #error "LCD_PROGRESS_BAR does not apply to graphical displays." #elif ENABLED(FILAMENT_LCD_DISPLAY) #error "LCD_PROGRESS_BAR and FILAMENT_LCD_DISPLAY are not fully compatible. Comment out this line to use both." #elif PROGRESS_MSG_EXPIRE < 0 #error "PROGRESS_MSG_EXPIRE must be greater than or equal to 0." #endif -#elif ENABLED(LCD_SET_PROGRESS_MANUALLY) && NONE(HAS_GRAPHICAL_LCD, HAS_GRAPHICAL_TFT, EXTENSIBLE_UI) - #error "LCD_SET_PROGRESS_MANUALLY requires LCD_PROGRESS_BAR, Graphical LCD, TFT, or EXTENSIBLE_UI." +#elif ENABLED(LCD_SET_PROGRESS_MANUALLY) && NONE(HAS_MARLINUI_U8GLIB, HAS_GRAPHICAL_TFT, HAS_MARLINUI_HD44780, EXTENSIBLE_UI) + #error "LCD_SET_PROGRESS_MANUALLY requires LCD_PROGRESS_BAR, Character LCD, Graphical LCD, TFT, or EXTENSIBLE_UI." #endif #if !HAS_LCD_MENU && ENABLED(SD_REPRINT_LAST_SELECTED_FILE) @@ -703,9 +713,9 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS /** * Custom Boot and Status screens */ -#if ENABLED(SHOW_CUSTOM_BOOTSCREEN) && NONE(HAS_GRAPHICAL_LCD, TOUCH_UI_FTDI_EVE) +#if ENABLED(SHOW_CUSTOM_BOOTSCREEN) && NONE(HAS_MARLINUI_U8GLIB, TOUCH_UI_FTDI_EVE) #error "SHOW_CUSTOM_BOOTSCREEN requires Graphical LCD or TOUCH_UI_FTDI_EVE." -#elif ENABLED(CUSTOM_STATUS_SCREEN_IMAGE) && !HAS_GRAPHICAL_LCD +#elif ENABLED(CUSTOM_STATUS_SCREEN_IMAGE) && !HAS_MARLINUI_U8GLIB #error "CUSTOM_STATUS_SCREEN_IMAGE requires a Graphical LCD." #endif @@ -764,13 +774,15 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #if ENABLED(BABYSTEPPING) #if ENABLED(SCARA) #error "BABYSTEPPING is not implemented for SCARA yet." + #elif BOTH(MARKFORGED_XY, BABYSTEP_XY) + #error "BABYSTEPPING only implemented for Z axis on MarkForged." #elif BOTH(DELTA, BABYSTEP_XY) #error "BABYSTEPPING only implemented for Z axis on deltabots." #elif BOTH(BABYSTEP_ZPROBE_OFFSET, MESH_BED_LEVELING) #error "MESH_BED_LEVELING and BABYSTEP_ZPROBE_OFFSET is not a valid combination" #elif ENABLED(BABYSTEP_ZPROBE_OFFSET) && !HAS_BED_PROBE #error "BABYSTEP_ZPROBE_OFFSET requires a probe." - #elif ENABLED(BABYSTEP_ZPROBE_GFX_OVERLAY) && !HAS_GRAPHICAL_LCD + #elif ENABLED(BABYSTEP_ZPROBE_GFX_OVERLAY) && !HAS_MARLINUI_U8GLIB #error "BABYSTEP_ZPROBE_GFX_OVERLAY requires a Graphical LCD." #elif ENABLED(BABYSTEP_ZPROBE_GFX_OVERLAY) && DISABLED(BABYSTEP_ZPROBE_OFFSET) #error "BABYSTEP_ZPROBE_GFX_OVERLAY requires a BABYSTEP_ZPROBE_OFFSET." @@ -787,6 +799,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #if ENABLED(BABYSTEP_XY) static_assert(BABYSTEP_MULTIPLICATOR_XY <= 0.25f, "BABYSTEP_MULTIPLICATOR_XY must be less than or equal to 0.25mm."); #endif + #elif ENABLED(BABYSTEP_DISPLAY_TOTAL) && ANY(TFT_320x240, TFT_320x240_SPI, TFT_480x320, TFT_480x320_SPI) + #error "New Color UI (TFT_320x240, TFT_320x240_SPI, TFT_480x320, TFT_480x320_SPI) does not support BABYSTEP_DISPLAY_TOTAL yet." #endif #endif @@ -861,7 +875,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS /** * Options only for EXTRUDERS > 1 */ -#if EXTRUDERS > 1 +#if HAS_MULTI_EXTRUDER #if EXTRUDERS > 8 #error "Marlin supports a maximum of 8 EXTRUDERS." @@ -983,7 +997,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS * Mixing Extruder requirements */ #if ENABLED(MIXING_EXTRUDER) - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER #error "For MIXING_EXTRUDER set MIXING_STEPPERS > 1 instead of EXTRUDERS > 1." #elif MIXING_STEPPERS < 2 #error "You must set MIXING_STEPPERS >= 2 for a mixing extruder." @@ -1129,7 +1143,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS /** * Required LCD language */ -#if HAS_CHARACTER_LCD && !defined(DISPLAY_CHARSET_HD44780) +#if HAS_MARLINUI_HD44780 && !defined(DISPLAY_CHARSET_HD44780) #error "You must set DISPLAY_CHARSET_HD44780 to JAPANESE, WESTERN or CYRILLIC for your LCD controller." #endif @@ -1155,8 +1169,9 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS + ENABLED(COREYZ) \ + ENABLED(COREYX) \ + ENABLED(COREZX) \ - + ENABLED(COREZY) - #error "Please enable only one of DELTA, MORGAN_SCARA, COREXY, COREYX, COREXZ, COREZX, COREYZ, or COREZY." + + ENABLED(COREZY) \ + + ENABLED(MARKFORGED_XY) + #error "Please enable only one of DELTA, MORGAN_SCARA, COREXY, COREYX, COREXZ, COREZX, COREYZ, COREZY, or MARKFORGED_XY." #endif /** @@ -1450,7 +1465,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #endif #endif -#if ENABLED(MESH_EDIT_GFX_OVERLAY) && !BOTH(AUTO_BED_LEVELING_UBL, HAS_GRAPHICAL_LCD) +#if ENABLED(MESH_EDIT_GFX_OVERLAY) && !BOTH(AUTO_BED_LEVELING_UBL, HAS_MARLINUI_U8GLIB) #error "MESH_EDIT_GFX_OVERLAY requires AUTO_BED_LEVELING_UBL and a Graphical LCD." #endif @@ -1576,8 +1591,8 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #if ENABLED(DUAL_X_CARRIAGE) #if EXTRUDERS < 2 #error "DUAL_X_CARRIAGE requires 2 (or more) extruders." - #elif CORE_IS_XY || CORE_IS_XZ - #error "DUAL_X_CARRIAGE cannot be used with COREXY, COREYX, COREXZ, or COREZX." + #elif ANY(CORE_IS_XY, CORE_IS_XZ, MARKFORGED_XY) + #error "DUAL_X_CARRIAGE cannot be used with COREXY, COREYX, COREXZ, COREZX, or MARKFORGED_XY." #elif !GOOD_AXIS_PINS(X2) #error "DUAL_X_CARRIAGE requires X2 stepper pins to be defined." #elif !HAS_X_MAX @@ -2116,18 +2131,20 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #if !(_RGB_TEST && PIN_EXISTS(RGB_LED_W)) #error "RGBW_LED requires RGB_LED_R_PIN, RGB_LED_G_PIN, RGB_LED_B_PIN, and RGB_LED_W_PIN." #endif -#elif ENABLED(NEOPIXEL_LED) - #if !(PIN_EXISTS(NEOPIXEL) && NEOPIXEL_PIXELS > 0) +#endif +#undef _RGB_TEST + +// NeoPixel requirements +#if ENABLED(NEOPIXEL_LED) + #if !PIN_EXISTS(NEOPIXEL) || NEOPIXEL_PIXELS == 0 #error "NEOPIXEL_LED requires NEOPIXEL_PIN and NEOPIXEL_PIXELS." - #endif - #elif ENABLED(NEOPIXEL2_SEPARATE) - #if !(PIN_EXISTS(NEOPIXEL2) && NEOPIXEL2_PIXELS > 0) - #error "NEOPIXEL2 requires NEOPIXEL2_PIN and NEOPIXEL2_PIXELS." + #elif ENABLED(NEOPIXEL2_SEPARATE) && !(defined(NEOPIXEL2_TYPE) && PIN_EXISTS(NEOPIXEL2) && NEOPIXEL2_PIXELS > 0) + #error "NEOPIXEL2_SEPARATE requires NEOPIXEL2_TYPE, NEOPIXEL2_PIN and NEOPIXEL2_PIXELS." + #elif ENABLED(NEO2_COLOR_PRESETS) && DISABLED(NEOPIXEL2_SEPARATE) + #error "NEO2_COLOR_PRESETS requires NEOPIXEL2_SEPARATE to be enabled." #endif #endif -#undef _RGB_TEST - #if DISABLED(NO_COMPILE_TIME_PWM) #define _TEST_PWM(P) PWM_PIN(P) #else @@ -2175,16 +2192,16 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #endif /** - * Make sure features that need to write to the SD card are - * disabled unless write support is enabled. + * Make sure features that need to write to the SD card can */ -#if ENABLED(SDCARD_READONLY) +#if ENABLED(SDCARD_READONLY) && ANY(POWER_LOSS_RECOVERY, BINARY_FILE_TRANSFER, SDCARD_EEPROM_EMULATION) + #undef SDCARD_READONLY #if ENABLED(POWER_LOSS_RECOVERY) - #error "POWER_LOSS_RECOVERY is incompatible with SDCARD_READONLY." + #warning "Either disable SDCARD_READONLY or disable POWER_LOSS_RECOVERY." #elif ENABLED(BINARY_FILE_TRANSFER) - #error "BINARY_FILE_TRANSFER is incompatible with SDCARD_READONLY." + #warning "Either disable SDCARD_READONLY or disable BINARY_FILE_TRANSFER." #elif ENABLED(SDCARD_EEPROM_EMULATION) - #error "SDCARD_EEPROM_EMULATION is incompatible with SDCARD_READONLY." + #warning "Either disable SDCARD_READONLY or disable SDCARD_EEPROM_EMULATION." #endif #endif @@ -2257,7 +2274,9 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal + ENABLED(TFT_LVGL_UI_FSMC) \ + ENABLED(TFT_LVGL_UI_SPI) \ + ENABLED(ANYCUBIC_LCD_I3MEGA) \ - + ENABLED(ANYCUBIC_LCD_CHIRON) + + ENABLED(ANYCUBIC_LCD_CHIRON) \ + + ENABLED(TFTGLCD_PANEL_SPI) \ + + ENABLED(TFTGLCD_PANEL_I2C) #error "Please select only one LCD controller option." #endif @@ -2273,6 +2292,25 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #error "Please enable only one LCD_SCREEN_ROT_* option: 0, 90, 180, or 270." #endif +/** + * Serial displays require a dedicated serial port + */ +#ifdef LCD_SERIAL_PORT + #if LCD_SERIAL_PORT == SERIAL_PORT + #error "LCD_SERIAL_PORT cannot be the same as SERIAL_PORT. Please update your configuration." + #elif defined(SERIAL_PORT_2) && LCD_SERIAL_PORT == SERIAL_PORT_2 + #error "LCD_SERIAL_PORT cannot be the same as SERIAL_PORT_2. Please update your configuration." + #endif +#else + #if HAS_DGUS_LCD + #error "The DGUS LCD requires LCD_SERIAL_PORT to be defined in Configuration.h" + #elif EITHER(ANYCUBIC_LCD_I3MEGA, ANYCUBIC_LCD_CHIRON) + #error "The ANYCUBIC LCD requires LCD_SERIAL_PORT to be defined in Configuration.h" + #elif ENABLED(MALYAN_LCD) + #error "MALYAN_LCD requires LCD_SERIAL_PORT to be defined in Configuration.h" + #endif +#endif + /** * FYSETC Mini 12864 RGB backlighting required */ @@ -2533,6 +2571,8 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #error "CoreXZ requires both X and Z to use sensorless homing if either one does." #elif CORE_IS_YZ && Y_SENSORLESS != Z_SENSORLESS && !HOMING_Z_WITH_PROBE #error "CoreYZ requires both Y and Z to use sensorless homing if either one does." +#elif ENABLED(MARKFORGED_XY) && X_SENSORLESS != Y_SENSORLESS + #error "MARKFORGED_XY requires both X and Y to use sensorless homing if either one does." #endif // Other TMC feature requirements @@ -2848,6 +2888,10 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #error "BACKLASH_COMPENSATION requires BACKLASH_DISTANCE_MM." #elif !defined(BACKLASH_CORRECTION) #error "BACKLASH_COMPENSATION requires BACKLASH_CORRECTION." + #elif ENABLED(MARKFORGED_XY) + constexpr float backlash_arr[] = BACKLASH_DISTANCE_MM; + static_assert(!backlash_arr[CORE_AXIS_1] && !backlash_arr[CORE_AXIS_2], + "BACKLASH_COMPENSATION can only apply to " STRINGIFY(NORMAL_AXIS) " on a MarkForged system."); #elif IS_CORE constexpr float backlash_arr[] = BACKLASH_DISTANCE_MM; static_assert(!backlash_arr[CORE_AXIS_1] && !backlash_arr[CORE_AXIS_2], @@ -3039,11 +3083,9 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #undef _PIN_CONFLICT #endif -#if !HAS_GRAPHICAL_LCD +#if !HAS_MARLINUI_U8GLIB #if ENABLED(PRINT_PROGRESS_SHOW_DECIMALS) #error "PRINT_PROGRESS_SHOW_DECIMALS currently requires a Graphical LCD." - #elif ENABLED(SHOW_REMAINING_TIME) - #error "SHOW_REMAINING_TIME currently requires a Graphical LCD." #endif #endif @@ -3093,7 +3135,7 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) * Sanity check for WIFI */ #if EITHER(ESP3D_WIFISUPPORT, WIFISUPPORT) && DISABLED(ARDUINO_ARCH_ESP32) - #error "ESP3D_WIFISUPPORT or WIFISUPPORT requires an ESP32 controller." + #error "ESP3D_WIFISUPPORT or WIFISUPPORT requires an ESP32 MOTHERBOARD." #endif /** diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 74d0cf2ab5..30b21629a6 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -25,7 +25,7 @@ * Release version. Leave the Marlin version or apply a custom scheme. */ #ifndef SHORT_BUILD_VERSION - #define SHORT_BUILD_VERSION "2.0.6.1" + #define SHORT_BUILD_VERSION "2.0.7" #endif /** @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-08-28" + #define STRING_DISTRIBUTION_DATE "2020-09-29" #endif /** @@ -52,7 +52,7 @@ * to alert users to major changes. */ -#define MARLIN_HEX_VERSION 020006 +#define MARLIN_HEX_VERSION 020007 #ifndef REQUIRED_CONFIGURATION_H_VERSION #define REQUIRED_CONFIGURATION_H_VERSION MARLIN_HEX_VERSION #endif diff --git a/Marlin/src/lcd/HD44780/lcdprint_hd44780.cpp b/Marlin/src/lcd/HD44780/lcdprint_hd44780.cpp index 9ba9b871ec..aa3c3c04a1 100644 --- a/Marlin/src/lcd/HD44780/lcdprint_hd44780.cpp +++ b/Marlin/src/lcd/HD44780/lcdprint_hd44780.cpp @@ -14,7 +14,7 @@ #include "../../inc/MarlinConfigPre.h" -#if HAS_CHARACTER_LCD +#if HAS_MARLINUI_HD44780 #include "../ultralcd.h" #include "../../MarlinCore.h" @@ -982,7 +982,7 @@ int lcd_put_wchar_max(wchar_t c, pixel_len_t max_length) { if (max_length < 1) return 0; - // TODO: fix the '\\' that doesnt exist in the HD44870 + // TODO: fix the '\\' that doesn't exist in the HD44870 if (c < 128) { lcd.write((uint8_t)c); return 1; @@ -1119,4 +1119,4 @@ int lcd_put_u8str_max_P(PGM_P utf8_str_P, pixel_len_t max_length) { #endif // DEBUG_LCDPRINT -#endif // HAS_CHARACTER_LCD +#endif // HAS_MARLINUI_HD44780 diff --git a/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp b/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp index 22dd63f68c..e6cc227465 100644 --- a/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp +++ b/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp @@ -22,7 +22,7 @@ #include "../../inc/MarlinConfigPre.h" -#if HAS_CHARACTER_LCD +#if HAS_MARLINUI_HD44780 /** * ultralcd_HD44780.cpp @@ -519,13 +519,13 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const } } -FORCE_INLINE void _draw_heater_status(const heater_ind_t heater, const char prefix, const bool blink) { +FORCE_INLINE void _draw_heater_status(const heater_id_t heater_id, const char prefix, const bool blink) { #if HAS_HEATED_BED - const bool isBed = heater < 0; - const float t1 = (isBed ? thermalManager.degBed() : thermalManager.degHotend(heater)), - t2 = (isBed ? thermalManager.degTargetBed() : thermalManager.degTargetHotend(heater)); + const bool isBed = TERN(HAS_HEATED_CHAMBER, heater_id == H_BED, heater_id < 0); + const float t1 = (isBed ? thermalManager.degBed() : thermalManager.degHotend(heater_id)), + t2 = (isBed ? thermalManager.degTargetBed() : thermalManager.degTargetHotend(heater_id)); #else - const float t1 = thermalManager.degHotend(heater), t2 = thermalManager.degTargetHotend(heater); + const float t1 = thermalManager.degHotend(heater_id), t2 = thermalManager.degTargetHotend(heater_id); #endif if (prefix >= 0) lcd_put_wchar(prefix); @@ -536,14 +536,7 @@ FORCE_INLINE void _draw_heater_status(const heater_ind_t heater, const char pref #if !HEATER_IDLE_HANDLER UNUSED(blink); #else - const bool is_idle = ( - #if HAS_HEATED_BED - isBed ? thermalManager.bed_idle.timed_out : - #endif - thermalManager.hotend_idle[heater].timed_out - ); - - if (!blink && is_idle) { + if (!blink && thermalManager.heater_idle[thermalManager.idle_index_for_id(heater_id)].timed_out) { lcd_put_wchar(' '); if (t2 >= 10) lcd_put_wchar(' '); if (t2 >= 100) lcd_put_wchar(' '); @@ -560,27 +553,14 @@ FORCE_INLINE void _draw_heater_status(const heater_ind_t heater, const char pref } FORCE_INLINE void _draw_bed_status(const bool blink) { - _draw_heater_status(H_BED, ( - #if HAS_LEVELING - planner.leveling_active && blink ? '_' : - #endif - LCD_STR_BEDTEMP[0] - ), - blink - ); + _draw_heater_status(H_BED, TERN0(HAS_LEVELING, blink && planner.leveling_active) ? '_' : LCD_STR_BEDTEMP[0], blink); } #if HAS_PRINT_PROGRESS FORCE_INLINE void _draw_print_progress() { const uint8_t progress = ui.get_progress_percent(); - lcd_put_u8str_P(PSTR( - #if ENABLED(SDSUPPORT) - "SD" - #elif ENABLED(LCD_SET_PROGRESS_MANUALLY) - "P:" - #endif - )); + lcd_put_u8str_P(PSTR(TERN(SDSUPPORT, "SD", "P:"))); if (progress) lcd_put_u8str(ui8tostr3rj(progress)); else @@ -865,10 +845,31 @@ void MarlinUI::draw_status_screen() { lcd_put_wchar('%'); char buffer[14]; - duration_t elapsed = print_job_timer.duration(); - const uint8_t len = elapsed.toDigital(buffer), - timepos = LCD_WIDTH - len - 1; - lcd_put_wchar(timepos, 2, LCD_STR_CLOCK[0]); + uint8_t timepos = 0; + #if ENABLED(SHOW_REMAINING_TIME) + const bool show_remain = TERN1(ROTATE_PROGRESS_DISPLAY, blink) && (printingIsActive() || marlin_state == MF_SD_COMPLETE); + if (show_remain) { + #if ENABLED(USE_M73_REMAINING_TIME) + duration_t remaining = get_remaining_time(); + #else + uint8_t progress = get_progress_percent(); + uint32_t elapsed = print_job_timer.duration(); + duration_t remaining = (progress > 0) ? ((elapsed * 25600 / progress) >> 8) - elapsed : 0; + #endif + const uint8_t len = remaining.toDigital(buffer); + timepos = LCD_WIDTH - 1 - len; + lcd_put_wchar(timepos, 2, 'R'); + } + #else + constexpr bool show_remain = false; + #endif + + if (!show_remain) { + duration_t elapsed = print_job_timer.duration(); + const uint8_t len = elapsed.toDigital(buffer); + timepos = LCD_WIDTH - 1 - len; + lcd_put_wchar(timepos, 2, LCD_STR_CLOCK[0]); + } lcd_put_u8str(buffer); #if LCD_WIDTH >= 20 @@ -990,7 +991,7 @@ void MarlinUI::draw_status_screen() { void MarlinUI::draw_hotend_status(const uint8_t row, const uint8_t extruder) { if (row < LCD_HEIGHT) { lcd_moveto(LCD_WIDTH - 9, row); - _draw_heater_status((heater_ind_t)extruder, LCD_STR_THERMOMETER[0], get_blink()); + _draw_heater_status((heater_id_t)extruder, LCD_STR_THERMOMETER[0], get_blink()); } } @@ -1516,4 +1517,4 @@ void MarlinUI::draw_status_screen() { #endif // HAS_LCD_MENU -#endif // HAS_CHARACTER_LCD +#endif // HAS_MARLINUI_HD44780 diff --git a/Marlin/src/lcd/TFTGLCD/lcdprint_TFTGLCD.cpp b/Marlin/src/lcd/TFTGLCD/lcdprint_TFTGLCD.cpp new file mode 100644 index 0000000000..6cf660a6a9 --- /dev/null +++ b/Marlin/src/lcd/TFTGLCD/lcdprint_TFTGLCD.cpp @@ -0,0 +1,1142 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * @file lcdprint_TFTGLCD.cpp + * @brief LCD print API for TFT-GLCD interface + * @author Yunhui Fu (yhfudev@gmail.com) + * @version 1.0 + * @date 2016-08-19 + * @copyright GPL/BSD + */ + +/** + * The TFTGLCD only supports ??? languages. + */ + +#include "../../inc/MarlinConfigPre.h" + +#if IS_TFTGLCD_PANEL + +#include "../ultralcd.h" +#include "../../MarlinCore.h" +#include "../../libs/numtostr.h" + +#include "ultralcd_TFTGLCD.h" + +#include + +int lcd_glyph_height(void) { return 1; } + +typedef struct _TFTGLCD_charmap_t { + wchar_t uchar; // the unicode char + uint8_t idx; // the glyph of the char in the ROM + uint8_t idx2; // the char used to be combined with the idx to simulate a single char +} TFTGLCD_charmap_t; + +#ifdef __AVR__ + #define IV(a) U##a +#else + #define IV(a) L##a +#endif + +static const TFTGLCD_charmap_t g_TFTGLCD_charmap_device[] PROGMEM = { + // sorted by uchar: + #if DISPLAY_CHARSET_HD44780 == JAPANESE + + {IV('¢'), 0xEC, 0}, // A2 + {IV('°'), 0xDF, 0}, // B0, Marlin special: '°' LCD_STR_DEGREE (0x09) + {IV('ä'), 0xE1, 0}, // E4 + {IV('ö'), 0xEF, 0}, // F6 + {IV('÷'), 0xFD, 0}, // 00F7 + {IV('ü'), 0xF5, 0}, // 00FC + {IV('ˣ'), 0xEB, 0}, // 02E3 + + {IV('·'), 0xA5, 0}, // 0387 + {IV('Ώ'), 0xF4, 0}, // 038F + {IV('Θ'), 0xF2, 0}, // 0398, Theta + {IV('Ξ'), 0xE3, 0}, // 039E, Xi + {IV('Σ'), 0xF6, 0}, // 03A3, Sigma + {IV('Ω'), 0xF4, 0}, // 03A9, Omega + {IV('ά'), 0xE0, 0}, // 03AC + {IV('έ'), 0xE3, 0}, // 03AD + {IV('α'), 0xE0, 0}, // 03B1, alpha + {IV('β'), 0xE2, 0}, // 03B2, beta + {IV('ε'), 0xE3, 0}, // 03B5, epsilon + {IV('θ'), 0xF2, 0}, // 03B8, theta + {IV('μ'), 0xE4, 0}, // 03BC, mu + {IV('ξ'), 0xE3, 0}, // 03BE, xi + {IV('π'), 0xF7, 0}, // 03C0, pi + {IV('ρ'), 0xE6, 0}, // 03C1, rho + {IV('σ'), 0xE5, 0}, // 03C3, sigma + + {IV('←'), 0x7F, 0}, // 2190 + {IV('→'), 0x7E, 0}, // 2192, Marlin special: '⮈⮉⮊⮋➤→' LCD_STR_ARROW_RIGHT (0x03) + {IV('√'), 0xE8, 0}, // 221A + {IV('∞'), 0xF3, 0}, // 221E + {IV('█'), 0xFF, 0}, // 2588 + + //{IV(''), 0xA0, 0}, + {IV('。'), 0xA1, 0}, + {IV('「'), 0xA2, 0}, + {IV('」'), 0xA3, 0}, + {IV('゛'), 0xDE, 0}, // ‶ + {IV('゜'), 0xDF, 0}, // '〫' + {IV('゠'), '=', 0}, + {IV('ァ'), 0xA7, 0}, + {IV('ア'), 0xB1, 0}, + {IV('ィ'), 0xA8, 0}, + {IV('イ'), 0xB2, 0}, + {IV('ゥ'), 0xA9, 0}, + {IV('ウ'), 0xB3, 0}, + {IV('ェ'), 0xAA, 0}, + {IV('エ'), 0xB4, 0}, + {IV('ォ'), 0xAB, 0}, + + {IV('オ'), 0xB5, 0}, + {IV('カ'), 0xB6, 0}, + {IV('ガ'), 0xB6, 0xDE}, + {IV('キ'), 0xB7, 0}, + {IV('ギ'), 0xB7, 0xDE}, // + {IV('ク'), 0xB8, 0}, + {IV('グ'), 0xB8, 0xDE}, + {IV('ケ'), 0xB9, 0}, + {IV('ゲ'), 0xB9, 0xDE}, + {IV('コ'), 0xBA, 0}, + {IV('ゴ'), 0xBA, 0xDE}, + {IV('サ'), 0xBB, 0}, + {IV('ザ'), 0xBB, 0xDE}, + {IV('シ'), 0xBC, 0}, + {IV('ジ'), 0xBC, 0xDE}, + {IV('ス'), 0xBD, 0}, + {IV('ズ'), 0xBD, 0xDE}, + {IV('セ'), 0xBE, 0}, + {IV('ゼ'), 0xBE, 0xDE}, + {IV('ソ'), 0xBF, 0}, + {IV('ゾ'), 0xBF, 0xDE}, + + {IV('タ'), 0xC0, 0}, + {IV('ダ'), 0xC0, 0xDE}, + {IV('チ'), 0xC1, 0}, + {IV('ヂ'), 0xC1, 0xDE}, + {IV('ッ'), 0xAF, 0}, + {IV('ツ'), 0xC2, 0}, + {IV('ヅ'), 0xC2, 0xDE}, + {IV('テ'), 0xC3, 0}, + {IV('デ'), 0xC3, 0xDE}, + {IV('ト'), 0xC4, 0}, + {IV('ド'), 0xC4, 0xDE}, + {IV('ナ'), 0xC5, 0}, + {IV('ニ'), 0xC6, 0}, + {IV('ヌ'), 0xC7, 0}, + {IV('ネ'), 0xC8, 0}, + {IV('ノ'), 0xC9, 0}, + {IV('ハ'), 0xCA, 0}, + {IV('バ'), 0xCA, 0xDE}, + {IV('パ'), 0xCA, 0xDF}, + {IV('ヒ'), 0xCB, 0}, + {IV('ビ'), 0xCB, 0xDE}, + {IV('ピ'), 0xCB, 0xDF}, + {IV('フ'), 0xCC, 0}, + {IV('ブ'), 0xCC, 0xDE}, + {IV('プ'), 0xCC, 0xDF}, + {IV('ヘ'), 0xCD, 0}, + {IV('ベ'), 0xCD, 0xDE}, + {IV('ペ'), 0xCD, 0xDF}, + {IV('ホ'), 0xCE, 0}, + {IV('ボ'), 0xCE, 0xDE}, + {IV('ポ'), 0xCE, 0xDF}, + {IV('マ'), 0xCF, 0}, + + {IV('ミ'), 0xD0, 0}, + {IV('ム'), 0xD1, 0}, + {IV('メ'), 0xD2, 0}, + {IV('モ'), 0xD3, 0}, + {IV('ャ'), 0xAC, 0}, + {IV('ヤ'), 0xD4, 0}, + {IV('ュ'), 0xAD, 0}, + {IV('ユ'), 0xD5, 0}, + {IV('ョ'), 0xAE, 0}, + {IV('ヨ'), 0xD6, 0}, + {IV('ラ'), 0xD7, 0}, + {IV('リ'), 0xD8, 0}, + {IV('ル'), 0xD9, 0}, + {IV('レ'), 0xDA, 0}, + {IV('ロ'), 0xDB, 0}, + {IV('ワ'), 0xDC, 0}, + {IV('ヲ'), 0xA6, 0}, + {IV('ン'), 0xDD, 0}, + {IV('ヴ'), 0xB3, 0xDE}, + {IV('ヷ'), 0xDC, 0xDE}, + {IV('ヺ'), 0xA6, 0xDE}, + {IV('・'), 0xA5, 0}, + {IV('ー'), 0xB0, 0}, + {IV('ヽ'), 0xA4, 0}, + + //{IV('g'), 0xE7, 0}, // error + //{IV(''), 0xE9, 0}, + //{IV('j'), 0xEA, 0}, // error + //{IV(''), 0xED, 0}, + //{IV(''), 0xEE, 0}, + + //{IV('p'), 0xF0, 0}, // error + //{IV('q'), 0xF1, 0}, // error + //{IV(''), 0xF8, 0}, + //{IV('y'), 0xF9, 0}, // error + {IV('万'), 0xFB, 0}, + {IV('円'), 0xFC, 0}, + {IV('千'), 0xFA, 0}, + //{IV(''), 0xFE, 0}, + + //、・ヲァィゥェォャュョッー + {IV('、'), 0xA4, 0}, //ヽ + {IV('・'), 0xA5, 0}, //・ + {IV('ヲ'), 0xA6, 0}, //ヲ + {IV('ァ'), 0xA7, 0}, //ァ + {IV('ィ'), 0xA8, 0}, //ィ + {IV('ゥ'), 0xA9, 0}, //ゥ + {IV('ェ'), 0xAA, 0}, //ェ + {IV('ォ'), 0xAB, 0}, //ォ + {IV('ャ'), 0xAC, 0}, //ャ + {IV('ュ'), 0xAD, 0}, //ュ + {IV('ョ'), 0xAE, 0}, //ョ + {IV('ッ'), 0xAF, 0}, //ッ + {IV('ー'), 0xB0, 0}, //ー + + //アイウエオカキクケコサシスセ + {IV('ア'), 0xB1, 0}, //ア + {IV('イ'), 0xB2, 0}, //イ + {IV('ウ'), 0xB3, 0}, //ウ + {IV('エ'), 0xB4, 0}, //エ + {IV('オ'), 0xB5, 0}, //オ + {IV('カ'), 0xB6, 0}, //カ + {IV('キ'), 0xB7, 0}, //キ + {IV('ク'), 0xB8, 0}, //ク + {IV('ケ'), 0xB9, 0}, //ケ + {IV('コ'), 0xBA, 0}, //コ + {IV('サ'), 0xBB, 0}, //サ + {IV('シ'), 0xBC, 0}, //シ + {IV('ス'), 0xBD, 0}, //ス + {IV('セ'), 0xBE, 0}, //セ + + //ソタチツテトナニヌネノハヒフ + {IV('ソ'), 0xBF, 0}, //ソ + {IV('タ'), 0xC0, 0}, //タ + {IV('チ'), 0xC1, 0}, //チ + {IV('ツ'), 0xC2, 0}, //ツ + {IV('テ'), 0xC3, 0}, //テ + {IV('ト'), 0xC4, 0}, //ト + {IV('ナ'), 0xC5, 0}, //ナ + {IV('ニ'), 0xC6, 0}, //ニ + {IV('ヌ'), 0xC7, 0}, //ヌ + {IV('ネ'), 0xC8, 0}, //ネ + {IV('ノ'), 0xC9, 0}, //ノ + {IV('ハ'), 0xCA, 0}, //ハ + {IV('ヒ'), 0xCB, 0}, //ヒ + {IV('フ'), 0xCC, 0}, //フ + + //ヘホマミムメモヤユヨラリルレロワン゙゚ + {IV('ヘ'), 0xCD, 0}, //ヘ + {IV('ホ'), 0xCE, 0}, //ホ + {IV('マ'), 0xCF, 0}, //マ + {IV('ミ'), 0xD0, 0}, //ミ + {IV('ム'), 0xD1, 0}, //ム + {IV('メ'), 0xD2, 0}, //メ + {IV('モ'), 0xD3, 0}, //モ + {IV('ヤ'), 0xD4, 0}, //ヤ + {IV('ユ'), 0xD5, 0}, //ユ + {IV('ヨ'), 0xD6, 0}, //ヨ + {IV('ラ'), 0xD7, 0}, //ラ + {IV('リ'), 0xD8, 0}, //リ + {IV('ル'), 0xD9, 0}, //ル + {IV('レ'), 0xDA, 0}, //レ + {IV('ロ'), 0xDB, 0}, //ロ + {IV('ワ'), 0xDC, 0}, //ワ + {IV('ン'), 0xDD, 0}, //ン + {IV('゙'), 0xDE, 0}, // ゛ + {IV('゚'), 0xDF, 0}, // ゜ + + {IV('¥'), 0x5C, 0}, + + #elif DISPLAY_CHARSET_HD44780 == WESTERN + // 0x10 -- 0x1F (except 0x1C) + // 0x80 -- 0xFF (except 0xA7,0xB0,0xB1,0xB3,0xB4,0xBF,0xD1,0xF8,0xFA,0xFC-0xFF) + + {IV('¡'), 0xA9, 0}, + {IV('¢'), 0xA4, 0}, + {IV('£'), 0xA5, 0}, + {IV('¥'), 0xA6, 0}, + {IV('§'), 0xD2, 0}, // section sign + {IV('©'), 0xCF, 0}, + + {IV('ª'), 0x9D, 0}, + {IV('«'), 0xBB, 0}, + {IV('®'), 0xCE, 0}, + + {IV('°'), 0xB2, 0}, // Marlin special: '°' LCD_STR_DEGREE (0x09) + //{IV(''), 0xD1, 0}, + {IV('±'), 0x10, 0}, //∓± + //{'='), 0x1C, 0}, // error + {IV('²'), 0x1E, 0}, + {IV('³'), 0x1F, 0}, + {IV('¶'), 0xD3, 0}, // pilcrow sign + {IV('º'), 0x9E, 0}, + {IV('»'), 0xBC, 0}, // 00BB + //{IV(''), 0xB3, 0}, // error + //{IV(''), 0xB4, 0}, // error + {IV('¼'), 0xB6, 0}, // 00BC + {IV('½'), 0xB5, 0}, // 00BD + //{IV('¾'), '3', 0}, // 00BE + {IV('¿'), 0x9F, 0}, // 00BF + + {IV('Â'), 0x8F, 0}, + {IV('Ã'), 0xAA, 0}, + {IV('Ä'), 0x8E, 0}, + {IV('Æ'), 0x92, 0}, + {IV('Ç'), 0x80, 0}, + {IV('É'), 0x90, 0}, + {IV('Ñ'), 0x9C, 0}, + {IV('Õ'), 0xAC, 0}, + {IV('Ö'), 0x99, 0}, + {IV('×'), 0xB7, 0}, + {IV('Ø'), 0xAE, 0}, + {IV('Ü'), 0x9A, 0}, + {IV('à'), 0x85, 0}, + {IV('á'), 0xA0, 0}, + {IV('â'), 0x83, 0}, + {IV('ã'), 0xAB, 0}, + {IV('ä'), 0x84, 0}, + {IV('å'), 0x86, 0}, + {IV('æ'), 0x91, 0}, + {IV('ç'), 0x87, 0}, + {IV('è'), 0x8A, 0}, + {IV('é'), 0x82, 0}, + {IV('ê'), 0x88, 0}, + {IV('ë'), 0x89, 0}, + {IV('ì'), 0x8D, 0}, + {IV('í'), 0xA1, 0}, + {IV('î'), 0x8C, 0}, + {IV('ï'), 0x8B, 0}, + + {IV('ñ'), 0x9B, 0}, + {IV('ò'), 0x95, 0}, + {IV('ó'), 0xA2, 0}, + {IV('ô'), 0x93, 0}, + {IV('õ'), 0xAD, 0}, + {IV('ö'), 0x94, 0}, + {IV('÷'), 0xB8, 0}, + {IV('ø'), 0xAF, 0}, + {IV('ù'), 0x97, 0}, + {IV('ú'), 0xA3, 0}, + {IV('û'), 0x96, 0}, + {IV('ü'), 0x81, 0}, + {IV('ÿ'), 0x98, 0}, + + //{IV(''), 0xB0, 0}, // error + //{IV(''), 0xB1, 0}, // error + {IV('ƒ'), 0xA8, 0}, // 0192 + + {IV('Ύ'), 0xDB, 0}, // 038E + {IV('Ώ'), 0xDE, 0}, // 038F + {IV('ΐ'), 0xE7, 0}, // 0390 + + {IV('Γ'), 0xD4, 0}, // 0393, Gamma + {IV('Δ'), 0xD5, 0}, // 0394, Delta, ◿ + {IV('Θ'), 0xD6, 0}, // 0398, Theta + {IV('Λ'), 0xD7, 0}, // 039B, Lambda + {IV('Ξ'), 0xD8, 0}, // 039E, Xi + {IV('Π'), 0xD9, 0}, // Pi + {IV('Σ'), 0xDA, 0}, // Sigma + {IV('Υ'), 0xDB, 0}, // Upsilon + {IV('Φ'), 0xDC, 0}, // Phi + {IV('Ψ'), 0xDD, 0}, // Psi + {IV('Ω'), 0xDE, 0}, // Omega + + {IV('ά'), 0xDF, 0}, // 03AC + {IV('έ'), 0xE3, 0}, // 03AD + {IV('ή'), 0xE5, 0}, // 03AE + {IV('ί'), 0xE7, 0}, // 03AF + {IV('ΰ'), 0xF1, 0}, // 03B0 + + {IV('α'), 0xDF, 0}, // alpha + {IV('β'), 0xE0, 0}, // beta + {IV('γ'), 0xE1, 0}, // gamma + {IV('δ'), 0xE2, 0}, // delta + {IV('ε'), 0xE3, 0}, // epsilon + {IV('ζ'), 0xE4, 0}, // zeta + {IV('η'), 0xE5, 0}, // eta + {IV('θ'), 0xE6, 0}, // theta + {IV('ι'), 0xE7, 0}, // lota + {IV('κ'), 0xE8, 0}, // kappa + {IV('λ'), 0xE9, 0}, // lambda + {IV('μ'), 0xEA, 0}, // mu + {IV('ν'), 0xEB, 0}, // nu + {IV('ξ'), 0xEC, 0}, // xi + {IV('π'), 0xED, 0}, // pi + {IV('ρ'), 0xEE, 0}, // rho + {IV('σ'), 0xEF, 0}, // sigma + + {IV('τ'), 0xF0, 0}, // tau + {IV('υ'), 0xF1, 0}, // upsilon + {IV('χ'), 0xF2, 0}, // chi + {IV('ψ'), 0xF3, 0}, // psi + {IV('ω'), 0xF4, 0}, // 03C9, omega + {IV('ϊ'), 0xE7, 0}, // 03CA + {IV('ϋ'), 0xF1, 0}, // 03CB + {IV('ύ'), 0xF1, 0}, // 03CD + {IV('ώ'), 0xF4, 0}, // 03CE + + {IV('•'), 0xCD, 0}, // · + {IV('℞'), 0xA7, 0}, // ℞ Pt ASCII 158 + {IV('™'), 0xD0, 0}, + {IV('↤'), 0xF9, 0}, // ⟻ + {IV('↵'), 0xC4, 0}, + {IV('↻'), 0x04, 0}, // Marlin special: '↻↺⟳⟲' LCD_STR_REFRESH (0x01) + {IV('⇥'), 0xFB, 0}, + {IV('√'), 0xBE, 0}, // √ + {IV('∞'), 0xC2, 0}, // infinity + {IV('∫'), 0x1B, 0}, + {IV('∼'), 0x1D, 0}, + {IV('≈'), 0x1A, 0}, + {IV('≠'), 0xBD, 0}, + {IV('≡'), 0x11, 0}, + {IV('≤'), 0xB9, 0},// ≤≥ ⩽⩾ + {IV('≥'), 0xBA, 0}, + //{IV(''), 0xBF, 0}, // error + + {IV('⌠'), 0xC0, 0}, + {IV('⌡'), 0xC1, 0}, + + {IV('⎧'), 0x14, 0}, + {IV('⎩'), 0x15, 0}, + {IV('⎫'), 0x16, 0}, + {IV('⎭'), 0x17, 0}, + {IV('⎰'), 0x18, 0}, + {IV('⎱'), 0x19, 0}, + {IV('⎲'), 0x12, 0}, + {IV('⎳'), 0x13, 0}, + + {IV('⏱'), 0x07, 0}, // Marlin special: '🕐🕑🕒🕓🕔🕕🕖🕗🕘🕙🕚🕛🕜🕝🕞🕟🕠🕡🕢🕣🕤🕥🕦🕧 ⌚⌛⏰⏱⏳⧖⧗' LCD_STR_CLOCK (0x05) + {IV('┌'), 0xC9, 0}, + {IV('┐'), 0xCA, 0}, + {IV('└'), 0xCB, 0}, + {IV('┘'), 0xCC, 0}, + {IV('◸'), 0xC3, 0}, // ◿ + {IV('⭠'), 0xC8, 0}, + {IV('⭡'), 0xC5, 0}, + {IV('⭢'), 0xC7, 0}, + {IV('⭣'), 0xC6, 0}, + + + {IV('⯆'), 0xF5, 0}, + {IV('⯇'), 0xF7, 0}, // ⯅ + {IV('⯈'), 0xF6, 0}, + //{IV(''), 0xF8, 0}, // error + //{IV(''), 0xFA, 0}, // error + //{IV(''), 0xFC, 0}, // error + //{IV(''), 0xFD, 0}, // error + //{IV(''), 0xFE, 0}, // error + //{IV(''), 0xFF, 0}, // error + + #elif DISPLAY_CHARSET_HD44780 == CYRILLIC + + #ifdef CONVERT_TO_EXT_ASCII + {IV('°'), 0x01, 0}, // 00B0, Marlin special: '°' LCD_STR_DEGREE (0x09) + {IV('²'), 0x0e, 0}, // 0x32 if no special symbol in panel font + {IV('³'), 0x0f, 0}, // 0x33 if no special symbol in panel font + + // translate to cp866 codepage + //first ASCII symbols in panel font must be replaced with Marlin special symbols + {IV('Ё'), 0xF0, 0}, // 0401 + {IV('Є'), 0xF2, 0}, // 0404 + {IV('І'), 'I', 0}, // 0406 + {IV('Ї'), 0xF4, 0}, // 0407 + {IV('Ў'), 0xF6, 0}, // 040E + {IV('А'), 0x80, 0}, // 0410 + {IV('Б'), 0x81, 0}, + {IV('В'), 0x82, 0}, + {IV('Г'), 0x83, 0}, + {IV('Д'), 0x84, 0}, + {IV('Е'), 0x85, 0}, + {IV('Ж'), 0x86, 0}, + {IV('З'), 0x87, 0}, + {IV('И'), 0x88, 0}, + {IV('Й'), 0x89, 0}, + {IV('К'), 0x8A, 0}, + {IV('Л'), 0x8B, 0}, + {IV('М'), 0x8C, 0}, + {IV('Н'), 0x8D, 0}, + {IV('О'), 0x8E, 0}, + {IV('П'), 0x8F, 0}, + {IV('Р'), 0x90, 0}, + {IV('С'), 0x91, 0}, + {IV('Т'), 0x92, 0}, + {IV('У'), 0x93, 0}, + {IV('Ф'), 0x94, 0}, + {IV('Х'), 0x95, 0}, + {IV('Ц'), 0x96, 0}, + {IV('Ч'), 0x97, 0}, + {IV('Ш'), 0x98, 0}, + {IV('Щ'), 0x99, 0}, + {IV('Ъ'), 0x9A, 0}, + {IV('Ы'), 0x9B, 0}, + {IV('Ь'), 0x9C, 0}, + {IV('Э'), 0x9D, 0}, + {IV('Ю'), 0x9E, 0}, + {IV('Я'), 0x9F, 0}, + + {IV('а'), 0xA0, 0}, + {IV('б'), 0xA1, 0}, + {IV('в'), 0xA2, 0}, + {IV('г'), 0xA3, 0}, + {IV('д'), 0xA4, 0}, + {IV('е'), 0xA5, 0}, + {IV('ж'), 0xA6, 0}, + {IV('з'), 0xA7, 0}, + {IV('и'), 0xA8, 0}, + {IV('й'), 0xA9, 0}, + {IV('к'), 0xAA, 0}, + {IV('л'), 0xAB, 0}, + {IV('м'), 0xAC, 0}, + {IV('н'), 0xAD, 0}, + {IV('о'), 0xAE, 0}, + {IV('п'), 0xAF, 0}, + {IV('р'), 0xE0, 0}, + {IV('с'), 0xE1, 0}, + {IV('т'), 0xE2, 0}, + {IV('у'), 0xE3, 0}, + {IV('ф'), 0xE4, 0}, + {IV('х'), 0xE5, 0}, + {IV('ц'), 0xE6, 0}, + {IV('ч'), 0xE7, 0}, + {IV('ш'), 0xE8, 0}, + {IV('щ'), 0xE9, 0}, + {IV('ъ'), 0xEA, 0}, + {IV('ы'), 0xEB, 0}, + {IV('ь'), 0xEC, 0}, + {IV('э'), 0xED, 0}, + {IV('ю'), 0xEE, 0}, + {IV('я'), 0xEF, 0}, // 044F + {IV('ё'), 0xF1, 0}, // 0451 + {IV('є'), 0xF3, 0}, // 0454 + {IV('і'), 'i', 0}, // 0456 + {IV('ї'), 0xF5, 0}, // 0457 + {IV('ў'), 0xF7, 0}, // 045E + + #else + + {IV('¢'), 0x5C, 0}, // 00A2 + {IV('£'), 0xCF, 0}, // 00A3 + {IV('°'), 0x01, 0}, // 00B0, Marlin special: '°' LCD_STR_DEGREE (0x09) + + //{IV(''), 0x80, 0}, + //{IV(''), 0x81, 0}, + //{IV(''), 0x82, 0}, + //{IV(''), 0x83, 0}, + //{IV(''), 0x84, 0}, + //{IV(''), 0x85, 0}, + //{IV(''), 0x86, 0}, + //{IV(''), 0x87, 0}, + //{IV(''), 0x88, 0}, + //{IV(''), 0x89, 0}, + //{IV(''), 0x8A, 0}, + //{IV(''), 0x8B, 0}, + //{IV(''), 0x8C, 0}, + //{IV(''), 0x8D, 0}, + //{IV(''), 0x8E, 0}, + //{IV(''), 0x8F, 0}, + + //{IV(''), 0x90, 0}, + //{IV(''), 0x91, 0}, + //{IV(''), 0x92, 0}, + //{IV(''), 0x93, 0}, + //{IV(''), 0x94, 0}, + //{IV(''), 0x95, 0}, + //{IV(''), 0x96, 0}, + //{IV(''), 0x97, 0}, + //{IV(''), 0x98, 0}, + //{IV(''), 0x99, 0}, + //{IV(''), 0x9A, 0}, + //{IV(''), 0x9B, 0}, + //{IV(''), 0x9C, 0}, + //{IV(''), 0x9D, 0}, + //{IV(''), 0x9E, 0}, + //{IV(''), 0x9F, 0}, + + {IV('¼'), 0xF0, 0}, // 00BC + {IV('⅓'), 0xF1, 0}, + {IV('½'), 0xF2, 0}, // 00BD + {IV('¾'), 0xF3, 0}, // 00BE + {IV('¿'), 0xCD, 0}, // 00BF + + {IV('Ё'), 0xA2, 0}, // 0401 + {IV('А'), 'A', 0}, // 0410 + {IV('Б'), 0xA0, 0}, + {IV('В'), 'B', 0}, + {IV('Г'), 0xA1, 0}, + {IV('Д'), 0xE0, 0}, + {IV('Е'), 'E', 0}, + {IV('Ж'), 0xA3, 0}, + {IV('З'), 0xA4, 0}, + {IV('И'), 0xA5, 0}, + {IV('Й'), 0xA6, 0}, + {IV('К'), 'K', 0}, + {IV('Л'), 0xA7, 0}, + {IV('М'), 'M', 0}, + {IV('Н'), 'H', 0}, + {IV('О'), 'O', 0}, + {IV('П'), 0xA8, 0}, + {IV('Р'), 'P', 0}, + {IV('С'), 'C', 0}, + {IV('Т'), 'T', 0}, + {IV('У'), 0xA9, 0}, + {IV('Ф'), 0xAA, 0}, + {IV('Х'), 'X', 0}, + {IV('Ц'), 0xE1, 0}, + {IV('Ч'), 0xAB, 0}, + {IV('Ш'), 0xAC, 0}, + {IV('Щ'), 0xE2, 0}, + {IV('Ъ'), 0xAD, 0}, + {IV('Ы'), 0xAE, 0}, + {IV('Ь'), 'b', 0}, + {IV('Э'), 0xAF, 0}, + {IV('Ю'), 0xB0, 0}, + {IV('Я'), 0xB1, 0}, + {IV('а'), 'a', 0}, + + {IV('б'), 0xB2, 0}, + {IV('в'), 0xB3, 0}, + {IV('г'), 0xB4, 0}, + {IV('д'), 0xE3, 0}, + {IV('е'), 'e', 0}, + {IV('ж'), 0xB6, 0}, + {IV('з'), 0xB7, 0}, + {IV('и'), 0xB8, 0}, + {IV('й'), 0xB9, 0}, + {IV('к'), 0xBA, 0}, + {IV('л'), 0xBB, 0}, + {IV('м'), 0xBC, 0}, + {IV('н'), 0xBD, 0}, + {IV('о'), 'o', 0}, + {IV('п'), 0xBE, 0}, + {IV('р'), 'p', 0}, + {IV('с'), 'c', 0}, + {IV('т'), 0xBF, 0}, + + {IV('у'), 'y', 0}, + {IV('ф'), 0xE4, 0}, + {IV('х'), 'x', 0}, + {IV('ц'), 0xE5, 0}, + {IV('ч'), 0xC0, 0}, + {IV('ш'), 0xC1, 0}, + {IV('щ'), 0xE6, 0}, + {IV('ъ'), 0xC2, 0}, + {IV('ы'), 0xC3, 0}, + {IV('ь'), 0xC4, 0}, + {IV('э'), 0xC5, 0}, + {IV('ю'), 0xC6, 0}, + {IV('я'), 0xC7, 0}, // 044F + {IV('ё'), 0xB5, 0}, // 0451 + //{IV(''), 0xC8, 0}, + //{IV(''), 0xC9, 0}, + //{IV(''), 0xCA, 0}, + //{IV(''), 0xCB, 0}, + //{IV(''), 0xCC, 0}, + //{IV(''), 0xCD, 0}, + //{IV(''), 0xCE, 0}, + + //{IV(''), 0xD0, 0}, + //{IV(''), 0xD1, 0}, + //{IV(''), 0xD2, 0}, + //{IV(''), 0xD3, 0}, + //{IV(''), 0xD4, 0}, + //{IV(''), 0xD5, 0}, + //{IV(''), 0xD6, 0}, + //{IV(''), 0xD7, 0}, + //{IV(''), 0xD8, 0}, + //{IV(''), 0xDB, 0}, + //{IV(''), 0xDC, 0}, + //{IV(''), 0xDD, 0}, + //{IV(''), 0xDE, 0}, + //{IV(''), 0xDF, 0}, + + //{IV(''), 0xE7, 0}, + //{IV(''), 0xE8, 0}, + //{IV(''), 0xE9, 0}, + //{IV(''), 0xEA, 0}, + //{IV(''), 0xEB, 0}, + //{IV(''), 0xEC, 0}, + //{IV(''), 0xED, 0}, + //{IV(''), 0xEE, 0}, + //{IV(''), 0xEF, 0}, + + //{IV(''), 0xF4, 0}, + //{IV(''), 0xF5, 0}, + //{IV(''), 0xF6, 0}, + //{IV(''), 0xF7, 0}, + //{IV(''), 0xF8, 0}, + //{IV(''), 0xF9, 0}, + //{IV(''), 0xFA, 0}, + //{IV(''), 0xFB, 0}, + //{IV(''), 0xFC, 0}, + //{IV(''), 0xFD, 0}, + //{IV(''), 0xFE, 0}, + //{IV(''), 0xFF, 0}, + + {IV('↑'), 0xD9, 0}, // 2191 ←↑→↓ + {IV('↓'), 0xDA, 0}, // 2193 + + #endif + + #endif +}; + +// the plain ASCII replacement for various char +static const TFTGLCD_charmap_t g_TFTGLCD_charmap_common[] PROGMEM = { + {IV('¡'), 'i', 0}, // A1 + {IV('¢'), 'c', 0}, // A2 + {IV('°'), 0x09, 0}, // B0 Marlin special: '°' LCD_STR_DEGREE (0x09) + + #ifndef CONVERT_TO_EXT_ASCII //this time CONVERT_TO_EXT_ASCII works only with en, ru and uk languages + + // map WESTERN code to the plain ASCII + {IV('Á'), 'A', 0}, // C1 + {IV('Â'), 'A', 0}, // C2 + {IV('Ã'), 'A', 0}, // C3 + {IV('Ä'), 'A', 0}, // C4 + {IV('Å'), 'A', 0}, // C5 + {IV('Æ'), 'A', 'E'}, // C6 + {IV('Ç'), 'C', 0}, // C7 + {IV('È'), 'E', 0}, // C8 + {IV('É'), 'E', 0}, // C9 + {IV('Í'), 'I', 0}, // CD + {IV('Ñ'), 'N', 0}, // D1 + {IV('Õ'), 'O', 0}, // D5 + {IV('Ö'), 'O', 0}, // D6 + {IV('×'), 'x', 0}, // D7 + {IV('Ü'), 'U', 0}, // DC + {IV('Ý'), 'Y', 0}, // DD + {IV('à'), 'a', 0}, // E0 + {IV('á'), 'a', 0}, + {IV('â'), 'a', 0}, + {IV('ã'), 'a', 0}, + {IV('ä'), 'a', 0}, + {IV('å'), 'a', 0}, + {IV('æ'), 'a', 'e'}, + {IV('ç'), 'c', 0}, + {IV('è'), 'e', 0}, // 00E8 + {IV('é'), 'e', 0}, + {IV('ê'), 'e', 0}, + {IV('ë'), 'e', 0}, + {IV('ì'), 'i', 0}, // 00EC + {IV('í'), 'i', 0}, + {IV('î'), 'i', 0}, + {IV('ï'), 'i', 0}, // 00EF + + {IV('ñ'), 'n', 0}, // 00F1 + {IV('ò'), 'o', 0}, + {IV('ó'), 'o', 0}, + {IV('ô'), 'o', 0}, + {IV('õ'), 'o', 0}, + {IV('ö'), 'o', 0}, + //{IV('÷'), 0xB8, 0}, + {IV('ø'), 'o', 0}, + {IV('ù'), 'u', 0}, + {IV('ú'), 'u', 0}, + {IV('û'), 'u', 0}, + {IV('ü'), 'u', 0}, // FC + {IV('ý'), 'y', 0}, // FD + {IV('ÿ'), 'y', 0}, // FF + + {IV('Ą'), 'A', 0}, // 0104 + {IV('ą'), 'a', 0}, // 0105 + {IV('Ć'), 'C', 0}, // 0106 + {IV('ć'), 'c', 0}, // 0107 + {IV('Č'), 'C', 0}, // 010C + {IV('č'), 'c', 0}, // 010D + {IV('Ď'), 'D', 0}, // 010E + {IV('ď'), 'd', 0}, // 010F + {IV('đ'), 'd', 0}, // 0111 + {IV('ę'), 'e', 0}, // 0119 + {IV('ğ'), 'g', 0}, // 011F + {IV('İ'), 'I', 0}, // 0130 + {IV('ı'), 'i', 0}, // 0131 + + {IV('Ł'), 'L', 0}, // 0141 + {IV('ł'), 'l', 0}, // 0142 + {IV('Ń'), 'N', 0}, // 0143 + {IV('ń'), 'n', 0}, // 0144 + {IV('ň'), 'n', 0}, // 0148 + + {IV('ř'), 'r', 0}, // 0159 + {IV('Ś'), 'S', 0}, // 015A + {IV('ś'), 's', 0}, // 015B + {IV('ş'), 's', 0}, // 015F + {IV('Š'), 'S', 0}, // 0160 + {IV('š'), 's', 0}, // 0161 + {IV('ť'), 't', 0}, // 0165 + {IV('ů'), 'u', 0}, // 016F + {IV('ż'), 'z', 0}, // 017C + {IV('Ž'), 'Z', 0}, // 017D + {IV('ž'), 'z', 0}, // 017E + {IV('ƒ'), 'f', 0}, // 0192 + + {IV('ˣ'), 'x', 0}, // 02E3 + + {IV('΄'), '\'', 0}, // 0384 + {IV('΅'), '\'', 0}, // 0385 + {IV('Ά'), 'A', 0}, // 0386 + {IV('·'), '.', 0}, // 0387 + {IV('Έ'), 'E', 0}, // 0388 + {IV('Ή'), 'H', 0}, // 0389 + {IV('Ί'), 'I', 0}, // 038A + {IV('Ό'), 'O', 0}, // 038C + {IV('Ύ'), 'Y', 0}, // 038E + {IV('Ώ'), 'O', 0}, // 038F + {IV('ΐ'), 'i', 0}, // 0390 + {IV('Α'), 'A', 0}, // 0391 + {IV('Β'), 'B', 0}, // 0392 + {IV('Γ'), 'T', 0}, // 0393, Gamma + {IV('Δ'), '4', 0}, // 0394, Delta, ◿ + {IV('Ε'), 'E', 0}, // 0395 + {IV('Ζ'), 'Z', 0}, // 0396 + {IV('Η'), 'H', 0}, // 0397 + {IV('Θ'), '0', 0}, // 0398, Theta + {IV('Ι'), 'I', 0}, // 0399 + {IV('Κ'), 'K', 0}, // 039A + {IV('Λ'), '^', 0}, // 039B, Lambda + {IV('Μ'), 'M', 0}, // 039C + {IV('Ν'), 'N', 0}, // 039D + {IV('Ξ'), '3', 0}, // 039E, Xi + {IV('Ο'), 'O', 0}, // 039F + {IV('Π'), 'n', 0}, // 03A0, Pi + {IV('Ρ'), 'P', 0}, // 03A1 + {IV('Σ'), 'E', 0}, // 03A3, Sigma + {IV('Τ'), 'T', 0}, // 03A4 + {IV('Υ'), 'Y', 0}, // 03A5, Upsilon + {IV('Φ'), 'p', 0}, // 03A6, Phi + {IV('Χ'), 'X', 0}, // 03A7 + {IV('Ψ'), 'P', 0}, // 03A8, Psi + {IV('Ω'), 'O', 0}, // 03A9, Omega + {IV('Ϊ'), 'I', 0}, // 03AA + {IV('Ϋ'), 'Y', 0}, // 03AB + {IV('ά'), 'a', 0}, // 03AC + {IV('έ'), 'e', 0}, // 03AD + {IV('ή'), 'n', 0}, // 03AE + {IV('ί'), 'i', 0}, // 03AF + {IV('ΰ'), 'v', 0}, // 03B0 + {IV('α'), 'a', 0}, // 03B1, alpha + {IV('β'), 'B', 0}, // 03B2, beta + {IV('γ'), 'v', 0}, // 03B3, gamma + {IV('δ'), 'd', 0}, // 03B4, delta + {IV('ε'), 'e', 0}, // 03B5, epsilon + {IV('ζ'), 'Z', 0}, // 03B6, zeta + {IV('η'), 'n', 0}, // 03B7, eta + {IV('θ'), '0', 0}, // 03B8, theta + {IV('ι'), 'i', 0}, // 03B9, lota + {IV('κ'), 'k', 0}, // 03BA, kappa + {IV('λ'), 'L', 0}, // 03BB, lambda + {IV('μ'), 'u', 0}, // 03BC, mu + {IV('ν'), 'v', 0}, // 03BD, nu + {IV('ξ'), 'e', 0}, // 03BE, xi + {IV('ο'), 'o', 0}, // 03BF + {IV('π'), 'n', 0}, // 03C0, pi + {IV('ρ'), 'p', 0}, // 03C1, rho + {IV('ς'), 'c', 0}, // 03C2 + {IV('σ'), 'o', 0}, // 03C3, sigma + {IV('τ'), 't', 0}, // 03C4, tau + {IV('υ'), 'v', 0}, // 03C5, upsilon + {IV('φ'), 'p', 0}, // 03C6 + {IV('χ'), 'X', 0}, // 03C7, chi + {IV('ψ'), 'W', 0}, // 03C8, psi + {IV('ω'), 'w', 0}, // 03C9, omega + {IV('ϊ'), 'i', 0}, // 03CA + {IV('ϋ'), 'v', 0}, // 03CB + {IV('ό'), 'o', 0}, // 03CC + {IV('ύ'), 'v', 0}, // 03CD + {IV('ώ'), 'w', 0}, // 03CE + + // map CYRILLIC code to the plain ASCII + {IV('А'), 'A', 0}, // 0410 + {IV('Б'), 'b', 0}, // 0411 + {IV('В'), 'B', 0}, // 0412 + {IV('Г'), 'T', 0}, // 0413 + {IV('Д'), 'Q', 0}, // 0414 + {IV('Е'), 'E', 0}, // 0415 + {IV('Ж'), '*', 0}, // 0416 + {IV('З'), 'E', 0}, // 0417 + {IV('И'), 'N', 0}, // 0418 + {IV('Й'), 'N', 0}, // 0419 + {IV('К'), 'K', 0}, // 041A + {IV('Л'), 'T', 0}, // 041B + {IV('М'), 'M', 0}, // 041C + {IV('Н'), 'H', 0}, // 041D + {IV('О'), 'O', 0}, // 041E + {IV('П'), 'n', 0}, // 041F + {IV('Р'), 'P', 0}, // 0420 + {IV('С'), 'C', 0}, // 0421 + {IV('Т'), 'T', 0}, // 0422 + {IV('У'), 'Y', 0}, + {IV('Ф'), 'o', 0}, + {IV('Х'), 'X', 0}, + {IV('Ц'), 'U', 0}, + {IV('Ч'), 'y', 0}, + {IV('Ш'), 'W', 0}, + {IV('Щ'), 'W', 0}, + {IV('Ъ'), 'b', 0}, + {IV('Ы'), 'b', '|'}, + {IV('Ь'), 'b'}, + {IV('Э'), 'e'}, + {IV('Ю'), '|', 'O'}, + {IV('Я'), '9', '|'}, // 042F + + {IV('а'), 'a', 0}, // 0430 + {IV('б'), '6', 0}, // 0431 + {IV('в'), 'B', 0}, // 0432, + {IV('г'), 'r', 0}, // 0433 + {IV('д'), 'a', 0}, // 0434, + {IV('е'), 'e', 0}, // 0435 + {IV('ж'), '*', 0}, // 0436 + {IV('з'), 'e', 0}, // 0437, + {IV('и'), 'u', 0}, // 0438 + {IV('й'), 'u', 0}, // 0439, + {IV('к'), 'k', 0}, // 043A + {IV('л'), 'n', 0}, + {IV('м'), 'm', 0}, + {IV('н'), 'H', 0}, + {IV('о'), 'o', 0}, + {IV('п'), 'n', 0}, + {IV('р'), 'p', 0}, + {IV('с'), 'c', 0}, + {IV('т'), 't', 0}, + {IV('у'), 'y', 0}, + {IV('ф'), 'q', 'p'}, + {IV('х'), 'x', 0}, + {IV('ц'), 'u', 0}, + {IV('ч'), 'y', 0}, + {IV('ш'), 'w', 0}, + {IV('щ'), 'w', 0}, + {IV('ъ'), 'b', 0}, + {IV('ы'), 'b', '|'}, + {IV('ь'), 'b', 0}, + {IV('э'), 'e', 0}, + {IV('ю'), '|', 'o'}, + {IV('я'), 'g', 0}, // 044F + + #endif + + {IV('•'), '.', 0}, // 2022 · + {IV('℞'), 'P', 'x'}, // 211E ℞ Pt ASCII 158 + {IV('™'), 'T', 'M'}, // 2122 + {IV('←'), '<', '-'}, // 2190 + {IV('→'), '-', '>'}, // 2192, Marlin special: '⮈⮉⮊⮋➤→⏵➟➠➡' LCD_STR_ARROW_RIGHT (0x03) + //{IV('↰'), '<', 0}, // 21B0, Marlin special: '⮥⮭⮉⇧↑↰⤴' LCD_STR_UPLEVEL (0x04) + {IV('↰'), 0x03, 0}, // 21B0, Marlin special: '⮥⮭⮉⇧↑↰⤴' LCD_STR_UPLEVEL (0x04) + {IV('↻'), 0x04, 0}, // 21BB Marlin special: '↻↺⟳⟲' LCD_STR_REFRESH (0x01) + {IV('∼'), '~', 0}, // 223C + {IV('≈'), '~', '='}, // 2248 + {IV('≠'), '!', '='}, // 2260 + {IV('≡'), '=', 0}, // 2261 + {IV('≤'), '<', '='},// 2264, ≤≥ ⩽⩾ + {IV('≥'), '>', '='}, // 2265 + {IV('⏱'), 0x07, 0}, // 23F1, Marlin special: '🕐🕑🕒🕓🕔🕕🕖🕗🕘🕙🕚🕛🕜🕝🕞🕟🕠🕡🕢🕣🕤🕥🕦🕧 ⌚⌛⏰⏱⏳⧖⧗' LCD_STR_CLOCK (0x05) + + {IV('゠'), '=', 0}, // 30A0 + + // ⏰⏱⏲⏳◴◵◶◷ + // ⏻⏼♁♂ + //{IV(''), 0x00, 0}, // Marlin special: '' LCD_STR_BEDTEMP (0x07) + {IV('🌡'), 0x02, 0}, // D83CDF21 Marlin special: '🌡' LCD_STR_THERMOMETER (0x08) + {IV('📂'), 0x05, 0}, // D83DDCC2 Marlin special: '📁📂' LCD_STR_FOLDER (0x02) + //{IV(''), 0x06, 0}, // Marlin special: '' LCD_STR_FEEDRATE (0x06) +}; + +/* return v1 - v2 */ +static int TFTGLCD_charmap_compare(TFTGLCD_charmap_t * v1, TFTGLCD_charmap_t * v2) { + return (v1->uchar < v2->uchar) ? -1 : (v1->uchar > v2->uchar) ? 1 : 0; +} + +static int pf_bsearch_cb_comp_hd4map_pgm(void *userdata, size_t idx, void * data_pin) { + TFTGLCD_charmap_t localval; + TFTGLCD_charmap_t *p_TFTGLCD_charmap = (TFTGLCD_charmap_t *)userdata; + memcpy_P(&localval, p_TFTGLCD_charmap + idx, sizeof(localval)); + return TFTGLCD_charmap_compare(&localval, (TFTGLCD_charmap_t *)data_pin); +} + +void lcd_moveto(const lcd_uint_t col, const lcd_uint_t row) { lcd.setCursor(col, row); } + +void lcd_put_int(const int i) { + const char* str = i16tostr3left(i); + while (*str) lcd.write(*str++); +} + +// return < 0 on error +// return the advanced cols +int lcd_put_wchar_max(wchar_t c, pixel_len_t max_length) { + + // find the HD44780 internal ROM first + int ret; + size_t idx = 0; + TFTGLCD_charmap_t pinval; + TFTGLCD_charmap_t *copy_address = nullptr; + pinval.uchar = c; + pinval.idx = -1; + + if (max_length < 1) return 0; + + if (c < 128) { + lcd.write((uint8_t)c); + return 1; + } + copy_address = nullptr; + ret = pf_bsearch_r((void *)g_TFTGLCD_charmap_device, COUNT(g_TFTGLCD_charmap_device), pf_bsearch_cb_comp_hd4map_pgm, (void *)&pinval, &idx); + if (ret >= 0) { + copy_address = (TFTGLCD_charmap_t *)(g_TFTGLCD_charmap_device + idx); + } + else { + ret = pf_bsearch_r((void *)g_TFTGLCD_charmap_common, COUNT(g_TFTGLCD_charmap_common), pf_bsearch_cb_comp_hd4map_pgm, (void *)&pinval, &idx); + if (ret >= 0) copy_address = (TFTGLCD_charmap_t *)(g_TFTGLCD_charmap_common + idx); + } + + if (ret >= 0) { + TFTGLCD_charmap_t localval; + // found + memcpy_P(&localval, copy_address, sizeof(localval)); + lcd.write(localval.idx); + if (max_length >= 2 && localval.idx2 > 0) { + lcd.write(localval.idx2); + return 2; + } + return 1; + } + + // Not found, print '?' instead + lcd.write((uint8_t)'?'); + return 1; +} + +/** + * @brief Draw a UTF-8 string + * + * @param utf8_str : the UTF-8 string + * @param cb_read_byte : the callback function to read one byte from the utf8_str (from RAM or ROM) + * @param max_length : the pixel length of the string allowed (or number of slots in HD44780) + * + * @return the number of pixels advanced + * + * Draw a UTF-8 string + */ +static int lcd_put_u8str_max_cb(const char * utf8_str, uint8_t (*cb_read_byte)(uint8_t * str), pixel_len_t max_length) { + pixel_len_t ret = 0; + uint8_t *p = (uint8_t *)utf8_str; + while (ret < max_length) { + wchar_t ch = 0; + p = get_utf8_value_cb(p, cb_read_byte, &ch); + if (!ch) break; + ret += lcd_put_wchar_max(ch, max_length - ret); + } + return (int)ret; +} + +int lcd_put_u8str_max(const char * utf8_str, pixel_len_t max_length) { + return lcd_put_u8str_max_cb(utf8_str, read_byte_ram, max_length); +} + +int lcd_put_u8str_max_P(PGM_P utf8_str_P, pixel_len_t max_length) { + return lcd_put_u8str_max_cb(utf8_str_P, read_byte_rom, max_length); +} + +#if ENABLED(DEBUG_LCDPRINT) + + int test_TFTGLCD_charmap(TFTGLCD_charmap_t *data, size_t size, char *name, char flg_show_contents) { + int ret; + size_t idx = 0; + TFTGLCD_charmap_t preval = {0, 0, 0}; + TFTGLCD_charmap_t pinval = {0, 0, 0}; + char flg_error = 0; + + int i; + + TRACE("Test %s\n", name); + + for (i = 0; i < size; i ++) { + memcpy_P(&pinval, &(data[i]), sizeof(pinval)); + + if (flg_show_contents) { + #if 1 + TRACE("[% 4d] % 6" PRIu32 "(0x%04" PRIX32 ") --> 0x%02X,0x%02X%s\n", i, pinval.uchar, pinval.uchar, (unsigned int)(pinval.idx), (unsigned int)(pinval.idx2), (preval.uchar < pinval.uchar?"":" <--- ERROR")); + #else + TRACE("[% 4d]", i); + TRACE("% 6" PRIu32 "(0x%04" PRIX32 "),", pinval.uchar, pinval.uchar); + TRACE("0x%02X,", (unsigned int)(pinval.idx)); + TRACE("0x%02X,", (unsigned int)(pinval.idx2)); + TRACE("%s", (preval.uchar < pinval.uchar?"":" <--- ERROR")); + #endif + } + if (preval.uchar >= pinval.uchar) { + flg_error = 1; + //TRACE("Error: out of order in array %s: idx=%d, val=%d(0x%x)\n", name, i, pinval.uchar, pinval.uchar); + //return -1; + } + memcpy(&preval, &pinval, sizeof(pinval)); + + ret = pf_bsearch_r((void *)data, size, pf_bsearch_cb_comp_hd4map_pgm, (void *)&pinval, &idx); + if (ret < 0) { + flg_error = 1; + TRACE("Error: not found item in array %s: idx=%d, val=%d(0x%x)\n", name, i, pinval.uchar, pinval.uchar); + //return -1; + } + if (idx != i) { + flg_error = 1; + TRACE("Error: wrong index found item in array %s: idx=%d, val=%d(0x%x)\n", name, i, pinval.uchar, pinval.uchar); + //return -1; + } + } + if (flg_error) { + TRACE("\nError: in array %s\n\n", name); + return -1; + } + TRACE("\nPASS array %s\n\n", name); + return 0; + } + + int test_TFTGLCD_charmap_all(void) { + int flg_error = 0; + if (test_TFTGLCD_charmap(g_TFTGLCD_charmap_device, COUNT(g_TFTGLCD_charmap_device), "g_TFTGLCD_charmap_device", 0) < 0) { + flg_error = 1; + test_TFTGLCD_charmap(g_TFTGLCD_charmap_device, COUNT(g_TFTGLCD_charmap_device), "g_TFTGLCD_charmap_device", 1); + } + if (test_TFTGLCD_charmap(g_TFTGLCD_charmap_common, COUNT(g_TFTGLCD_charmap_common), "g_TFTGLCD_charmap_common", 0) < 0) { + flg_error = 1; + test_TFTGLCD_charmap(g_TFTGLCD_charmap_common, COUNT(g_TFTGLCD_charmap_common), "g_TFTGLCD_charmap_common", 1); + } + if (flg_error) { + TRACE("\nFAILED in hd44780 tests!\n"); + return -1; + } + TRACE("\nPASS in hd44780 tests.\n"); + return 0; + } + +#endif // DEBUG_LCDPRINT + +#endif // IS_TFTGLCD_PANEL diff --git a/Marlin/src/lcd/TFTGLCD/ultralcd_TFTGLCD.cpp b/Marlin/src/lcd/TFTGLCD/ultralcd_TFTGLCD.cpp new file mode 100644 index 0000000000..c9a5b2525a --- /dev/null +++ b/Marlin/src/lcd/TFTGLCD/ultralcd_TFTGLCD.cpp @@ -0,0 +1,1018 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "../../inc/MarlinConfigPre.h" + +#if IS_TFTGLCD_PANEL + +/** + * ultralcd_TFTGLCD.cpp + * + * Implementation of the LCD display routines for a TFT GLCD displays with external controller. + * This display looks as a REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER but has good text font + * and supports color output. + */ + +#if NONE(__AVR__, MCU_LPC1768, __STM32F1__, STM32F4xx) + #warning "Selected platform not yet tested. Please contribute your good pin mappings." +#endif + +#if ENABLED(TFTGLCD_PANEL_SPI) + #include +#else + #include +#endif + +#include "ultralcd_TFTGLCD.h" +#include "../ultralcd.h" +#include "../../libs/numtostr.h" + +#include "../../sd/cardreader.h" +#include "../../module/temperature.h" +#include "../../module/printcounter.h" +#include "../../module/planner.h" +#include "../../module/motion.h" + +#if DISABLED(LCD_PROGRESS_BAR) && BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) + #include "../../feature/filwidth.h" + #include "../../gcode/parser.h" +#endif + +#if ENABLED(AUTO_BED_LEVELING_UBL) + #include "../../feature/bedlevel/bedlevel.h" +#endif + +TFTGLCD lcd; + +#define ICON_LOGO B00000001 +#define ICON_TEMP1 B00000010 //hotend 1 +#define ICON_TEMP2 B00000100 //hotend 2 +#define ICON_TEMP3 B00001000 //hotend 3 +#define ICON_BED B00010000 +#define ICON_FAN B00100000 +#define ICON_HOT B01000000 //when any T > 50deg +#define PIC_MASK 0x7f + +//LEDs not used, for compatibility with Smoothieware +#define LED_HOTEND_ON B00000001 +#define LED_BED_ON B00000010 +#define LED_FAN_ON B00000100 +#define LED_HOT B00001000 +#define LED_MASK 0x0f + +#define FBSIZE (LCD_WIDTH * LCD_HEIGHT + 2) + +//markers for change line color +#define COLOR_EDIT '#' +#define COLOR_ERROR '!' + +#ifdef CONVERT_TO_EXT_ASCII //use standart pseudographic symbols in ASCII table + #define LR 179 //vertical line + #define TRC 191 //top right corner + #define BLC 192 //bottom left corner + #define GL 196 //horizontal line + #define BRC 217 //bottom right corner, should be replaced to 12 for some languages + #define TLC 218 //top left corner, should be replaced to 13 for some languages +#else //next symbols must be present in panel font + #define LR 8 //equal to 179 + #define TRC 9 //equal to 191 + #define BLC 10 //equal to 192 + #define GL 11 //equal to 196 + #define BRC 12 //equal to 217 + #define TLC 13 //equal to 218 +#endif + +#define Marlin 0x01 + +enum Commands { // based on Smoothieware commands + GET_SPI_DATA = 0, + READ_BUTTONS, // read buttons + READ_ENCODER, // read encoder + LCD_WRITE, // write all screen to LCD + BUZZER, // beep buzzer + CONTRAST, // set contrast (brightnes) + // Other commands... 0xE0 thru 0xFF + GET_LCD_ROW = 0xE0, // for detect panel + GET_LCD_COL, // reserved for compatibility with Smoothieware, not used + LCD_PUT, // write one line to LCD + INIT_SCREEN = 0xFE, // clear panel buffer +}; + +static unsigned char framebuffer[FBSIZE]; +static unsigned char *fb; +static uint8_t cour_line; +static uint8_t picBits, ledBits, hotBits; +static uint8_t PanelDetected = 0; + +// Constructor +TFTGLCD::TFTGLCD() {} + +//clearing local buffer +void TFTGLCD::clear_buffer() { + memset(&framebuffer[0], ' ', FBSIZE - 2); + framebuffer[FBSIZE - 1] = framebuffer[FBSIZE - 2] = 0; + picBits = ledBits = 0; +} + +//set new text cursor position +void TFTGLCD::setCursor(uint8_t col, uint8_t row) { + fb = &framebuffer[0] + col + row * LCD_WIDTH; + cour_line = row; +} + +//send char to buffer +void TFTGLCD::write(char c) { + *fb++ = c; +} + +//send text line to buffer +void TFTGLCD::print(const char *line) { + while (*line) *fb++ = *line++; +} + +// For menu +void TFTGLCD::print_line() { + if (!PanelDetected) return; + #if ENABLED(TFTGLCD_PANEL_SPI) + WRITE(TFTGLCD_CS, LOW); + #ifdef __AVR__ + SPI.transfer(LCD_PUT); + SPI.transfer(cour_line); + SPI.transfer(&framebuffer[cour_line * LCD_WIDTH], LCD_WIDTH); + #elif EITHER(MCU_LPC1768, __STM32F1__) + SPI.transfer(LCD_PUT); + SPI.transfer(cour_line); + for (uint16_t i = 0; i < LCD_WIDTH; i++) SPI.transfer(framebuffer[cour_line * LCD_WIDTH + i]); + #elif defined(STM32F4xx) + SPI.transfer(LCD_PUT, SPI_CONTINUE); + SPI.transfer(cour_line, SPI_CONTINUE); + SPI.transfer(&framebuffer[cour_line * LCD_WIDTH], LCD_WIDTH, SPI_CONTINUE); + #elif ANY(ARDUINO_ARCH_SAM, __SAMD51__, __MK20DX256__, __MK64FX512__) + SPI.transfer(LCD_PUT); + SPI.transfer(cour_line); + SPI.transfer(&framebuffer[cour_line * LCD_WIDTH], LCD_WIDTH); + #elif defined(ARDUINO_ARCH_ESP32) + SPI.write(LCD_PUT); + SPI.write(cour_line); + for (uint16_t i = 0; i < LCD_WIDTH; i++) SPI.write(framebuffer[cour_line * LCD_WIDTH + i]); + #endif + WRITE(TFTGLCD_CS, HIGH); + #else + Wire.beginTransmission((uint8_t)LCD_I2C_ADDRESS); //set I2C device address + Wire.write(LCD_PUT); + Wire.write(cour_line); + Wire.write(&framebuffer[cour_line * LCD_WIDTH], LCD_WIDTH); //transfer 1 line to txBuffer + Wire.endTransmission(); //transmit data + safe_delay(1); + #endif +} + +void TFTGLCD::print_screen(){ + if (!PanelDetected) return; + framebuffer[FBSIZE - 2] = picBits & PIC_MASK; + framebuffer[FBSIZE - 1] = ledBits; + #if ENABLED(TFTGLCD_PANEL_SPI) + // Send all framebuffer to panel + WRITE(TFTGLCD_CS, LOW); + #ifdef __AVR__ + SPI.transfer(LCD_WRITE); + SPI.transfer(&framebuffer[0], FBSIZE); + #elif EITHER(MCU_LPC1768, __STM32F1__) + SPI.transfer(LCD_WRITE); + for (uint16_t i = 0; i < FBSIZE; i++) SPI.transfer(framebuffer[i]); + #elif defined(STM32F4xx) + SPI.transfer(LCD_WRITE, SPI_CONTINUE); + SPI.transfer(&framebuffer[0], FBSIZE, SPI_CONTINUE); + #elif ANY(ARDUINO_ARCH_SAM, __SAMD51__, __MK20DX256__, __MK64FX512__) + SPI.transfer(LCD_WRITE); + SPI.transfer(&framebuffer[0], FBSIZE); + #elif defined(ARDUINO_ARCH_ESP32) + SPI.write(LCD_WRITE); + for (uint16_t i = 0; i < FBSIZE; i++) SPI.write(framebuffer[i]); + #endif + WRITE(TFTGLCD_CS, HIGH); + #else + uint8_t r; + // Send framebuffer to panel by line + Wire.beginTransmission((uint8_t)LCD_I2C_ADDRESS); + // First line + Wire.write(LCD_WRITE); + Wire.write(&framebuffer[0], LCD_WIDTH); + Wire.endTransmission(); + for (r = 1; r < (LCD_HEIGHT - 1); r++) { + Wire.beginTransmission((uint8_t)LCD_I2C_ADDRESS); + Wire.write(&framebuffer[r * LCD_WIDTH], LCD_WIDTH); + Wire.endTransmission(); + } + // Last line + Wire.beginTransmission((uint8_t)LCD_I2C_ADDRESS); + Wire.write(&framebuffer[r * LCD_WIDTH], LCD_WIDTH); + Wire.write(&framebuffer[FBSIZE - 2], 2); + Wire.endTransmission(); + #endif +} + +void TFTGLCD::setContrast(uint16_t contrast) { + if (!PanelDetected) return; + #if ENABLED(TFTGLCD_PANEL_SPI) + WRITE(TFTGLCD_CS, LOW); + #if ANY(__AVR__, MCU_LPC1768, __STM32F1__) + SPI.transfer(CONTRAST); + SPI.transfer((uint8_t)contrast); + #elif defined(STM32F4xx) + SPI.transfer(CONTRAST, SPI_CONTINUE); + SPI.transfer((uint8_t)contrast, SPI_CONTINUE); + #elif ANY(ARDUINO_ARCH_SAM, __SAMD51__, __MK20DX256__, __MK64FX512__) + SPI.transfer(CONTRAST); + SPI.transfer((uint8_t)contrast); + #elif defined(ARDUINO_ARCH_ESP32) + SPI.write(CONTRAST); + SPI.write((uint8_t)contrast); + #endif + WRITE(TFTGLCD_CS, HIGH); + #else + Wire.beginTransmission((uint8_t)LCD_I2C_ADDRESS); + Wire.write(CONTRAST); + Wire.write((uint8_t)contrast); + Wire.endTransmission(); + #endif +} + +//reading buttons and encoder states +extern volatile int8_t encoderDiff; + +uint8_t MarlinUI::read_slow_buttons(void) { + if (!PanelDetected) return 0; + #if ENABLED(TFTGLCD_PANEL_SPI) + uint8_t b = 0; + WRITE(TFTGLCD_CS, LOW); + #if ANY(__AVR__, MCU_LPC1768, __STM32F1__) + SPI.transfer(READ_ENCODER); + WRITE(TFTGLCD_CS, LOW); //for delay + encoderDiff += SPI.transfer(READ_BUTTONS); + WRITE(TFTGLCD_CS, LOW); //for delay + b = SPI.transfer(GET_SPI_DATA); + #elif defined(STM32F4xx) + SPI.transfer(READ_ENCODER, SPI_CONTINUE); + encoderDiff += SPI.transfer(READ_BUTTONS, SPI_CONTINUE); + b = SPI.transfer(GET_SPI_DATA, SPI_CONTINUE); + #elif ANY(ARDUINO_ARCH_SAM, __SAMD51__, __MK20DX256__, __MK64FX512__) + SPI.transfer(READ_ENCODER); + WRITE(TFTGLCD_CS, LOW); //for delay ???? + encoderDiff += SPI.transfer(READ_BUTTONS); + WRITE(TFTGLCD_CS, LOW); //for delay ???? + b = SPI.transfer(GET_SPI_DATA); + #elif defined(ARDUINO_ARCH_ESP32) + SPI.transfer(READ_ENCODER); + WRITE(TFTGLCD_CS, LOW); //for delay ???? + encoderDiff += SPI.transfer(READ_BUTTONS); + WRITE(TFTGLCD_CS, LOW); //for delay ???? + b = SPI.transfer(GET_SPI_DATA); + #endif + WRITE(TFTGLCD_CS, HIGH); + return b; + #else + Wire.beginTransmission((uint8_t)LCD_I2C_ADDRESS); + Wire.write(READ_ENCODER); + Wire.endTransmission(); + #ifdef __AVR__ + Wire.requestFrom((uint8_t)LCD_I2C_ADDRESS, 2, 0, 0, 1); + #elif defined(__STM32F1__) + Wire.requestFrom((uint8_t)LCD_I2C_ADDRESS, (uint8_t)2); + #elif EITHER(STM32F4xx, MCU_LPC1768) + Wire.requestFrom(LCD_I2C_ADDRESS, 2); + #endif + encoderDiff += Wire.read(); + return Wire.read(); //buttons + #endif +} + +// duration in ms, freq in Hz +void MarlinUI::buzz(const long duration, const uint16_t freq) { + if (!PanelDetected) return; + #if ENABLED(TFTGLCD_PANEL_SPI) + WRITE(TFTGLCD_CS, LOW); + #if ANY(__AVR__, MCU_LPC1768, __STM32F1__) + SPI.transfer(BUZZER); + SPI.transfer16((uint16_t)duration); + SPI.transfer16(freq); + #elif defined(STM32F4xx) + SPI.transfer(BUZZER, SPI_CONTINUE); + SPI.transfer16((uint16_t)duration, SPI_CONTINUE); + SPI.transfer16(freq, SPI_CONTINUE); + #elif ANY(ARDUINO_ARCH_SAM, __SAMD51__, __MK20DX256__, __MK64FX512__) + SPI.transfer(BUZZER); + SPI.transfer16((uint16_t)duration); + SPI.transfer16(freq); + #elif defined(ARDUINO_ARCH_ESP32) + SPI.write(BUZZER); + SPI.write16((uint16_t)duration); + SPI.write16(freq); + #endif + WRITE(TFTGLCD_CS, HIGH); + #else + Wire.beginTransmission((uint8_t)LCD_I2C_ADDRESS); + Wire.write(BUZZER); + Wire.write((uint8_t)(duration >> 8)); + Wire.write((uint8_t)duration); + Wire.write((uint8_t)(freq >> 8)); + Wire.write((uint8_t)freq); + Wire.endTransmission(); + #endif +} + +void MarlinUI::init_lcd() { + uint8_t t; + lcd.clear_buffer(); + t = 0; + #if ENABLED(TFTGLCD_PANEL_SPI) + // SPI speed must be less 10MHz + OUT_WRITE(TFTGLCD_CS, HIGH); + spiInit(TERN(__STM32F1__, SPI_QUARTER_SPEED, SPI_FULL_SPEED)); + WRITE(TFTGLCD_CS, LOW); + #if ANY(__AVR__, MCU_LPC1768, __STM32F1__) + SPI.transfer(GET_LCD_ROW); + t = SPI.transfer(GET_SPI_DATA); + #elif defined(STM32F4xx) + SPI.transfer(GET_LCD_ROW, SPI_CONTINUE); + t = SPI.transfer(GET_SPI_DATA, SPI_CONTINUE); + #elif ANY(ARDUINO_ARCH_SAM, __SAMD51__, __MK20DX256__, __MK64FX512__) + SPI.transfer(GET_LCD_ROW); + t = SPI.transfer(GET_SPI_DATA); + #elif defined(ARDUINO_ARCH_ESP32) + SPI.write(GET_LCD_ROW); + t = SPI.transfer(GET_SPI_DATA); + #endif + #else + #ifdef MCU_LPC1768 + Wire.begin(); //init twi/I2C + #else + Wire.begin((uint8_t)LCD_I2C_ADDRESS); //init twi/I2C + #endif + Wire.beginTransmission((uint8_t)LCD_I2C_ADDRESS); + Wire.write((uint8_t)GET_LCD_ROW); // put command to buffer + Wire.endTransmission(); // send buffer + #ifdef __AVR__ + Wire.requestFrom((uint8_t)LCD_I2C_ADDRESS, 1, 0, 0, 1); + #elif ANY(__STM32F1__, STM32F4xx, MCU_LPC1768) + Wire.requestFrom(LCD_I2C_ADDRESS, 1); + #endif + t = (uint8_t)Wire.read(); + #endif + + if (t == LCD_HEIGHT) { + PanelDetected = 1; + #if ENABLED(TFTGLCD_PANEL_SPI) + PanelDetected = 1; + #if ANY(__AVR__, MCU_LPC1768, __STM32F1__) + SPI.transfer(INIT_SCREEN); + SPI.transfer(Marlin); + #elif defined(STM32F4xx) + SPI.transfer(INIT_SCREEN, SPI_CONTINUE); + SPI.transfer(Marlin, SPI_CONTINUE); + #elif ANY(ARDUINO_ARCH_SAM, __SAMD51__, __MK20DX256__, __MK64FX512__) + SPI.transfer(INIT_SCREEN); + SPI.transfer(Marlin); + #elif defined(ARDUINO_ARCH_ESP32) + SPI.write(INIT_SCREEN); + SPI.write(Marlin); + #endif + WRITE(TFTGLCD_CS, HIGH); + #else + Wire.beginTransmission((uint8_t)LCD_I2C_ADDRESS); + Wire.write((uint8_t)INIT_SCREEN); + Wire.write(Marlin); + Wire.endTransmission(); + #endif + } + else + PanelDetected = 0; + safe_delay(100); +} + +bool MarlinUI::detected() { + return PanelDetected; +} + +void MarlinUI::clear_lcd() { + if (!PanelDetected) return; + lcd.clear_buffer(); + lcd.print_screen(); +} + +int16_t MarlinUI::contrast; // Initialized by settings.load() + +void MarlinUI::set_contrast(const int16_t value) { + contrast = constrain(value, LCD_CONTRAST_MIN, LCD_CONTRAST_MAX); + lcd.setContrast(contrast); +} + +static void center_text_P(PGM_P pstart, uint8_t y) { + uint8_t len = utf8_strlen_P(pstart); + if (len < LCD_WIDTH) + lcd.setCursor((LCD_WIDTH - len) / 2, y); + else + lcd.setCursor(0, y); + lcd_put_u8str_P(pstart); +} + +#if ENABLED(SHOW_BOOTSCREEN) + + void MarlinUI::show_bootscreen() { + if (!PanelDetected) return; + // + // Show the Marlin logo, splash line1, and splash line 2 + // + uint8_t indent = (LCD_WIDTH - 8) / 2; + // symbols 217 (bottom right corner) and 218 (top left corner) are using for letters in some languages + // and they should be moved to begining ASCII table as spetial symbols + lcd.setCursor(indent, 0); lcd.write(TLC); lcd_put_u8str_P(PSTR("------")); lcd.write(TRC); + lcd.setCursor(indent, 1); lcd.write(LR); lcd_put_u8str_P(PSTR("Marlin")); lcd.write(LR); + lcd.setCursor(indent, 2); lcd.write(BLC); lcd_put_u8str_P(PSTR("------")); lcd.write(BRC); + center_text_P(PSTR(SHORT_BUILD_VERSION), 3); + center_text_P(PSTR(MARLIN_WEBSITE_URL), 4); + picBits = ICON_LOGO; + lcd.print_screen(); + safe_delay(1500); + } + +#endif // SHOW_BOOTSCREEN + +void MarlinUI::draw_kill_screen() { + if (!PanelDetected) return; + lcd.clear_buffer(); + lcd.setCursor(0, 3); lcd.write(COLOR_ERROR); + lcd.setCursor((LCD_WIDTH - utf8_strlen(status_message)) / 2 + 1, 3); + lcd_put_u8str(status_message); + center_text_P(GET_TEXT(MSG_HALTED), 5); + center_text_P(GET_TEXT(MSG_PLEASE_RESET), 6); + lcd.print_screen(); +} + +// +// Before homing, blink '123' <-> '???'. +// Homed but unknown... '123' <-> ' '. +// Homed and known, display constantly. +// +FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const bool blink) { + lcd.write('X' + uint8_t(axis)); + if (blink) + lcd.print(value); + else { + if (!TEST(axis_homed, axis)) + while (const char c = *value++) lcd.write(c <= '.' ? c : '?'); + else { + #if NONE(HOME_AFTER_DEACTIVATE, DISABLE_REDUCED_ACCURACY_WARNING) + if (!TEST(axis_known_position, axis)) + lcd_put_u8str_P(axis == Z_AXIS ? PSTR(" ") : PSTR(" ")); + else + #endif + lcd_put_u8str(value); + } + } +} + +FORCE_INLINE void _draw_heater_status(const heater_id_t heater_id, const char *prefix, const bool blink) { + uint8_t pic_hot_bits; + #if HAS_HEATED_BED + const bool isBed = heater_id < 0; + const float t1 = (isBed ? thermalManager.degBed() : thermalManager.degHotend(heater_id)); + const float t2 = (isBed ? thermalManager.degTargetBed() : thermalManager.degTargetHotend(heater_id)); + #else + const float t1 = thermalManager.degHotend(heater_id); + const float t2 = thermalManager.degTargetHotend(heater_id); + #endif + + #if HOTENDS < 2 + if (heater_id == H_E0) { + lcd.setCursor(2, 5); lcd.print(prefix); //HE + lcd.setCursor(1, 6); lcd.print(i16tostr3rj(t1 + 0.5)); + lcd.setCursor(1, 7); + } + else { + lcd.setCursor(6, 5); lcd.print(prefix); //BED + lcd.setCursor(6, 6); lcd.print(i16tostr3rj(t1 + 0.5)); + lcd.setCursor(6, 7); + } + #else + if (heater_id > H_BED) { + lcd.setCursor(heater_id * 4, 5); lcd.print(prefix); //HE1 or HE2 or HE3 + lcd.setCursor(heater_id * 4, 6); lcd.print(i16tostr3rj(t1 + 0.5)); + lcd.setCursor(heater_id * 4, 7); + } + else { + lcd.setCursor(13, 5); lcd.print(prefix); //BED + lcd.setCursor(13, 6); lcd.print(i16tostr3rj(t1 + 0.5)); + lcd.setCursor(13, 7); + } + #endif // HOTENDS <= 1 + + #if !HEATER_IDLE_HANDLER + UNUSED(blink); + #else + if (!blink && thermalManager.heater_idle[thermalManager.idle_index_for_id(heater_id)].timed_out) { + lcd.write(' '); + if (t2 >= 10) lcd.write(' '); + if (t2 >= 100) lcd.write(' '); + } + else + #endif // !HEATER_IDLE_HANDLER + lcd.print(i16tostr3rj(t2 + 0.5)); + + switch (heater_id) { + case H_BED: pic_hot_bits = ICON_BED; break; + case H_E0: pic_hot_bits = ICON_TEMP1; break; + case H_E1: pic_hot_bits = ICON_TEMP2; break; + case H_E2: pic_hot_bits = ICON_TEMP3; + default: break; + } + + if (t2) picBits |= pic_hot_bits; + else picBits &= ~pic_hot_bits; + + if (t1 > 50) hotBits |= pic_hot_bits; + else hotBits &= ~pic_hot_bits; + + if (hotBits) picBits |= ICON_HOT; + else picBits &= ~ICON_HOT; +} + +#if HAS_PRINT_PROGRESS + + FORCE_INLINE void _draw_print_progress() { + if (!PanelDetected) return; + const uint8_t progress = ui._get_progress(); + #if ENABLED(SDSUPPORT) + lcd_put_u8str_P(PSTR("SD")); + #elif ENABLED(LCD_SET_PROGRESS_MANUALLY) + lcd_put_u8str_P(PSTR("P:")); + #endif + if (progress) + lcd.print(ui8tostr3rj(progress)); + else + lcd_put_u8str_P(PSTR("---")); + lcd.write('%'); + } + +#endif // HAS_PRINT_PROGRESS + +#if ENABLED(LCD_PROGRESS_BAR) + + void MarlinUI::draw_progress_bar(const uint8_t percent) { + if (!PanelDetected) return; + if (fb == &framebuffer[0] + LCD_WIDTH * 2) { // For status screen + lcd.write('%'); lcd.write(percent); + } + else { // For progress bar test + lcd.setCursor(LCD_WIDTH / 2 - 2, LCD_HEIGHT / 2 - 2); + lcd.print(i16tostr3rj(percent)); lcd.write('%'); + lcd.print_line(); + lcd.setCursor(0, LCD_HEIGHT / 2 - 1); + lcd.write('%'); lcd.write(percent); + lcd.print_line(); + } + } + +#endif + +void MarlinUI::draw_status_message(const bool blink) { + if (!PanelDetected) return; + lcd.setCursor(0, 3); + #if BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) + + // Alternate Status message and Filament display + if (ELAPSED(millis(), next_filament_display)) { + lcd_put_u8str_P(PSTR("Dia ")); + lcd.print(ftostr12ns(filament_width_meas)); + lcd_put_u8str_P(PSTR(" V")); + lcd.print(i16tostr3rj(100.0 * ( + parser.volumetric_enabled + ? planner.volumetric_area_nominal / planner.volumetric_multiplier[FILAMENT_SENSOR_EXTRUDER_NUM] + : planner.volumetric_multiplier[FILAMENT_SENSOR_EXTRUDER_NUM] + ) + )); + lcd.write('%'); + return; + } + + #endif // FILAMENT_LCD_DISPLAY && SDSUPPORT + + // Get the UTF8 character count of the string + uint8_t slen = utf8_strlen(status_message); + + #if ENABLED(STATUS_MESSAGE_SCROLLING) + + static bool last_blink = false; + + // If the string fits into the LCD, just print it and do not scroll it + if (slen <= LCD_WIDTH) { + + // The string isn't scrolling and may not fill the screen + lcd_put_u8str(status_message); + + // Fill the rest with spaces + while (slen < LCD_WIDTH) { lcd.write(' '); ++slen; } + } + else { + // String is larger than the available space in screen. + + // Get a pointer to the next valid UTF8 character + // and the string remaining length + uint8_t rlen; + const char *stat = status_and_len(rlen); + lcd_put_u8str_max(stat, LCD_WIDTH); // The string leaves space + + // If the remaining string doesn't completely fill the screen + if (rlen < LCD_WIDTH) { + lcd.write('.'); // Always at 1+ spaces left, draw a dot + uint8_t chars = LCD_WIDTH - rlen; // Amount of space left in characters + if (--chars) { // Draw a second dot if there's space + lcd.write('.'); + if (--chars) + lcd_put_u8str_max(status_message, chars); // Print a second copy of the message + } + } + if (last_blink != blink) { + last_blink = blink; + advance_status_scroll(); + } + } + + #else + + UNUSED(blink); + + // Just print the string to the LCD + lcd_put_u8str_max(status_message, LCD_WIDTH); + + // Fill the rest with spaces if there are missing spaces + while (slen < LCD_WIDTH) { + lcd.write(' '); + ++slen; + } + + #endif +} + +/** +Possible status screens: + +Equal to 20x10 text LCD + +|X 000 Y 000 Z 000.00| +|FR100% SD100% C--:--| +| Progress bar line | +|Status message | +| | +| HE BED FAN | +| ttc ttc % | ttc - current temperature +| tts tts %%% | tts - setted temperature, %%% - percent for FAN +| ICO ICO ICO ICO | ICO - icon 48x48, placed in 2 text lines +| ICO ICO ICO ICO | ICO / + +or + +|X 000 Y 000 Z 000.00| +|FR100% SD100% C--:--| +| Progress bar line | +|Status message | +| | +|HE1 HE2 HE3 BED ICO| +|ttc ttc ttc ttc ICO| +|tts tts tts tts %%%| +|ICO ICO ICO ICO ICO| +|ICO ICO ICO ICO ICO| + +or + +Equal to 24x10 text LCD + +|X 000 Y 000 Z 000.00 | +|FR100% SD100% C--:--| +| Progress bar line | +|Status message | +| | +|HE1 HE2 HE3 BED FAN | +|ttc ttc ttc ttc % | +|tts tts tts tts %%% | +|ICO ICO ICO ICO ICO ICO| +|ICO ICO ICO ICO ICO ICO| +*/ + +void MarlinUI::draw_status_screen() { + if (!PanelDetected) return; + + const bool blink = get_blink(); + + lcd.clear_buffer(); + + // + // Line 1 - XYZ coordinates + // + + lcd.setCursor(0, 0); + _draw_axis_value(X_AXIS, ftostr4sign(LOGICAL_X_POSITION(current_position[X_AXIS])), blink); lcd.write(' '); + _draw_axis_value(Y_AXIS, ftostr4sign(LOGICAL_Y_POSITION(current_position[Y_AXIS])), blink); lcd.write(' '); + _draw_axis_value(Z_AXIS, ftostr52sp(LOGICAL_Z_POSITION(current_position[Z_AXIS])), blink); + + #if HAS_LEVELING && !HAS_HEATED_BED + lcd.write(planner.leveling_active || blink ? '_' : ' '); + #endif + + // + // Line 2 - feedrate, , time + // + + lcd.setCursor(0, 1); + lcd_put_u8str_P(PSTR("FR")); lcd.print(i16tostr3rj(feedrate_percentage)); lcd.write('%'); + + #if BOTH(SDSUPPORT, HAS_PRINT_PROGRESS) + lcd.setCursor(LCD_WIDTH / 2 - 3, 1); + _draw_print_progress(); + #endif + + char buffer[10]; + duration_t elapsed = print_job_timer.duration(); + uint8_t len = elapsed.toDigital(buffer); + + lcd.setCursor((LCD_WIDTH - 1) - len, 1); + lcd.write(0x07); lcd.print(buffer); // LCD_CLOCK_CHAR + + // + // Line 3 - progressbar + // + + lcd.setCursor(0, 2); + #if ENABLED(LCD_PROGRESS_BAR) + draw_progress_bar(_get_progress()); + #else + lcd.write('%'); lcd.write(0); + #endif + + // + // Line 4 - Status Message (which may be a Filament display) + // + + draw_status_message(blink); + + // + // Line 5 + // + + #if HOTENDS <= 1 || (HOTENDS <= 2 && !HAS_HEATED_BED) + #if DUAL_MIXING_EXTRUDER + lcd.setCursor(0, 4); + // Two-component mix / gradient instead of XY + char mixer_messages[12]; + const char *mix_label; + #if ENABLED(GRADIENT_MIX) + if (mixer.gradient.enabled) { + mixer.update_mix_from_gradient(); + mix_label = "Gr"; + } + else + #endif + { + mixer.update_mix_from_vtool(); + mix_label = "Mx"; + } + sprintf_P(mixer_messages, PSTR("%s %d;%d%% "), mix_label, int(mixer.mix[0]), int(mixer.mix[1])); + lcd_put_u8str(mixer_messages); + #endif + #endif + + // + // Line 6..8 Temperatures, FAN + // + + #if HOTENDS < 2 + _draw_heater_status(H_E0, "HE", blink); // Hotend Temperature + #else + _draw_heater_status(H_E0, "HE1", blink); // Hotend 1 Temperature + _draw_heater_status(H_E1, "HE2", blink); // Hotend 2 Temperature + #if HOTENDS > 2 + _draw_heater_status(H_E2, "HE3", blink); // Hotend 3 Temperature + #endif + #endif // HOTENDS <= 1 + + #if HAS_HEATED_BED + #if HAS_LEVELING + _draw_heater_status(H_BED, (planner.leveling_active && blink ? "___" : "BED"), blink); + #else + _draw_heater_status(H_BED, "BED", blink); + #endif + #endif // HAS_HEATED_BED + + #if FAN_COUNT > 0 + uint16_t spd = thermalManager.fan_speed[0]; + + #if ENABLED(ADAPTIVE_FAN_SLOWING) + if (!blink) spd = thermalManager.scaledFanSpeed(0, spd); + #endif + + uint16_t per = thermalManager.fanPercent(spd); + #if HOTENDS < 2 + #define FANX 11 + #else + #define FANX 17 + #endif + lcd.setCursor(FANX, 5); lcd_put_u8str_P(PSTR("FAN")); + lcd.setCursor(FANX + 1, 6); lcd.write('%'); + lcd.setCursor(FANX, 7); + lcd.print(i16tostr3rj(per)); + + if (TERN0(HAS_FAN0, thermalManager.fan_speed[0]) || TERN0(HAS_FAN1, thermalManager.fan_speed[1]) || TERN0(HAS_FAN2, thermalManager.fan_speed[2])) + picBits |= ICON_FAN; + else + picBits &= ~ICON_FAN; + + #endif // FAN_COUNT > 0 + + // + // Line 9, 10 - icons + // + lcd.print_screen(); +} + +#if HAS_LCD_MENU + + #include "../menu/menu.h" + + #if ENABLED(ADVANCED_PAUSE_FEATURE) + + void MarlinUI::draw_hotend_status(const uint8_t row, const uint8_t extruder) { + if (!PanelDetected) return; + lcd.setCursor((LCD_WIDTH - 14) / 2, row + 1); + lcd.write(0x02); lcd_put_u8str_P(" E"); lcd.write('1' + extruder); lcd.write(' '); + lcd.print(i16tostr3rj(thermalManager.degHotend(extruder))); lcd.write(0x01); lcd.write('/'); + lcd.print(i16tostr3rj(thermalManager.degTargetHotend(extruder))); lcd.write(0x01); + lcd.print_line(); + } + + #endif // ADVANCED_PAUSE_FEATURE + + // Draw a static item with no left-right margin required. Centered by default. + void MenuItem_static::draw(const uint8_t row, PGM_P const pstr, const uint8_t style/*=SS_DEFAULT*/, const char * const valstr/*=nullptr*/) { + if (!PanelDetected) return; + uint8_t n = LCD_WIDTH; + lcd.setCursor(0, row); + if ((style & SS_CENTER) && !valstr) { + int8_t pad = (LCD_WIDTH - utf8_strlen_P(pstr)) / 2; + while (--pad >= 0) { lcd.write(' '); n--; } + } + n = lcd_put_u8str_ind_P(pstr, itemIndex, itemString, n); + if (valstr) n -= lcd_put_u8str_max(valstr, n); + for (; n; --n) lcd.write(' '); + lcd.print_line(); + } + + // Draw a generic menu item with pre_char (if selected) and post_char + void MenuItemBase::_draw(const bool sel, const uint8_t row, PGM_P const pstr, const char pre_char, const char post_char) { + if (!PanelDetected) return; + lcd.setCursor(0, row); + lcd.write(sel ? pre_char : ' '); + uint8_t n = lcd_put_u8str_ind_P(pstr, itemIndex, itemString, LCD_WIDTH - 2); + for (; n; --n) lcd.write(' '); + lcd.write(post_char); + lcd.print_line(); + } + + // Draw a menu item with a (potentially) editable value + void MenuEditItemBase::draw(const bool sel, const uint8_t row, PGM_P const pstr, const char* const data, const bool pgm) { + if (!PanelDetected) return; + const uint8_t vlen = data ? (pgm ? utf8_strlen_P(data) : utf8_strlen(data)) : 0; + lcd.setCursor(0, row); + lcd.write(sel ? LCD_STR_ARROW_RIGHT[0] : ' '); + uint8_t n = lcd_put_u8str_ind_P(pstr, itemIndex, itemString, LCD_WIDTH - 2 - vlen); + if (vlen) { + lcd.write(':'); + for (; n; --n) lcd.write(' '); + if (pgm) lcd_put_u8str_P(data); else lcd_put_u8str(data); + } + lcd.print_line(); + } + + // Low-level draw_edit_screen can be used to draw an edit screen from anyplace + void MenuEditItemBase::draw_edit_screen(PGM_P const pstr, const char* const value/*=nullptr*/) { + if (!PanelDetected) return; + ui.encoder_direction_normal(); + lcd.setCursor(0, LCD_HEIGHT - 1); //last line is free most time + lcd.write(COLOR_EDIT); + lcd_put_u8str_P(pstr); + if (value != nullptr) { + lcd.write(':'); + lcd.setCursor((LCD_WIDTH - 1) - (utf8_strlen(value) + 1), LCD_HEIGHT - 1); // Right-justified, padded by spaces + lcd.write(' '); // Overwrite char if value gets shorter + lcd.print(value); + lcd.write(' '); + lcd.print_line(); + } + } + + // The Select Screen presents a prompt and two "buttons" + void MenuItem_confirm::draw_select_screen(PGM_P const yes, PGM_P const no, const bool yesno, PGM_P const pref, const char * const string, PGM_P const suff) { + if (!PanelDetected) return; + ui.draw_select_screen_prompt(pref, string, suff); + lcd.setCursor(0, LCD_HEIGHT - 1); + lcd.write(COLOR_EDIT); + lcd.write(yesno ? ' ' : '['); lcd_put_u8str_P(no); lcd.write(yesno ? ' ' : ']'); + lcd.setCursor(LCD_WIDTH - utf8_strlen_P(yes) - 3, LCD_HEIGHT - 1); + lcd.write(yesno ? '[' : ' '); lcd_put_u8str_P(yes); lcd.write(yesno ? ']' : ' '); + lcd.print_line(); + } + + #if ENABLED(SDSUPPORT) + + void MenuItem_sdbase::draw(const bool sel, const uint8_t row, PGM_P const, CardReader &theCard, const bool isDir) { + if (!PanelDetected) return; + lcd.setCursor(0, row); + lcd.write(sel ? LCD_STR_ARROW_RIGHT[0] : ' '); + constexpr uint8_t maxlen = LCD_WIDTH - 2; + uint8_t n = maxlen - lcd_put_u8str_max(ui.scrolled_filename(theCard, maxlen, row, sel), maxlen); + for (; n; --n) lcd.write(' '); + lcd.write(isDir ? LCD_STR_FOLDER[0] : ' '); + lcd.print_line(); + } + + #endif // SDSUPPORT + + #if ENABLED(LCD_HAS_STATUS_INDICATORS) + + void MarlinUI::update_indicators() {} + + #endif // LCD_HAS_STATUS_INDICATORS + + #if ENABLED(AUTO_BED_LEVELING_UBL) + /** + * Map screen: + * |/---------\ (00,00) | + * || . . . . | X:000.00| + * || . . . . | Y:000.00| + * || . . . . | Z:00.000| + * || . . . . | | + * || . . . . | | + * || . . . . | | + * |+---------/ | + * | | + * |____________________| + */ + void MarlinUI::ubl_plot(const uint8_t x_plot, const uint8_t y_plot) { + if (!PanelDetected) return; + + #define _LCD_W_POS 12 + + lcd.clear_buffer(); + + //print only top left corner. All frame with grid points will be printed by panel + lcd.setCursor(0, 0); + *fb++ = TLC; //top left corner - marker for plot parameters + *fb = (GRID_MAX_POINTS_X << 4) + GRID_MAX_POINTS_Y; //set mesh size + + // Print plot position + lcd.setCursor(_LCD_W_POS, 0); + *fb++ = '('; lcd.print(i16tostr3left(x_plot)); + *fb++ = ','; lcd.print(i16tostr3left(y_plot)); *fb = ')'; + + // Show all values + lcd.setCursor(_LCD_W_POS, 1); lcd_put_u8str_P(PSTR("X:")); + lcd.print(ftostr52(LOGICAL_X_POSITION(pgm_read_float(&ubl._mesh_index_to_xpos[x_plot])))); + lcd.setCursor(_LCD_W_POS, 2); lcd_put_u8str_P(PSTR("Y:")); + lcd.print(ftostr52(LOGICAL_Y_POSITION(pgm_read_float(&ubl._mesh_index_to_ypos[y_plot])))); + + // Show the location value + lcd.setCursor(_LCD_W_POS, 3); lcd_put_u8str_P(PSTR("Z:")); + + if (!isnan(ubl.z_values[x_plot][y_plot])) + lcd.print(ftostr43sign(ubl.z_values[x_plot][y_plot])); + else + lcd_put_u8str_P(PSTR(" -----")); + + center_text_P(GET_TEXT(MSG_UBL_FINE_TUNE_MESH), 8); + + lcd.print_screen(); + } + + #endif // AUTO_BED_LEVELING_UBL + +#endif // HAS_LCD_MENU + +#endif // IS_TFTGLCD_PANEL diff --git a/Marlin/src/lcd/TFTGLCD/ultralcd_TFTGLCD.h b/Marlin/src/lcd/TFTGLCD/ultralcd_TFTGLCD.h new file mode 100644 index 0000000000..9f54730c3c --- /dev/null +++ b/Marlin/src/lcd/TFTGLCD/ultralcd_TFTGLCD.h @@ -0,0 +1,74 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * Implementation of the LCD display routines for a TFT GLCD displays with external controller. + */ + +#include "../../inc/MarlinConfig.h" + +#if IS_TFTGLCD_PANEL + +#include "../../libs/duration_t.h" + +//////////////////////////////////// +// Set up button and encode mappings for each panel (into 'buttons' variable) +// +// This is just to map common functions (across different panels) onto the same +// macro name. The mapping is independent of whether the button is directly connected or +// via a shift/i2c register. + +//////////////////////////////////// +// Create LCD class instance and chipset-specific information +class TFTGLCD { + private: + public: + TFTGLCD(); + void clear_buffer(); + void setCursor(uint8_t col, uint8_t row); + void write(char c); + void print(const char *line); + void print_line(); + void print_screen(); + void redraw_screen(); + void setContrast(uint16_t contrast); +}; + +extern TFTGLCD lcd; + +#include "../fontutils.h" +#include "../lcdprint.h" + +// Use panel encoder - free old encoder pins +#undef BTN_EN1 +#undef BTN_EN2 +#undef BTN_ENC +#define BTN_EN1 -1 +#define BTN_EN2 -1 +#define BTN_ENC -1 + +#ifndef EN_C + #define EN_C 4 //for click +#endif + +#endif // IS_TFTGLCD_PANEL diff --git a/Marlin/src/lcd/dogm/fontdata/fontdata_ISO10646_1.h b/Marlin/src/lcd/dogm/fontdata/fontdata_ISO10646_1.h index 451383045b..276cae522a 100644 --- a/Marlin/src/lcd/dogm/fontdata/fontdata_ISO10646_1.h +++ b/Marlin/src/lcd/dogm/fontdata/fontdata_ISO10646_1.h @@ -25,97 +25,97 @@ Fontname: -Marlin6x12-Fixed-Medium-R-SemiCondensed--12-90-100-100-C-111-ISO10646-1 Copyright: Public domain terminal emulator font. Share and enjoy. original font -Misc-Fixed-Medium-R-SemiCondensed--12-110-75-75-C-60-ISO10646-1 Capital A Height: 7, '1' Height: 7 - Calculated Max Values w= 5 h=10 x= 5 y= 5 dx= 6 dy= 0 ascent= 8 len=10 + Calculated Max Values w= 7 h=10 x= 5 y= 5 dx= 7 dy= 0 ascent= 8 len=10 Font Bounding box w=12 h=15 x= 0 y=-2 Calculated Min Values x= 0 y=-2 dx= 0 dy= 0 Pure Font ascent = 7 descent=-2 X Font ascent = 8 descent=-2 Max Font ascent = 8 descent=-2 */ -const u8g_fntpgm_uint8_t ISO10646_1_5x7[1325] U8G_FONT_SECTION("ISO10646_1_5x7") = { - 0x00,0x0c,0x0f,0x00,0xfe,0x07,0x02,0x26,0x03,0xbc,0x01,0x7f,0xfe,0x08,0xfe,0x08, +const u8g_fntpgm_uint8_t ISO10646_1_5x7[1324] U8G_FONT_SECTION("ISO10646_1_5x7") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x07,0x02,0x25,0x03,0xbb,0x01,0x7f,0xfe,0x08,0xfe,0x08, 0xfe,0x05,0x08,0x08,0x06,0x00,0x00,0x40,0xf0,0xc8,0x88,0x88,0x98,0x78,0x10,0x05, 0x08,0x08,0x06,0x00,0x00,0xc0,0xf8,0x88,0x88,0x88,0x88,0x88,0xf8,0x05,0x05,0x05, 0x06,0x00,0x01,0x20,0x30,0xf8,0x30,0x20,0x05,0x08,0x08,0x06,0x00,0x00,0x20,0x70, 0xf8,0x20,0x20,0x20,0x20,0xe0,0x05,0x09,0x09,0x06,0x00,0xff,0x20,0x70,0xa8,0xa8, - 0xb8,0x88,0x88,0x70,0x20,0x05,0x06,0x06,0x06,0x00,0x01,0xe0,0x8c,0xea,0x8c,0x8a, - 0x0a,0x05,0x09,0x09,0x06,0x00,0xff,0xf8,0xa8,0x88,0x88,0x88,0x88,0x88,0xa8,0xf8, - 0x05,0x0a,0x0a,0x06,0x00,0xfe,0x20,0x50,0x50,0x50,0x50,0x88,0xa8,0xa8,0x88,0x70, - 0x03,0x03,0x03,0x06,0x00,0x03,0x40,0xa0,0x40,0xff,0xff,0xff,0xff,0xff,0xff,0xff, - 0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0x00, - 0x00,0x00,0x06,0x05,0xff,0x01,0x07,0x07,0x06,0x02,0x00,0x80,0x80,0x80,0x80,0x80, - 0x00,0x80,0x03,0x03,0x03,0x06,0x01,0x05,0xa0,0xa0,0xa0,0x05,0x06,0x06,0x06,0x00, - 0x00,0x50,0xf8,0x50,0x50,0xf8,0x50,0x05,0x09,0x09,0x06,0x00,0xff,0x20,0x70,0xa8, - 0xa0,0x70,0x28,0xa8,0x70,0x20,0x05,0x07,0x07,0x06,0x00,0x00,0xc8,0xc8,0x10,0x20, - 0x40,0x98,0x98,0x05,0x07,0x07,0x06,0x00,0x00,0x40,0xa0,0xa0,0x40,0xa8,0x90,0x68, - 0x01,0x03,0x03,0x06,0x02,0x05,0x80,0x80,0x80,0x03,0x09,0x09,0x06,0x01,0xff,0x20, - 0x40,0x40,0x80,0x80,0x80,0x40,0x40,0x20,0x03,0x09,0x09,0x06,0x01,0xff,0x80,0x40, - 0x40,0x20,0x20,0x20,0x40,0x40,0x80,0x05,0x07,0x07,0x06,0x00,0x00,0x20,0xa8,0x70, - 0x20,0x70,0xa8,0x20,0x05,0x05,0x05,0x06,0x00,0x01,0x20,0x20,0xf8,0x20,0x20,0x02, - 0x03,0x03,0x06,0x01,0xff,0xc0,0x40,0x80,0x05,0x01,0x01,0x06,0x00,0x03,0xf8,0x02, - 0x02,0x02,0x06,0x01,0x00,0xc0,0xc0,0x05,0x07,0x07,0x06,0x00,0x00,0x08,0x10,0x10, - 0x20,0x40,0x40,0x80,0x05,0x07,0x07,0x06,0x00,0x00,0x70,0x88,0x98,0xa8,0xc8,0x88, - 0x70,0x03,0x07,0x07,0x06,0x01,0x00,0x40,0xc0,0x40,0x40,0x40,0x40,0xe0,0x05,0x07, - 0x07,0x06,0x00,0x00,0x70,0x88,0x08,0x10,0x20,0x40,0xf8,0x05,0x07,0x07,0x06,0x00, - 0x00,0xf8,0x08,0x10,0x30,0x08,0x88,0x70,0x05,0x07,0x07,0x06,0x00,0x00,0x10,0x30, - 0x50,0x90,0xf8,0x10,0x10,0x05,0x07,0x07,0x06,0x00,0x00,0xf8,0x80,0xf0,0x08,0x08, - 0x88,0x70,0x05,0x07,0x07,0x06,0x00,0x00,0x30,0x40,0x80,0xf0,0x88,0x88,0x70,0x05, - 0x07,0x07,0x06,0x00,0x00,0xf8,0x08,0x10,0x10,0x20,0x20,0x20,0x05,0x07,0x07,0x06, - 0x00,0x00,0x70,0x88,0x88,0x70,0x88,0x88,0x70,0x05,0x07,0x07,0x06,0x00,0x00,0x70, - 0x88,0x88,0x78,0x08,0x10,0x60,0x02,0x05,0x05,0x06,0x01,0x00,0xc0,0xc0,0x00,0xc0, - 0xc0,0x02,0x06,0x06,0x06,0x01,0xff,0xc0,0xc0,0x00,0xc0,0x40,0x80,0x03,0x05,0x05, - 0x06,0x01,0x01,0x20,0x40,0x80,0x40,0x20,0x05,0x03,0x03,0x06,0x00,0x02,0xf8,0x00, - 0xf8,0x03,0x05,0x05,0x06,0x01,0x01,0x80,0x40,0x20,0x40,0x80,0x05,0x07,0x07,0x06, - 0x00,0x00,0x70,0x88,0x10,0x20,0x20,0x00,0x20,0x05,0x07,0x07,0x06,0x00,0x00,0x70, - 0x88,0xb8,0xa8,0xb8,0x80,0x70,0x05,0x07,0x07,0x06,0x00,0x00,0x70,0x88,0x88,0xf8, - 0x88,0x88,0x88,0x05,0x07,0x07,0x06,0x00,0x00,0xf0,0x48,0x48,0x70,0x48,0x48,0xf0, - 0x05,0x07,0x07,0x06,0x00,0x00,0x70,0x88,0x80,0x80,0x80,0x88,0x70,0x05,0x07,0x07, - 0x06,0x00,0x00,0xf0,0x48,0x48,0x48,0x48,0x48,0xf0,0x05,0x07,0x07,0x06,0x00,0x00, - 0xf8,0x80,0x80,0xf0,0x80,0x80,0xf8,0x05,0x07,0x07,0x06,0x00,0x00,0xf8,0x80,0x80, - 0xf0,0x80,0x80,0x80,0x05,0x07,0x07,0x06,0x00,0x00,0x70,0x88,0x80,0x80,0x98,0x88, - 0x70,0x05,0x07,0x07,0x06,0x00,0x00,0x88,0x88,0x88,0xf8,0x88,0x88,0x88,0x03,0x07, - 0x07,0x06,0x01,0x00,0xe0,0x40,0x40,0x40,0x40,0x40,0xe0,0x05,0x07,0x07,0x06,0x00, - 0x00,0x38,0x10,0x10,0x10,0x10,0x90,0x60,0x05,0x07,0x07,0x06,0x00,0x00,0x88,0x90, - 0xa0,0xc0,0xa0,0x90,0x88,0x05,0x07,0x07,0x06,0x00,0x00,0x80,0x80,0x80,0x80,0x80, - 0x80,0xf8,0x05,0x07,0x07,0x06,0x00,0x00,0x88,0xd8,0xa8,0x88,0x88,0x88,0x88,0x05, - 0x07,0x07,0x06,0x00,0x00,0x88,0x88,0xc8,0xa8,0x98,0x88,0x88,0x05,0x07,0x07,0x06, - 0x00,0x00,0x70,0x88,0x88,0x88,0x88,0x88,0x70,0x05,0x07,0x07,0x06,0x00,0x00,0xf0, - 0x88,0x88,0xf0,0x80,0x80,0x80,0x05,0x07,0x07,0x06,0x00,0x00,0x70,0x88,0x88,0x88, - 0xa8,0x90,0x68,0x05,0x07,0x07,0x06,0x00,0x00,0xf0,0x88,0x88,0xf0,0xa0,0x90,0x88, - 0x05,0x07,0x07,0x06,0x00,0x00,0x70,0x88,0x80,0x70,0x08,0x88,0x70,0x05,0x07,0x07, - 0x06,0x00,0x00,0xf8,0x20,0x20,0x20,0x20,0x20,0x20,0x05,0x07,0x07,0x06,0x00,0x00, - 0x88,0x88,0x88,0x88,0x88,0x88,0x70,0x05,0x07,0x07,0x06,0x00,0x00,0x88,0x88,0x88, - 0x88,0x50,0x50,0x20,0x05,0x07,0x07,0x06,0x00,0x00,0x88,0x88,0x88,0x88,0xa8,0xa8, - 0x50,0x05,0x07,0x07,0x06,0x00,0x00,0x88,0x88,0x50,0x20,0x50,0x88,0x88,0x05,0x07, - 0x07,0x06,0x00,0x00,0x88,0x88,0x50,0x20,0x20,0x20,0x20,0x05,0x07,0x07,0x06,0x00, - 0x00,0xf8,0x08,0x10,0x20,0x40,0x80,0xf8,0x03,0x09,0x09,0x06,0x01,0xff,0xe0,0x80, - 0x80,0x80,0x80,0x80,0x80,0x80,0xe0,0x05,0x07,0x07,0x06,0x00,0x00,0x80,0x40,0x40, - 0x20,0x10,0x10,0x08,0x03,0x09,0x09,0x06,0x01,0xff,0xe0,0x20,0x20,0x20,0x20,0x20, - 0x20,0x20,0xe0,0x05,0x03,0x03,0x06,0x00,0x05,0x20,0x50,0x88,0x05,0x01,0x01,0x06, - 0x00,0xfe,0xf8,0x03,0x03,0x03,0x06,0x01,0x05,0x80,0x40,0x20,0x05,0x05,0x05,0x06, - 0x00,0x00,0x70,0x08,0x78,0x88,0x78,0x05,0x07,0x07,0x06,0x00,0x00,0x80,0x80,0xf0, - 0x88,0x88,0x88,0xf0,0x05,0x05,0x05,0x06,0x00,0x00,0x70,0x80,0x80,0x88,0x70,0x05, - 0x07,0x07,0x06,0x00,0x00,0x08,0x08,0x78,0x88,0x88,0x88,0x78,0x05,0x05,0x05,0x06, - 0x00,0x00,0x70,0x88,0xf0,0x80,0x70,0x05,0x07,0x07,0x06,0x00,0x00,0x30,0x48,0x40, - 0xe0,0x40,0x40,0x40,0x05,0x07,0x07,0x06,0x00,0xfe,0x70,0x88,0x88,0x88,0x78,0x08, - 0x70,0x05,0x07,0x07,0x06,0x00,0x00,0x80,0x80,0xf0,0x88,0x88,0x88,0x88,0x03,0x07, - 0x07,0x06,0x01,0x00,0x40,0x00,0xc0,0x40,0x40,0x40,0xe0,0x04,0x09,0x09,0x06,0x01, - 0xfe,0x10,0x00,0x30,0x10,0x10,0x10,0x10,0x90,0x60,0x05,0x07,0x07,0x06,0x00,0x00, - 0x80,0x80,0x88,0x90,0xe0,0x90,0x88,0x03,0x07,0x07,0x06,0x01,0x00,0xc0,0x40,0x40, - 0x40,0x40,0x40,0xe0,0x05,0x05,0x05,0x06,0x00,0x00,0xd0,0xa8,0xa8,0xa8,0xa8,0x05, - 0x05,0x05,0x06,0x00,0x00,0xb0,0xc8,0x88,0x88,0x88,0x05,0x05,0x05,0x06,0x00,0x00, - 0x70,0x88,0x88,0x88,0x70,0x05,0x07,0x07,0x06,0x00,0xfe,0xf0,0x88,0x88,0x88,0xf0, - 0x80,0x80,0x05,0x07,0x07,0x06,0x00,0xfe,0x78,0x88,0x88,0x88,0x78,0x08,0x08,0x05, - 0x05,0x05,0x06,0x00,0x00,0xb0,0xc8,0x80,0x80,0x80,0x05,0x05,0x05,0x06,0x00,0x00, - 0x78,0x80,0x70,0x08,0xf0,0x05,0x07,0x07,0x06,0x00,0x00,0x20,0x20,0xf8,0x20,0x20, - 0x20,0x18,0x05,0x05,0x05,0x06,0x00,0x00,0x88,0x88,0x88,0x98,0x68,0x05,0x05,0x05, - 0x06,0x00,0x00,0x88,0x88,0x88,0x50,0x20,0x05,0x05,0x05,0x06,0x00,0x00,0x88,0x88, - 0xa8,0xa8,0x50,0x05,0x05,0x05,0x06,0x00,0x00,0x88,0x50,0x20,0x50,0x88,0x05,0x07, - 0x07,0x06,0x00,0xfe,0x88,0x88,0x88,0x50,0x20,0x40,0x80,0x05,0x05,0x05,0x06,0x00, - 0x00,0xf8,0x10,0x20,0x40,0xf8,0x03,0x09,0x09,0x06,0x01,0xff,0x20,0x40,0x40,0x40, - 0x80,0x40,0x40,0x40,0x20,0x01,0x09,0x09,0x06,0x02,0xff,0x80,0x80,0x80,0x80,0x80, - 0x80,0x80,0x80,0x80,0x03,0x09,0x09,0x06,0x01,0xff,0x80,0x40,0x40,0x40,0x20,0x40, - 0x40,0x40,0x80,0x05,0x03,0x03,0x06,0x00,0x02,0x48,0xa8,0x90,0xff}; + 0xb8,0x88,0x88,0x70,0x20,0x07,0x05,0x05,0x07,0x00,0x01,0xd8,0x6c,0x36,0x6c,0xd8, + 0x05,0x09,0x09,0x06,0x00,0xff,0xf8,0xa8,0x88,0x88,0x88,0x88,0x88,0xa8,0xf8,0x05, + 0x0a,0x0a,0x06,0x00,0xfe,0x20,0x50,0x50,0x50,0x50,0x88,0xa8,0xa8,0x88,0x70,0x03, + 0x03,0x03,0x06,0x00,0x03,0x40,0xa0,0x40,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff, + 0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0x00,0x00, + 0x00,0x06,0x05,0xff,0x01,0x07,0x07,0x06,0x02,0x00,0x80,0x80,0x80,0x80,0x80,0x00, + 0x80,0x03,0x03,0x03,0x06,0x01,0x05,0xa0,0xa0,0xa0,0x05,0x06,0x06,0x06,0x00,0x00, + 0x50,0xf8,0x50,0x50,0xf8,0x50,0x05,0x09,0x09,0x06,0x00,0xff,0x20,0x70,0xa8,0xa0, + 0x70,0x28,0xa8,0x70,0x20,0x05,0x07,0x07,0x06,0x00,0x00,0xc8,0xc8,0x10,0x20,0x40, + 0x98,0x98,0x05,0x07,0x07,0x06,0x00,0x00,0x40,0xa0,0xa0,0x40,0xa8,0x90,0x68,0x01, + 0x03,0x03,0x06,0x02,0x05,0x80,0x80,0x80,0x03,0x09,0x09,0x06,0x01,0xff,0x20,0x40, + 0x40,0x80,0x80,0x80,0x40,0x40,0x20,0x03,0x09,0x09,0x06,0x01,0xff,0x80,0x40,0x40, + 0x20,0x20,0x20,0x40,0x40,0x80,0x05,0x07,0x07,0x06,0x00,0x00,0x20,0xa8,0x70,0x20, + 0x70,0xa8,0x20,0x05,0x05,0x05,0x06,0x00,0x01,0x20,0x20,0xf8,0x20,0x20,0x02,0x03, + 0x03,0x06,0x01,0xff,0xc0,0x40,0x80,0x05,0x01,0x01,0x06,0x00,0x03,0xf8,0x02,0x02, + 0x02,0x06,0x01,0x00,0xc0,0xc0,0x05,0x07,0x07,0x06,0x00,0x00,0x08,0x10,0x10,0x20, + 0x40,0x40,0x80,0x05,0x07,0x07,0x06,0x00,0x00,0x70,0x88,0x98,0xa8,0xc8,0x88,0x70, + 0x03,0x07,0x07,0x06,0x01,0x00,0x40,0xc0,0x40,0x40,0x40,0x40,0xe0,0x05,0x07,0x07, + 0x06,0x00,0x00,0x70,0x88,0x08,0x10,0x20,0x40,0xf8,0x05,0x07,0x07,0x06,0x00,0x00, + 0xf8,0x08,0x10,0x30,0x08,0x88,0x70,0x05,0x07,0x07,0x06,0x00,0x00,0x10,0x30,0x50, + 0x90,0xf8,0x10,0x10,0x05,0x07,0x07,0x06,0x00,0x00,0xf8,0x80,0xf0,0x08,0x08,0x88, + 0x70,0x05,0x07,0x07,0x06,0x00,0x00,0x30,0x40,0x80,0xf0,0x88,0x88,0x70,0x05,0x07, + 0x07,0x06,0x00,0x00,0xf8,0x08,0x10,0x10,0x20,0x20,0x20,0x05,0x07,0x07,0x06,0x00, + 0x00,0x70,0x88,0x88,0x70,0x88,0x88,0x70,0x05,0x07,0x07,0x06,0x00,0x00,0x70,0x88, + 0x88,0x78,0x08,0x10,0x60,0x02,0x05,0x05,0x06,0x01,0x00,0xc0,0xc0,0x00,0xc0,0xc0, + 0x02,0x06,0x06,0x06,0x01,0xff,0xc0,0xc0,0x00,0xc0,0x40,0x80,0x03,0x05,0x05,0x06, + 0x01,0x01,0x20,0x40,0x80,0x40,0x20,0x05,0x03,0x03,0x06,0x00,0x02,0xf8,0x00,0xf8, + 0x03,0x05,0x05,0x06,0x01,0x01,0x80,0x40,0x20,0x40,0x80,0x05,0x07,0x07,0x06,0x00, + 0x00,0x70,0x88,0x10,0x20,0x20,0x00,0x20,0x05,0x07,0x07,0x06,0x00,0x00,0x70,0x88, + 0xb8,0xa8,0xb8,0x80,0x70,0x05,0x07,0x07,0x06,0x00,0x00,0x70,0x88,0x88,0xf8,0x88, + 0x88,0x88,0x05,0x07,0x07,0x06,0x00,0x00,0xf0,0x48,0x48,0x70,0x48,0x48,0xf0,0x05, + 0x07,0x07,0x06,0x00,0x00,0x70,0x88,0x80,0x80,0x80,0x88,0x70,0x05,0x07,0x07,0x06, + 0x00,0x00,0xf0,0x48,0x48,0x48,0x48,0x48,0xf0,0x05,0x07,0x07,0x06,0x00,0x00,0xf8, + 0x80,0x80,0xf0,0x80,0x80,0xf8,0x05,0x07,0x07,0x06,0x00,0x00,0xf8,0x80,0x80,0xf0, + 0x80,0x80,0x80,0x05,0x07,0x07,0x06,0x00,0x00,0x70,0x88,0x80,0x80,0x98,0x88,0x70, + 0x05,0x07,0x07,0x06,0x00,0x00,0x88,0x88,0x88,0xf8,0x88,0x88,0x88,0x03,0x07,0x07, + 0x06,0x01,0x00,0xe0,0x40,0x40,0x40,0x40,0x40,0xe0,0x05,0x07,0x07,0x06,0x00,0x00, + 0x38,0x10,0x10,0x10,0x10,0x90,0x60,0x05,0x07,0x07,0x06,0x00,0x00,0x88,0x90,0xa0, + 0xc0,0xa0,0x90,0x88,0x05,0x07,0x07,0x06,0x00,0x00,0x80,0x80,0x80,0x80,0x80,0x80, + 0xf8,0x05,0x07,0x07,0x06,0x00,0x00,0x88,0xd8,0xa8,0x88,0x88,0x88,0x88,0x05,0x07, + 0x07,0x06,0x00,0x00,0x88,0x88,0xc8,0xa8,0x98,0x88,0x88,0x05,0x07,0x07,0x06,0x00, + 0x00,0x70,0x88,0x88,0x88,0x88,0x88,0x70,0x05,0x07,0x07,0x06,0x00,0x00,0xf0,0x88, + 0x88,0xf0,0x80,0x80,0x80,0x05,0x07,0x07,0x06,0x00,0x00,0x70,0x88,0x88,0x88,0xa8, + 0x90,0x68,0x05,0x07,0x07,0x06,0x00,0x00,0xf0,0x88,0x88,0xf0,0xa0,0x90,0x88,0x05, + 0x07,0x07,0x06,0x00,0x00,0x70,0x88,0x80,0x70,0x08,0x88,0x70,0x05,0x07,0x07,0x06, + 0x00,0x00,0xf8,0x20,0x20,0x20,0x20,0x20,0x20,0x05,0x07,0x07,0x06,0x00,0x00,0x88, + 0x88,0x88,0x88,0x88,0x88,0x70,0x05,0x07,0x07,0x06,0x00,0x00,0x88,0x88,0x88,0x88, + 0x50,0x50,0x20,0x05,0x07,0x07,0x06,0x00,0x00,0x88,0x88,0x88,0x88,0xa8,0xa8,0x50, + 0x05,0x07,0x07,0x06,0x00,0x00,0x88,0x88,0x50,0x20,0x50,0x88,0x88,0x05,0x07,0x07, + 0x06,0x00,0x00,0x88,0x88,0x50,0x20,0x20,0x20,0x20,0x05,0x07,0x07,0x06,0x00,0x00, + 0xf8,0x08,0x10,0x20,0x40,0x80,0xf8,0x03,0x09,0x09,0x06,0x01,0xff,0xe0,0x80,0x80, + 0x80,0x80,0x80,0x80,0x80,0xe0,0x05,0x07,0x07,0x06,0x00,0x00,0x80,0x40,0x40,0x20, + 0x10,0x10,0x08,0x03,0x09,0x09,0x06,0x01,0xff,0xe0,0x20,0x20,0x20,0x20,0x20,0x20, + 0x20,0xe0,0x05,0x03,0x03,0x06,0x00,0x05,0x20,0x50,0x88,0x05,0x01,0x01,0x06,0x00, + 0xfe,0xf8,0x03,0x03,0x03,0x06,0x01,0x05,0x80,0x40,0x20,0x05,0x05,0x05,0x06,0x00, + 0x00,0x70,0x08,0x78,0x88,0x78,0x05,0x07,0x07,0x06,0x00,0x00,0x80,0x80,0xf0,0x88, + 0x88,0x88,0xf0,0x05,0x05,0x05,0x06,0x00,0x00,0x70,0x80,0x80,0x88,0x70,0x05,0x07, + 0x07,0x06,0x00,0x00,0x08,0x08,0x78,0x88,0x88,0x88,0x78,0x05,0x05,0x05,0x06,0x00, + 0x00,0x70,0x88,0xf0,0x80,0x70,0x05,0x07,0x07,0x06,0x00,0x00,0x30,0x48,0x40,0xe0, + 0x40,0x40,0x40,0x05,0x07,0x07,0x06,0x00,0xfe,0x70,0x88,0x88,0x88,0x78,0x08,0x70, + 0x05,0x07,0x07,0x06,0x00,0x00,0x80,0x80,0xf0,0x88,0x88,0x88,0x88,0x03,0x07,0x07, + 0x06,0x01,0x00,0x40,0x00,0xc0,0x40,0x40,0x40,0xe0,0x04,0x09,0x09,0x06,0x01,0xfe, + 0x10,0x00,0x30,0x10,0x10,0x10,0x10,0x90,0x60,0x05,0x07,0x07,0x06,0x00,0x00,0x80, + 0x80,0x88,0x90,0xe0,0x90,0x88,0x03,0x07,0x07,0x06,0x01,0x00,0xc0,0x40,0x40,0x40, + 0x40,0x40,0xe0,0x05,0x05,0x05,0x06,0x00,0x00,0xd0,0xa8,0xa8,0xa8,0xa8,0x05,0x05, + 0x05,0x06,0x00,0x00,0xb0,0xc8,0x88,0x88,0x88,0x05,0x05,0x05,0x06,0x00,0x00,0x70, + 0x88,0x88,0x88,0x70,0x05,0x07,0x07,0x06,0x00,0xfe,0xf0,0x88,0x88,0x88,0xf0,0x80, + 0x80,0x05,0x07,0x07,0x06,0x00,0xfe,0x78,0x88,0x88,0x88,0x78,0x08,0x08,0x05,0x05, + 0x05,0x06,0x00,0x00,0xb0,0xc8,0x80,0x80,0x80,0x05,0x05,0x05,0x06,0x00,0x00,0x78, + 0x80,0x70,0x08,0xf0,0x05,0x07,0x07,0x06,0x00,0x00,0x20,0x20,0xf8,0x20,0x20,0x20, + 0x18,0x05,0x05,0x05,0x06,0x00,0x00,0x88,0x88,0x88,0x98,0x68,0x05,0x05,0x05,0x06, + 0x00,0x00,0x88,0x88,0x88,0x50,0x20,0x05,0x05,0x05,0x06,0x00,0x00,0x88,0x88,0xa8, + 0xa8,0x50,0x05,0x05,0x05,0x06,0x00,0x00,0x88,0x50,0x20,0x50,0x88,0x05,0x07,0x07, + 0x06,0x00,0xfe,0x88,0x88,0x88,0x50,0x20,0x40,0x80,0x05,0x05,0x05,0x06,0x00,0x00, + 0xf8,0x10,0x20,0x40,0xf8,0x03,0x09,0x09,0x06,0x01,0xff,0x20,0x40,0x40,0x40,0x80, + 0x40,0x40,0x40,0x20,0x01,0x09,0x09,0x06,0x02,0xff,0x80,0x80,0x80,0x80,0x80,0x80, + 0x80,0x80,0x80,0x03,0x09,0x09,0x06,0x01,0xff,0x80,0x40,0x40,0x40,0x20,0x40,0x40, + 0x40,0x80,0x05,0x03,0x03,0x06,0x00,0x02,0x48,0xa8,0x90,0xff}; #else // extended (original) font (symbols 1 - 255) @@ -123,179 +123,179 @@ const u8g_fntpgm_uint8_t ISO10646_1_5x7[1325] U8G_FONT_SECTION("ISO10646_1_5x7") Fontname: -Marlin6x12-Fixed-Medium-R-SemiCondensed--12-90-100-100-C-111-ISO10646-1 Copyright: Public domain terminal emulator font. Share and enjoy. original font -Misc-Fixed-Medium-R-SemiCondensed--12-110-75-75-C-60-ISO10646-1 Capital A Height: 7, '1' Height: 7 - Calculated Max Values w= 6 h=10 x= 5 y= 7 dx= 6 dy= 0 ascent=10 len=10 + Calculated Max Values w= 7 h=10 x= 5 y= 7 dx= 7 dy= 0 ascent=10 len=10 Font Bounding box w=12 h=15 x= 0 y=-2 Calculated Min Values x= 0 y=-2 dx= 0 dy= 0 Pure Font ascent = 7 descent=-2 X Font ascent = 8 descent=-2 Max Font ascent =10 descent=-2 */ -const u8g_fntpgm_uint8_t ISO10646_1_5x7[2648] U8G_FONT_SECTION("ISO10646_1_5x7") = { - 0x00,0x0c,0x0f,0x00,0xfe,0x07,0x02,0x26,0x03,0xbc,0x01,0xff,0xfe,0x0a,0xfe,0x08, +const u8g_fntpgm_uint8_t ISO10646_1_5x7[2647] U8G_FONT_SECTION("ISO10646_1_5x7") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x07,0x02,0x25,0x03,0xbb,0x01,0xff,0xfe,0x0a,0xfe,0x08, 0xfe,0x05,0x08,0x08,0x06,0x00,0x00,0x40,0xf0,0xc8,0x88,0x88,0x98,0x78,0x10,0x05, 0x08,0x08,0x06,0x00,0x00,0xc0,0xf8,0x88,0x88,0x88,0x88,0x88,0xf8,0x05,0x05,0x05, 0x06,0x00,0x01,0x20,0x30,0xf8,0x30,0x20,0x05,0x08,0x08,0x06,0x00,0x00,0x20,0x70, 0xf8,0x20,0x20,0x20,0x20,0xe0,0x05,0x09,0x09,0x06,0x00,0xff,0x20,0x70,0xa8,0xa8, - 0xb8,0x88,0x88,0x70,0x20,0x05,0x06,0x06,0x06,0x00,0x01,0xe0,0x8c,0xea,0x8c,0x8a, - 0x0a,0x05,0x09,0x09,0x06,0x00,0xff,0xf8,0xa8,0x88,0x88,0x88,0x88,0x88,0xa8,0xf8, - 0x05,0x0a,0x0a,0x06,0x00,0xfe,0x20,0x50,0x50,0x50,0x50,0x88,0xa8,0xa8,0x88,0x70, - 0x03,0x03,0x03,0x06,0x00,0x03,0x40,0xa0,0x40,0xff,0xff,0xff,0xff,0xff,0xff,0xff, - 0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0x00, - 0x00,0x00,0x06,0x05,0xff,0x01,0x07,0x07,0x06,0x02,0x00,0x80,0x80,0x80,0x80,0x80, - 0x00,0x80,0x03,0x03,0x03,0x06,0x01,0x05,0xa0,0xa0,0xa0,0x05,0x06,0x06,0x06,0x00, - 0x00,0x50,0xf8,0x50,0x50,0xf8,0x50,0x05,0x09,0x09,0x06,0x00,0xff,0x20,0x70,0xa8, - 0xa0,0x70,0x28,0xa8,0x70,0x20,0x05,0x07,0x07,0x06,0x00,0x00,0xc8,0xc8,0x10,0x20, - 0x40,0x98,0x98,0x05,0x07,0x07,0x06,0x00,0x00,0x40,0xa0,0xa0,0x40,0xa8,0x90,0x68, - 0x01,0x03,0x03,0x06,0x02,0x05,0x80,0x80,0x80,0x03,0x09,0x09,0x06,0x01,0xff,0x20, - 0x40,0x40,0x80,0x80,0x80,0x40,0x40,0x20,0x03,0x09,0x09,0x06,0x01,0xff,0x80,0x40, - 0x40,0x20,0x20,0x20,0x40,0x40,0x80,0x05,0x07,0x07,0x06,0x00,0x00,0x20,0xa8,0x70, - 0x20,0x70,0xa8,0x20,0x05,0x05,0x05,0x06,0x00,0x01,0x20,0x20,0xf8,0x20,0x20,0x02, - 0x03,0x03,0x06,0x01,0xff,0xc0,0x40,0x80,0x05,0x01,0x01,0x06,0x00,0x03,0xf8,0x02, - 0x02,0x02,0x06,0x01,0x00,0xc0,0xc0,0x05,0x07,0x07,0x06,0x00,0x00,0x08,0x10,0x10, - 0x20,0x40,0x40,0x80,0x05,0x07,0x07,0x06,0x00,0x00,0x70,0x88,0x98,0xa8,0xc8,0x88, - 0x70,0x03,0x07,0x07,0x06,0x01,0x00,0x40,0xc0,0x40,0x40,0x40,0x40,0xe0,0x05,0x07, - 0x07,0x06,0x00,0x00,0x70,0x88,0x08,0x10,0x20,0x40,0xf8,0x05,0x07,0x07,0x06,0x00, - 0x00,0xf8,0x08,0x10,0x30,0x08,0x88,0x70,0x05,0x07,0x07,0x06,0x00,0x00,0x10,0x30, - 0x50,0x90,0xf8,0x10,0x10,0x05,0x07,0x07,0x06,0x00,0x00,0xf8,0x80,0xf0,0x08,0x08, - 0x88,0x70,0x05,0x07,0x07,0x06,0x00,0x00,0x30,0x40,0x80,0xf0,0x88,0x88,0x70,0x05, - 0x07,0x07,0x06,0x00,0x00,0xf8,0x08,0x10,0x10,0x20,0x20,0x20,0x05,0x07,0x07,0x06, - 0x00,0x00,0x70,0x88,0x88,0x70,0x88,0x88,0x70,0x05,0x07,0x07,0x06,0x00,0x00,0x70, - 0x88,0x88,0x78,0x08,0x10,0x60,0x02,0x05,0x05,0x06,0x01,0x00,0xc0,0xc0,0x00,0xc0, - 0xc0,0x02,0x06,0x06,0x06,0x01,0xff,0xc0,0xc0,0x00,0xc0,0x40,0x80,0x03,0x05,0x05, - 0x06,0x01,0x01,0x20,0x40,0x80,0x40,0x20,0x05,0x03,0x03,0x06,0x00,0x02,0xf8,0x00, - 0xf8,0x03,0x05,0x05,0x06,0x01,0x01,0x80,0x40,0x20,0x40,0x80,0x05,0x07,0x07,0x06, - 0x00,0x00,0x70,0x88,0x10,0x20,0x20,0x00,0x20,0x05,0x07,0x07,0x06,0x00,0x00,0x70, - 0x88,0xb8,0xa8,0xb8,0x80,0x70,0x05,0x07,0x07,0x06,0x00,0x00,0x70,0x88,0x88,0xf8, - 0x88,0x88,0x88,0x05,0x07,0x07,0x06,0x00,0x00,0xf0,0x48,0x48,0x70,0x48,0x48,0xf0, - 0x05,0x07,0x07,0x06,0x00,0x00,0x70,0x88,0x80,0x80,0x80,0x88,0x70,0x05,0x07,0x07, - 0x06,0x00,0x00,0xf0,0x48,0x48,0x48,0x48,0x48,0xf0,0x05,0x07,0x07,0x06,0x00,0x00, - 0xf8,0x80,0x80,0xf0,0x80,0x80,0xf8,0x05,0x07,0x07,0x06,0x00,0x00,0xf8,0x80,0x80, - 0xf0,0x80,0x80,0x80,0x05,0x07,0x07,0x06,0x00,0x00,0x70,0x88,0x80,0x80,0x98,0x88, - 0x70,0x05,0x07,0x07,0x06,0x00,0x00,0x88,0x88,0x88,0xf8,0x88,0x88,0x88,0x03,0x07, - 0x07,0x06,0x01,0x00,0xe0,0x40,0x40,0x40,0x40,0x40,0xe0,0x05,0x07,0x07,0x06,0x00, - 0x00,0x38,0x10,0x10,0x10,0x10,0x90,0x60,0x05,0x07,0x07,0x06,0x00,0x00,0x88,0x90, - 0xa0,0xc0,0xa0,0x90,0x88,0x05,0x07,0x07,0x06,0x00,0x00,0x80,0x80,0x80,0x80,0x80, - 0x80,0xf8,0x05,0x07,0x07,0x06,0x00,0x00,0x88,0xd8,0xa8,0x88,0x88,0x88,0x88,0x05, - 0x07,0x07,0x06,0x00,0x00,0x88,0x88,0xc8,0xa8,0x98,0x88,0x88,0x05,0x07,0x07,0x06, - 0x00,0x00,0x70,0x88,0x88,0x88,0x88,0x88,0x70,0x05,0x07,0x07,0x06,0x00,0x00,0xf0, - 0x88,0x88,0xf0,0x80,0x80,0x80,0x05,0x07,0x07,0x06,0x00,0x00,0x70,0x88,0x88,0x88, - 0xa8,0x90,0x68,0x05,0x07,0x07,0x06,0x00,0x00,0xf0,0x88,0x88,0xf0,0xa0,0x90,0x88, - 0x05,0x07,0x07,0x06,0x00,0x00,0x70,0x88,0x80,0x70,0x08,0x88,0x70,0x05,0x07,0x07, - 0x06,0x00,0x00,0xf8,0x20,0x20,0x20,0x20,0x20,0x20,0x05,0x07,0x07,0x06,0x00,0x00, - 0x88,0x88,0x88,0x88,0x88,0x88,0x70,0x05,0x07,0x07,0x06,0x00,0x00,0x88,0x88,0x88, - 0x88,0x50,0x50,0x20,0x05,0x07,0x07,0x06,0x00,0x00,0x88,0x88,0x88,0x88,0xa8,0xa8, - 0x50,0x05,0x07,0x07,0x06,0x00,0x00,0x88,0x88,0x50,0x20,0x50,0x88,0x88,0x05,0x07, - 0x07,0x06,0x00,0x00,0x88,0x88,0x50,0x20,0x20,0x20,0x20,0x05,0x07,0x07,0x06,0x00, - 0x00,0xf8,0x08,0x10,0x20,0x40,0x80,0xf8,0x03,0x09,0x09,0x06,0x01,0xff,0xe0,0x80, - 0x80,0x80,0x80,0x80,0x80,0x80,0xe0,0x05,0x07,0x07,0x06,0x00,0x00,0x80,0x40,0x40, - 0x20,0x10,0x10,0x08,0x03,0x09,0x09,0x06,0x01,0xff,0xe0,0x20,0x20,0x20,0x20,0x20, - 0x20,0x20,0xe0,0x05,0x03,0x03,0x06,0x00,0x05,0x20,0x50,0x88,0x05,0x01,0x01,0x06, - 0x00,0xfe,0xf8,0x03,0x03,0x03,0x06,0x01,0x05,0x80,0x40,0x20,0x05,0x05,0x05,0x06, - 0x00,0x00,0x70,0x08,0x78,0x88,0x78,0x05,0x07,0x07,0x06,0x00,0x00,0x80,0x80,0xf0, - 0x88,0x88,0x88,0xf0,0x05,0x05,0x05,0x06,0x00,0x00,0x70,0x80,0x80,0x88,0x70,0x05, - 0x07,0x07,0x06,0x00,0x00,0x08,0x08,0x78,0x88,0x88,0x88,0x78,0x05,0x05,0x05,0x06, - 0x00,0x00,0x70,0x88,0xf0,0x80,0x70,0x05,0x07,0x07,0x06,0x00,0x00,0x30,0x48,0x40, - 0xe0,0x40,0x40,0x40,0x05,0x07,0x07,0x06,0x00,0xfe,0x70,0x88,0x88,0x88,0x78,0x08, - 0x70,0x05,0x07,0x07,0x06,0x00,0x00,0x80,0x80,0xf0,0x88,0x88,0x88,0x88,0x03,0x07, - 0x07,0x06,0x01,0x00,0x40,0x00,0xc0,0x40,0x40,0x40,0xe0,0x04,0x09,0x09,0x06,0x01, - 0xfe,0x10,0x00,0x30,0x10,0x10,0x10,0x10,0x90,0x60,0x05,0x07,0x07,0x06,0x00,0x00, - 0x80,0x80,0x88,0x90,0xe0,0x90,0x88,0x03,0x07,0x07,0x06,0x01,0x00,0xc0,0x40,0x40, - 0x40,0x40,0x40,0xe0,0x05,0x05,0x05,0x06,0x00,0x00,0xd0,0xa8,0xa8,0xa8,0xa8,0x05, - 0x05,0x05,0x06,0x00,0x00,0xb0,0xc8,0x88,0x88,0x88,0x05,0x05,0x05,0x06,0x00,0x00, - 0x70,0x88,0x88,0x88,0x70,0x05,0x07,0x07,0x06,0x00,0xfe,0xf0,0x88,0x88,0x88,0xf0, - 0x80,0x80,0x05,0x07,0x07,0x06,0x00,0xfe,0x78,0x88,0x88,0x88,0x78,0x08,0x08,0x05, - 0x05,0x05,0x06,0x00,0x00,0xb0,0xc8,0x80,0x80,0x80,0x05,0x05,0x05,0x06,0x00,0x00, - 0x78,0x80,0x70,0x08,0xf0,0x05,0x07,0x07,0x06,0x00,0x00,0x20,0x20,0xf8,0x20,0x20, - 0x20,0x18,0x05,0x05,0x05,0x06,0x00,0x00,0x88,0x88,0x88,0x98,0x68,0x05,0x05,0x05, - 0x06,0x00,0x00,0x88,0x88,0x88,0x50,0x20,0x05,0x05,0x05,0x06,0x00,0x00,0x88,0x88, - 0xa8,0xa8,0x50,0x05,0x05,0x05,0x06,0x00,0x00,0x88,0x50,0x20,0x50,0x88,0x05,0x07, - 0x07,0x06,0x00,0xfe,0x88,0x88,0x88,0x50,0x20,0x40,0x80,0x05,0x05,0x05,0x06,0x00, - 0x00,0xf8,0x10,0x20,0x40,0xf8,0x03,0x09,0x09,0x06,0x01,0xff,0x20,0x40,0x40,0x40, - 0x80,0x40,0x40,0x40,0x20,0x01,0x09,0x09,0x06,0x02,0xff,0x80,0x80,0x80,0x80,0x80, - 0x80,0x80,0x80,0x80,0x03,0x09,0x09,0x06,0x01,0xff,0x80,0x40,0x40,0x40,0x20,0x40, - 0x40,0x40,0x80,0x05,0x03,0x03,0x06,0x00,0x02,0x48,0xa8,0x90,0xff,0xff,0xff,0xff, + 0xb8,0x88,0x88,0x70,0x20,0x07,0x05,0x05,0x07,0x00,0x01,0xd8,0x6c,0x36,0x6c,0xd8, + 0x05,0x09,0x09,0x06,0x00,0xff,0xf8,0xa8,0x88,0x88,0x88,0x88,0x88,0xa8,0xf8,0x05, + 0x0a,0x0a,0x06,0x00,0xfe,0x20,0x50,0x50,0x50,0x50,0x88,0xa8,0xa8,0x88,0x70,0x03, + 0x03,0x03,0x06,0x00,0x03,0x40,0xa0,0x40,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff, + 0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0x00,0x00, + 0x00,0x06,0x05,0xff,0x01,0x07,0x07,0x06,0x02,0x00,0x80,0x80,0x80,0x80,0x80,0x00, + 0x80,0x03,0x03,0x03,0x06,0x01,0x05,0xa0,0xa0,0xa0,0x05,0x06,0x06,0x06,0x00,0x00, + 0x50,0xf8,0x50,0x50,0xf8,0x50,0x05,0x09,0x09,0x06,0x00,0xff,0x20,0x70,0xa8,0xa0, + 0x70,0x28,0xa8,0x70,0x20,0x05,0x07,0x07,0x06,0x00,0x00,0xc8,0xc8,0x10,0x20,0x40, + 0x98,0x98,0x05,0x07,0x07,0x06,0x00,0x00,0x40,0xa0,0xa0,0x40,0xa8,0x90,0x68,0x01, + 0x03,0x03,0x06,0x02,0x05,0x80,0x80,0x80,0x03,0x09,0x09,0x06,0x01,0xff,0x20,0x40, + 0x40,0x80,0x80,0x80,0x40,0x40,0x20,0x03,0x09,0x09,0x06,0x01,0xff,0x80,0x40,0x40, + 0x20,0x20,0x20,0x40,0x40,0x80,0x05,0x07,0x07,0x06,0x00,0x00,0x20,0xa8,0x70,0x20, + 0x70,0xa8,0x20,0x05,0x05,0x05,0x06,0x00,0x01,0x20,0x20,0xf8,0x20,0x20,0x02,0x03, + 0x03,0x06,0x01,0xff,0xc0,0x40,0x80,0x05,0x01,0x01,0x06,0x00,0x03,0xf8,0x02,0x02, + 0x02,0x06,0x01,0x00,0xc0,0xc0,0x05,0x07,0x07,0x06,0x00,0x00,0x08,0x10,0x10,0x20, + 0x40,0x40,0x80,0x05,0x07,0x07,0x06,0x00,0x00,0x70,0x88,0x98,0xa8,0xc8,0x88,0x70, + 0x03,0x07,0x07,0x06,0x01,0x00,0x40,0xc0,0x40,0x40,0x40,0x40,0xe0,0x05,0x07,0x07, + 0x06,0x00,0x00,0x70,0x88,0x08,0x10,0x20,0x40,0xf8,0x05,0x07,0x07,0x06,0x00,0x00, + 0xf8,0x08,0x10,0x30,0x08,0x88,0x70,0x05,0x07,0x07,0x06,0x00,0x00,0x10,0x30,0x50, + 0x90,0xf8,0x10,0x10,0x05,0x07,0x07,0x06,0x00,0x00,0xf8,0x80,0xf0,0x08,0x08,0x88, + 0x70,0x05,0x07,0x07,0x06,0x00,0x00,0x30,0x40,0x80,0xf0,0x88,0x88,0x70,0x05,0x07, + 0x07,0x06,0x00,0x00,0xf8,0x08,0x10,0x10,0x20,0x20,0x20,0x05,0x07,0x07,0x06,0x00, + 0x00,0x70,0x88,0x88,0x70,0x88,0x88,0x70,0x05,0x07,0x07,0x06,0x00,0x00,0x70,0x88, + 0x88,0x78,0x08,0x10,0x60,0x02,0x05,0x05,0x06,0x01,0x00,0xc0,0xc0,0x00,0xc0,0xc0, + 0x02,0x06,0x06,0x06,0x01,0xff,0xc0,0xc0,0x00,0xc0,0x40,0x80,0x03,0x05,0x05,0x06, + 0x01,0x01,0x20,0x40,0x80,0x40,0x20,0x05,0x03,0x03,0x06,0x00,0x02,0xf8,0x00,0xf8, + 0x03,0x05,0x05,0x06,0x01,0x01,0x80,0x40,0x20,0x40,0x80,0x05,0x07,0x07,0x06,0x00, + 0x00,0x70,0x88,0x10,0x20,0x20,0x00,0x20,0x05,0x07,0x07,0x06,0x00,0x00,0x70,0x88, + 0xb8,0xa8,0xb8,0x80,0x70,0x05,0x07,0x07,0x06,0x00,0x00,0x70,0x88,0x88,0xf8,0x88, + 0x88,0x88,0x05,0x07,0x07,0x06,0x00,0x00,0xf0,0x48,0x48,0x70,0x48,0x48,0xf0,0x05, + 0x07,0x07,0x06,0x00,0x00,0x70,0x88,0x80,0x80,0x80,0x88,0x70,0x05,0x07,0x07,0x06, + 0x00,0x00,0xf0,0x48,0x48,0x48,0x48,0x48,0xf0,0x05,0x07,0x07,0x06,0x00,0x00,0xf8, + 0x80,0x80,0xf0,0x80,0x80,0xf8,0x05,0x07,0x07,0x06,0x00,0x00,0xf8,0x80,0x80,0xf0, + 0x80,0x80,0x80,0x05,0x07,0x07,0x06,0x00,0x00,0x70,0x88,0x80,0x80,0x98,0x88,0x70, + 0x05,0x07,0x07,0x06,0x00,0x00,0x88,0x88,0x88,0xf8,0x88,0x88,0x88,0x03,0x07,0x07, + 0x06,0x01,0x00,0xe0,0x40,0x40,0x40,0x40,0x40,0xe0,0x05,0x07,0x07,0x06,0x00,0x00, + 0x38,0x10,0x10,0x10,0x10,0x90,0x60,0x05,0x07,0x07,0x06,0x00,0x00,0x88,0x90,0xa0, + 0xc0,0xa0,0x90,0x88,0x05,0x07,0x07,0x06,0x00,0x00,0x80,0x80,0x80,0x80,0x80,0x80, + 0xf8,0x05,0x07,0x07,0x06,0x00,0x00,0x88,0xd8,0xa8,0x88,0x88,0x88,0x88,0x05,0x07, + 0x07,0x06,0x00,0x00,0x88,0x88,0xc8,0xa8,0x98,0x88,0x88,0x05,0x07,0x07,0x06,0x00, + 0x00,0x70,0x88,0x88,0x88,0x88,0x88,0x70,0x05,0x07,0x07,0x06,0x00,0x00,0xf0,0x88, + 0x88,0xf0,0x80,0x80,0x80,0x05,0x07,0x07,0x06,0x00,0x00,0x70,0x88,0x88,0x88,0xa8, + 0x90,0x68,0x05,0x07,0x07,0x06,0x00,0x00,0xf0,0x88,0x88,0xf0,0xa0,0x90,0x88,0x05, + 0x07,0x07,0x06,0x00,0x00,0x70,0x88,0x80,0x70,0x08,0x88,0x70,0x05,0x07,0x07,0x06, + 0x00,0x00,0xf8,0x20,0x20,0x20,0x20,0x20,0x20,0x05,0x07,0x07,0x06,0x00,0x00,0x88, + 0x88,0x88,0x88,0x88,0x88,0x70,0x05,0x07,0x07,0x06,0x00,0x00,0x88,0x88,0x88,0x88, + 0x50,0x50,0x20,0x05,0x07,0x07,0x06,0x00,0x00,0x88,0x88,0x88,0x88,0xa8,0xa8,0x50, + 0x05,0x07,0x07,0x06,0x00,0x00,0x88,0x88,0x50,0x20,0x50,0x88,0x88,0x05,0x07,0x07, + 0x06,0x00,0x00,0x88,0x88,0x50,0x20,0x20,0x20,0x20,0x05,0x07,0x07,0x06,0x00,0x00, + 0xf8,0x08,0x10,0x20,0x40,0x80,0xf8,0x03,0x09,0x09,0x06,0x01,0xff,0xe0,0x80,0x80, + 0x80,0x80,0x80,0x80,0x80,0xe0,0x05,0x07,0x07,0x06,0x00,0x00,0x80,0x40,0x40,0x20, + 0x10,0x10,0x08,0x03,0x09,0x09,0x06,0x01,0xff,0xe0,0x20,0x20,0x20,0x20,0x20,0x20, + 0x20,0xe0,0x05,0x03,0x03,0x06,0x00,0x05,0x20,0x50,0x88,0x05,0x01,0x01,0x06,0x00, + 0xfe,0xf8,0x03,0x03,0x03,0x06,0x01,0x05,0x80,0x40,0x20,0x05,0x05,0x05,0x06,0x00, + 0x00,0x70,0x08,0x78,0x88,0x78,0x05,0x07,0x07,0x06,0x00,0x00,0x80,0x80,0xf0,0x88, + 0x88,0x88,0xf0,0x05,0x05,0x05,0x06,0x00,0x00,0x70,0x80,0x80,0x88,0x70,0x05,0x07, + 0x07,0x06,0x00,0x00,0x08,0x08,0x78,0x88,0x88,0x88,0x78,0x05,0x05,0x05,0x06,0x00, + 0x00,0x70,0x88,0xf0,0x80,0x70,0x05,0x07,0x07,0x06,0x00,0x00,0x30,0x48,0x40,0xe0, + 0x40,0x40,0x40,0x05,0x07,0x07,0x06,0x00,0xfe,0x70,0x88,0x88,0x88,0x78,0x08,0x70, + 0x05,0x07,0x07,0x06,0x00,0x00,0x80,0x80,0xf0,0x88,0x88,0x88,0x88,0x03,0x07,0x07, + 0x06,0x01,0x00,0x40,0x00,0xc0,0x40,0x40,0x40,0xe0,0x04,0x09,0x09,0x06,0x01,0xfe, + 0x10,0x00,0x30,0x10,0x10,0x10,0x10,0x90,0x60,0x05,0x07,0x07,0x06,0x00,0x00,0x80, + 0x80,0x88,0x90,0xe0,0x90,0x88,0x03,0x07,0x07,0x06,0x01,0x00,0xc0,0x40,0x40,0x40, + 0x40,0x40,0xe0,0x05,0x05,0x05,0x06,0x00,0x00,0xd0,0xa8,0xa8,0xa8,0xa8,0x05,0x05, + 0x05,0x06,0x00,0x00,0xb0,0xc8,0x88,0x88,0x88,0x05,0x05,0x05,0x06,0x00,0x00,0x70, + 0x88,0x88,0x88,0x70,0x05,0x07,0x07,0x06,0x00,0xfe,0xf0,0x88,0x88,0x88,0xf0,0x80, + 0x80,0x05,0x07,0x07,0x06,0x00,0xfe,0x78,0x88,0x88,0x88,0x78,0x08,0x08,0x05,0x05, + 0x05,0x06,0x00,0x00,0xb0,0xc8,0x80,0x80,0x80,0x05,0x05,0x05,0x06,0x00,0x00,0x78, + 0x80,0x70,0x08,0xf0,0x05,0x07,0x07,0x06,0x00,0x00,0x20,0x20,0xf8,0x20,0x20,0x20, + 0x18,0x05,0x05,0x05,0x06,0x00,0x00,0x88,0x88,0x88,0x98,0x68,0x05,0x05,0x05,0x06, + 0x00,0x00,0x88,0x88,0x88,0x50,0x20,0x05,0x05,0x05,0x06,0x00,0x00,0x88,0x88,0xa8, + 0xa8,0x50,0x05,0x05,0x05,0x06,0x00,0x00,0x88,0x50,0x20,0x50,0x88,0x05,0x07,0x07, + 0x06,0x00,0xfe,0x88,0x88,0x88,0x50,0x20,0x40,0x80,0x05,0x05,0x05,0x06,0x00,0x00, + 0xf8,0x10,0x20,0x40,0xf8,0x03,0x09,0x09,0x06,0x01,0xff,0x20,0x40,0x40,0x40,0x80, + 0x40,0x40,0x40,0x20,0x01,0x09,0x09,0x06,0x02,0xff,0x80,0x80,0x80,0x80,0x80,0x80, + 0x80,0x80,0x80,0x03,0x09,0x09,0x06,0x01,0xff,0x80,0x40,0x40,0x40,0x20,0x40,0x40, + 0x40,0x80,0x05,0x03,0x03,0x06,0x00,0x02,0x48,0xa8,0x90,0xff,0xff,0xff,0xff,0xff, 0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff, - 0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0x00,0x00,0x00, - 0x06,0x05,0xff,0x01,0x07,0x07,0x06,0x02,0x00,0x80,0x00,0x80,0x80,0x80,0x80,0x80, - 0x05,0x07,0x07,0x06,0x00,0xff,0x20,0x70,0xa8,0xa0,0xa8,0x70,0x20,0x05,0x07,0x07, - 0x06,0x00,0x00,0x30,0x48,0x40,0xe0,0x40,0x48,0xb0,0x05,0x05,0x05,0x06,0x00,0x00, - 0xa8,0x50,0x88,0x50,0xa8,0x05,0x07,0x07,0x06,0x00,0x00,0x88,0x50,0xf8,0x20,0xf8, - 0x20,0x20,0x01,0x07,0x07,0x06,0x02,0x00,0x80,0x80,0x80,0x00,0x80,0x80,0x80,0x04, - 0x08,0x08,0x06,0x01,0x00,0x70,0x80,0x60,0x90,0x90,0x60,0x10,0xe0,0x03,0x01,0x01, - 0x06,0x01,0x07,0xa0,0x06,0x07,0x07,0x06,0x00,0x00,0x78,0x84,0xb4,0xa4,0xb4,0x84, - 0x78,0x03,0x05,0x05,0x06,0x01,0x04,0x60,0xa0,0x60,0x00,0xe0,0x05,0x05,0x05,0x06, - 0x00,0x00,0x28,0x50,0xa0,0x50,0x28,0x05,0x03,0x03,0x06,0x00,0x01,0xf8,0x08,0x08, - 0x03,0x01,0x01,0x06,0x01,0x03,0xe0,0x06,0x07,0x07,0x06,0x00,0x00,0x78,0x84,0xb4, - 0xa4,0xa4,0x84,0x78,0x05,0x01,0x01,0x06,0x00,0x07,0xf8,0x04,0x04,0x04,0x06,0x01, - 0x05,0x60,0x90,0x90,0x60,0x05,0x07,0x07,0x06,0x00,0x00,0x20,0x20,0xf8,0x20,0x20, - 0x00,0xf8,0x03,0x05,0x05,0x06,0x01,0x04,0x40,0xa0,0x20,0x40,0xe0,0x03,0x05,0x05, - 0x06,0x01,0x04,0xc0,0x20,0x40,0x20,0xc0,0x03,0x03,0x03,0x06,0x01,0x05,0x20,0x40, - 0x80,0x05,0x07,0x07,0x06,0x00,0xfe,0x88,0x88,0x88,0x98,0xe8,0x80,0x80,0x05,0x08, - 0x08,0x06,0x00,0x00,0x78,0xe8,0xe8,0xe8,0x68,0x28,0x28,0x28,0x02,0x02,0x02,0x06, - 0x02,0x03,0xc0,0xc0,0x03,0x02,0x02,0x06,0x01,0xfe,0x20,0xc0,0x03,0x05,0x05,0x06, - 0x01,0x04,0x40,0xc0,0x40,0x40,0xe0,0x03,0x05,0x05,0x06,0x01,0x05,0x40,0xa0,0x40, - 0x00,0xe0,0x05,0x05,0x05,0x06,0x00,0x00,0xa0,0x50,0x28,0x50,0xa0,0x05,0x0a,0x0a, - 0x06,0x00,0x00,0x40,0xc0,0x48,0x50,0x60,0x50,0xb0,0x50,0x78,0x10,0x05,0x0a,0x0a, - 0x06,0x00,0x00,0x40,0xc0,0x48,0x50,0x60,0x50,0xa8,0x08,0x10,0x38,0x05,0x0a,0x0a, - 0x06,0x00,0x00,0xc0,0x20,0x48,0x30,0xe0,0x50,0xb0,0x50,0x78,0x10,0x05,0x07,0x07, - 0x06,0x00,0x00,0x20,0x00,0x20,0x20,0x40,0x88,0x70,0x05,0x0a,0x0a,0x06,0x00,0x00, - 0x40,0x20,0x00,0x70,0x88,0x88,0xf8,0x88,0x88,0x88,0x05,0x0a,0x0a,0x06,0x00,0x00, - 0x10,0x20,0x00,0x70,0x88,0x88,0xf8,0x88,0x88,0x88,0x05,0x0a,0x0a,0x06,0x00,0x00, - 0x20,0x50,0x00,0x70,0x88,0x88,0xf8,0x88,0x88,0x88,0x05,0x0a,0x0a,0x06,0x00,0x00, - 0x68,0xb0,0x00,0x70,0x88,0x88,0xf8,0x88,0x88,0x88,0x05,0x09,0x09,0x06,0x00,0x00, - 0x50,0x00,0x70,0x88,0x88,0xf8,0x88,0x88,0x88,0x05,0x0a,0x0a,0x06,0x00,0x00,0x20, - 0x50,0x20,0x70,0x88,0x88,0xf8,0x88,0x88,0x88,0x05,0x07,0x07,0x06,0x00,0x00,0x78, - 0xa0,0xa0,0xf0,0xa0,0xa0,0xb8,0x05,0x09,0x09,0x06,0x00,0xfe,0x70,0x88,0x80,0x80, - 0x80,0x88,0x70,0x10,0x60,0x05,0x0a,0x0a,0x06,0x00,0x00,0x40,0x20,0x00,0xf8,0x80, - 0x80,0xf0,0x80,0x80,0xf8,0x05,0x0a,0x0a,0x06,0x00,0x00,0x10,0x20,0x00,0xf8,0x80, - 0x80,0xf0,0x80,0x80,0xf8,0x05,0x0a,0x0a,0x06,0x00,0x00,0x20,0x50,0x00,0xf8,0x80, - 0x80,0xf0,0x80,0x80,0xf8,0x05,0x09,0x09,0x06,0x00,0x00,0x50,0x00,0xf8,0x80,0x80, - 0xf0,0x80,0x80,0xf8,0x03,0x0a,0x0a,0x06,0x01,0x00,0x80,0x40,0x00,0xe0,0x40,0x40, - 0x40,0x40,0x40,0xe0,0x03,0x0a,0x0a,0x06,0x01,0x00,0x20,0x40,0x00,0xe0,0x40,0x40, - 0x40,0x40,0x40,0xe0,0x03,0x0a,0x0a,0x06,0x01,0x00,0x40,0xa0,0x00,0xe0,0x40,0x40, - 0x40,0x40,0x40,0xe0,0x03,0x09,0x09,0x06,0x01,0x00,0xa0,0x00,0xe0,0x40,0x40,0x40, - 0x40,0x40,0xe0,0x05,0x07,0x07,0x06,0x00,0x00,0x70,0x48,0x48,0xe8,0x48,0x48,0x70, - 0x05,0x0a,0x0a,0x06,0x00,0x00,0x68,0xb0,0x00,0x88,0x88,0xc8,0xa8,0x98,0x88,0x88, - 0x05,0x0a,0x0a,0x06,0x00,0x00,0x40,0x20,0x00,0x70,0x88,0x88,0x88,0x88,0x88,0x70, - 0x05,0x0a,0x0a,0x06,0x00,0x00,0x10,0x20,0x00,0x70,0x88,0x88,0x88,0x88,0x88,0x70, - 0x05,0x0a,0x0a,0x06,0x00,0x00,0x20,0x50,0x00,0x70,0x88,0x88,0x88,0x88,0x88,0x70, - 0x05,0x0a,0x0a,0x06,0x00,0x00,0x68,0xb0,0x00,0x70,0x88,0x88,0x88,0x88,0x88,0x70, - 0x05,0x09,0x09,0x06,0x00,0x00,0x50,0x00,0x70,0x88,0x88,0x88,0x88,0x88,0x70,0x05, - 0x05,0x05,0x06,0x00,0x01,0x88,0x50,0x20,0x50,0x88,0x05,0x09,0x09,0x06,0x00,0xff, - 0x08,0x70,0x98,0xa8,0xa8,0xa8,0xc8,0x70,0x80,0x05,0x0a,0x0a,0x06,0x00,0x00,0x40, - 0x20,0x00,0x88,0x88,0x88,0x88,0x88,0x88,0x70,0x05,0x0a,0x0a,0x06,0x00,0x00,0x10, - 0x20,0x00,0x88,0x88,0x88,0x88,0x88,0x88,0x70,0x05,0x0a,0x0a,0x06,0x00,0x00,0x20, - 0x50,0x00,0x88,0x88,0x88,0x88,0x88,0x88,0x70,0x05,0x09,0x09,0x06,0x00,0x00,0x50, + 0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0x00,0x00,0x00,0x06, + 0x05,0xff,0x01,0x07,0x07,0x06,0x02,0x00,0x80,0x00,0x80,0x80,0x80,0x80,0x80,0x05, + 0x07,0x07,0x06,0x00,0xff,0x20,0x70,0xa8,0xa0,0xa8,0x70,0x20,0x05,0x07,0x07,0x06, + 0x00,0x00,0x30,0x48,0x40,0xe0,0x40,0x48,0xb0,0x05,0x05,0x05,0x06,0x00,0x00,0xa8, + 0x50,0x88,0x50,0xa8,0x05,0x07,0x07,0x06,0x00,0x00,0x88,0x50,0xf8,0x20,0xf8,0x20, + 0x20,0x01,0x07,0x07,0x06,0x02,0x00,0x80,0x80,0x80,0x00,0x80,0x80,0x80,0x04,0x08, + 0x08,0x06,0x01,0x00,0x70,0x80,0x60,0x90,0x90,0x60,0x10,0xe0,0x03,0x01,0x01,0x06, + 0x01,0x07,0xa0,0x06,0x07,0x07,0x06,0x00,0x00,0x78,0x84,0xb4,0xa4,0xb4,0x84,0x78, + 0x03,0x05,0x05,0x06,0x01,0x04,0x60,0xa0,0x60,0x00,0xe0,0x05,0x05,0x05,0x06,0x00, + 0x00,0x28,0x50,0xa0,0x50,0x28,0x05,0x03,0x03,0x06,0x00,0x01,0xf8,0x08,0x08,0x03, + 0x01,0x01,0x06,0x01,0x03,0xe0,0x06,0x07,0x07,0x06,0x00,0x00,0x78,0x84,0xb4,0xa4, + 0xa4,0x84,0x78,0x05,0x01,0x01,0x06,0x00,0x07,0xf8,0x04,0x04,0x04,0x06,0x01,0x05, + 0x60,0x90,0x90,0x60,0x05,0x07,0x07,0x06,0x00,0x00,0x20,0x20,0xf8,0x20,0x20,0x00, + 0xf8,0x03,0x05,0x05,0x06,0x01,0x04,0x40,0xa0,0x20,0x40,0xe0,0x03,0x05,0x05,0x06, + 0x01,0x04,0xc0,0x20,0x40,0x20,0xc0,0x03,0x03,0x03,0x06,0x01,0x05,0x20,0x40,0x80, + 0x05,0x07,0x07,0x06,0x00,0xfe,0x88,0x88,0x88,0x98,0xe8,0x80,0x80,0x05,0x08,0x08, + 0x06,0x00,0x00,0x78,0xe8,0xe8,0xe8,0x68,0x28,0x28,0x28,0x02,0x02,0x02,0x06,0x02, + 0x03,0xc0,0xc0,0x03,0x02,0x02,0x06,0x01,0xfe,0x20,0xc0,0x03,0x05,0x05,0x06,0x01, + 0x04,0x40,0xc0,0x40,0x40,0xe0,0x03,0x05,0x05,0x06,0x01,0x05,0x40,0xa0,0x40,0x00, + 0xe0,0x05,0x05,0x05,0x06,0x00,0x00,0xa0,0x50,0x28,0x50,0xa0,0x05,0x0a,0x0a,0x06, + 0x00,0x00,0x40,0xc0,0x48,0x50,0x60,0x50,0xb0,0x50,0x78,0x10,0x05,0x0a,0x0a,0x06, + 0x00,0x00,0x40,0xc0,0x48,0x50,0x60,0x50,0xa8,0x08,0x10,0x38,0x05,0x0a,0x0a,0x06, + 0x00,0x00,0xc0,0x20,0x48,0x30,0xe0,0x50,0xb0,0x50,0x78,0x10,0x05,0x07,0x07,0x06, + 0x00,0x00,0x20,0x00,0x20,0x20,0x40,0x88,0x70,0x05,0x0a,0x0a,0x06,0x00,0x00,0x40, + 0x20,0x00,0x70,0x88,0x88,0xf8,0x88,0x88,0x88,0x05,0x0a,0x0a,0x06,0x00,0x00,0x10, + 0x20,0x00,0x70,0x88,0x88,0xf8,0x88,0x88,0x88,0x05,0x0a,0x0a,0x06,0x00,0x00,0x20, + 0x50,0x00,0x70,0x88,0x88,0xf8,0x88,0x88,0x88,0x05,0x0a,0x0a,0x06,0x00,0x00,0x68, + 0xb0,0x00,0x70,0x88,0x88,0xf8,0x88,0x88,0x88,0x05,0x09,0x09,0x06,0x00,0x00,0x50, + 0x00,0x70,0x88,0x88,0xf8,0x88,0x88,0x88,0x05,0x0a,0x0a,0x06,0x00,0x00,0x20,0x50, + 0x20,0x70,0x88,0x88,0xf8,0x88,0x88,0x88,0x05,0x07,0x07,0x06,0x00,0x00,0x78,0xa0, + 0xa0,0xf0,0xa0,0xa0,0xb8,0x05,0x09,0x09,0x06,0x00,0xfe,0x70,0x88,0x80,0x80,0x80, + 0x88,0x70,0x10,0x60,0x05,0x0a,0x0a,0x06,0x00,0x00,0x40,0x20,0x00,0xf8,0x80,0x80, + 0xf0,0x80,0x80,0xf8,0x05,0x0a,0x0a,0x06,0x00,0x00,0x10,0x20,0x00,0xf8,0x80,0x80, + 0xf0,0x80,0x80,0xf8,0x05,0x0a,0x0a,0x06,0x00,0x00,0x20,0x50,0x00,0xf8,0x80,0x80, + 0xf0,0x80,0x80,0xf8,0x05,0x09,0x09,0x06,0x00,0x00,0x50,0x00,0xf8,0x80,0x80,0xf0, + 0x80,0x80,0xf8,0x03,0x0a,0x0a,0x06,0x01,0x00,0x80,0x40,0x00,0xe0,0x40,0x40,0x40, + 0x40,0x40,0xe0,0x03,0x0a,0x0a,0x06,0x01,0x00,0x20,0x40,0x00,0xe0,0x40,0x40,0x40, + 0x40,0x40,0xe0,0x03,0x0a,0x0a,0x06,0x01,0x00,0x40,0xa0,0x00,0xe0,0x40,0x40,0x40, + 0x40,0x40,0xe0,0x03,0x09,0x09,0x06,0x01,0x00,0xa0,0x00,0xe0,0x40,0x40,0x40,0x40, + 0x40,0xe0,0x05,0x07,0x07,0x06,0x00,0x00,0x70,0x48,0x48,0xe8,0x48,0x48,0x70,0x05, + 0x0a,0x0a,0x06,0x00,0x00,0x68,0xb0,0x00,0x88,0x88,0xc8,0xa8,0x98,0x88,0x88,0x05, + 0x0a,0x0a,0x06,0x00,0x00,0x40,0x20,0x00,0x70,0x88,0x88,0x88,0x88,0x88,0x70,0x05, + 0x0a,0x0a,0x06,0x00,0x00,0x10,0x20,0x00,0x70,0x88,0x88,0x88,0x88,0x88,0x70,0x05, + 0x0a,0x0a,0x06,0x00,0x00,0x20,0x50,0x00,0x70,0x88,0x88,0x88,0x88,0x88,0x70,0x05, + 0x0a,0x0a,0x06,0x00,0x00,0x68,0xb0,0x00,0x70,0x88,0x88,0x88,0x88,0x88,0x70,0x05, + 0x09,0x09,0x06,0x00,0x00,0x50,0x00,0x70,0x88,0x88,0x88,0x88,0x88,0x70,0x05,0x05, + 0x05,0x06,0x00,0x01,0x88,0x50,0x20,0x50,0x88,0x05,0x09,0x09,0x06,0x00,0xff,0x08, + 0x70,0x98,0xa8,0xa8,0xa8,0xc8,0x70,0x80,0x05,0x0a,0x0a,0x06,0x00,0x00,0x40,0x20, 0x00,0x88,0x88,0x88,0x88,0x88,0x88,0x70,0x05,0x0a,0x0a,0x06,0x00,0x00,0x10,0x20, - 0x00,0x88,0x88,0x50,0x20,0x20,0x20,0x20,0x04,0x07,0x07,0x06,0x01,0x00,0x80,0xe0, - 0x90,0x90,0x90,0xe0,0x80,0x05,0x07,0x07,0x06,0x00,0x00,0x70,0x88,0x90,0xa0,0x90, - 0x88,0xb0,0x05,0x08,0x08,0x06,0x00,0x00,0x40,0x20,0x00,0x70,0x08,0x78,0x88,0x78, - 0x05,0x08,0x08,0x06,0x00,0x00,0x10,0x20,0x00,0x70,0x08,0x78,0x88,0x78,0x05,0x08, - 0x08,0x06,0x00,0x00,0x20,0x50,0x00,0x70,0x08,0x78,0x88,0x78,0x05,0x08,0x08,0x06, - 0x00,0x00,0x68,0xb0,0x00,0x70,0x08,0x78,0x88,0x78,0x05,0x07,0x07,0x06,0x00,0x00, - 0x50,0x00,0x70,0x08,0x78,0x88,0x78,0x05,0x08,0x08,0x06,0x00,0x00,0x20,0x50,0x20, - 0x70,0x08,0x78,0x88,0x78,0x05,0x05,0x05,0x06,0x00,0x00,0x70,0x28,0x70,0xa0,0x78, - 0x05,0x07,0x07,0x06,0x00,0xfe,0x70,0x88,0x80,0x88,0x70,0x10,0x60,0x05,0x08,0x08, - 0x06,0x00,0x00,0x40,0x20,0x00,0x70,0x88,0xf0,0x80,0x70,0x05,0x08,0x08,0x06,0x00, - 0x00,0x10,0x20,0x00,0x70,0x88,0xf0,0x80,0x70,0x05,0x08,0x08,0x06,0x00,0x00,0x20, - 0x50,0x00,0x70,0x88,0xf0,0x80,0x70,0x05,0x07,0x07,0x06,0x00,0x00,0x50,0x00,0x70, - 0x88,0xf0,0x80,0x70,0x03,0x08,0x08,0x06,0x01,0x00,0x80,0x40,0x00,0xc0,0x40,0x40, - 0x40,0xe0,0x03,0x08,0x08,0x06,0x01,0x00,0x20,0x40,0x00,0xc0,0x40,0x40,0x40,0xe0, - 0x03,0x08,0x08,0x06,0x01,0x00,0x40,0xa0,0x00,0xc0,0x40,0x40,0x40,0xe0,0x03,0x07, - 0x07,0x06,0x01,0x00,0xa0,0x00,0xc0,0x40,0x40,0x40,0xe0,0x05,0x09,0x09,0x06,0x00, - 0x00,0x50,0x20,0x50,0x08,0x78,0x88,0x88,0x88,0x70,0x05,0x08,0x08,0x06,0x00,0x00, - 0x68,0xb0,0x00,0xb0,0xc8,0x88,0x88,0x88,0x05,0x08,0x08,0x06,0x00,0x00,0x40,0x20, - 0x00,0x70,0x88,0x88,0x88,0x70,0x05,0x08,0x08,0x06,0x00,0x00,0x10,0x20,0x00,0x70, - 0x88,0x88,0x88,0x70,0x05,0x08,0x08,0x06,0x00,0x00,0x20,0x50,0x00,0x70,0x88,0x88, - 0x88,0x70,0x05,0x08,0x08,0x06,0x00,0x00,0x68,0xb0,0x00,0x70,0x88,0x88,0x88,0x70, - 0x05,0x07,0x07,0x06,0x00,0x00,0x50,0x00,0x70,0x88,0x88,0x88,0x70,0x05,0x05,0x05, - 0x06,0x00,0x01,0x20,0x00,0xf8,0x00,0x20,0x05,0x05,0x05,0x06,0x00,0x00,0x78,0x98, - 0xa8,0xc8,0xf0,0x05,0x08,0x08,0x06,0x00,0x00,0x40,0x20,0x00,0x88,0x88,0x88,0x88, - 0x70,0x05,0x08,0x08,0x06,0x00,0x00,0x10,0x20,0x00,0x88,0x88,0x88,0x88,0x70,0x05, - 0x08,0x08,0x06,0x00,0x00,0x20,0x50,0x00,0x88,0x88,0x88,0x88,0x70,0x05,0x07,0x07, - 0x06,0x00,0x00,0x50,0x00,0x88,0x88,0x88,0x88,0x70,0x05,0x0a,0x0a,0x06,0x00,0xfe, - 0x10,0x20,0x00,0x88,0x88,0x88,0x50,0x20,0x40,0x80,0x05,0x09,0x09,0x06,0x00,0xfe, - 0x80,0x80,0xf0,0x88,0x88,0x88,0xf0,0x80,0x80,0x05,0x09,0x09,0x06,0x00,0xfe,0x50, - 0x00,0x88,0x88,0x88,0x50,0x20,0x40,0x80}; + 0x00,0x88,0x88,0x88,0x88,0x88,0x88,0x70,0x05,0x0a,0x0a,0x06,0x00,0x00,0x20,0x50, + 0x00,0x88,0x88,0x88,0x88,0x88,0x88,0x70,0x05,0x09,0x09,0x06,0x00,0x00,0x50,0x00, + 0x88,0x88,0x88,0x88,0x88,0x88,0x70,0x05,0x0a,0x0a,0x06,0x00,0x00,0x10,0x20,0x00, + 0x88,0x88,0x50,0x20,0x20,0x20,0x20,0x04,0x07,0x07,0x06,0x01,0x00,0x80,0xe0,0x90, + 0x90,0x90,0xe0,0x80,0x05,0x07,0x07,0x06,0x00,0x00,0x70,0x88,0x90,0xa0,0x90,0x88, + 0xb0,0x05,0x08,0x08,0x06,0x00,0x00,0x40,0x20,0x00,0x70,0x08,0x78,0x88,0x78,0x05, + 0x08,0x08,0x06,0x00,0x00,0x10,0x20,0x00,0x70,0x08,0x78,0x88,0x78,0x05,0x08,0x08, + 0x06,0x00,0x00,0x20,0x50,0x00,0x70,0x08,0x78,0x88,0x78,0x05,0x08,0x08,0x06,0x00, + 0x00,0x68,0xb0,0x00,0x70,0x08,0x78,0x88,0x78,0x05,0x07,0x07,0x06,0x00,0x00,0x50, + 0x00,0x70,0x08,0x78,0x88,0x78,0x05,0x08,0x08,0x06,0x00,0x00,0x20,0x50,0x20,0x70, + 0x08,0x78,0x88,0x78,0x05,0x05,0x05,0x06,0x00,0x00,0x70,0x28,0x70,0xa0,0x78,0x05, + 0x07,0x07,0x06,0x00,0xfe,0x70,0x88,0x80,0x88,0x70,0x10,0x60,0x05,0x08,0x08,0x06, + 0x00,0x00,0x40,0x20,0x00,0x70,0x88,0xf0,0x80,0x70,0x05,0x08,0x08,0x06,0x00,0x00, + 0x10,0x20,0x00,0x70,0x88,0xf0,0x80,0x70,0x05,0x08,0x08,0x06,0x00,0x00,0x20,0x50, + 0x00,0x70,0x88,0xf0,0x80,0x70,0x05,0x07,0x07,0x06,0x00,0x00,0x50,0x00,0x70,0x88, + 0xf0,0x80,0x70,0x03,0x08,0x08,0x06,0x01,0x00,0x80,0x40,0x00,0xc0,0x40,0x40,0x40, + 0xe0,0x03,0x08,0x08,0x06,0x01,0x00,0x20,0x40,0x00,0xc0,0x40,0x40,0x40,0xe0,0x03, + 0x08,0x08,0x06,0x01,0x00,0x40,0xa0,0x00,0xc0,0x40,0x40,0x40,0xe0,0x03,0x07,0x07, + 0x06,0x01,0x00,0xa0,0x00,0xc0,0x40,0x40,0x40,0xe0,0x05,0x09,0x09,0x06,0x00,0x00, + 0x50,0x20,0x50,0x08,0x78,0x88,0x88,0x88,0x70,0x05,0x08,0x08,0x06,0x00,0x00,0x68, + 0xb0,0x00,0xb0,0xc8,0x88,0x88,0x88,0x05,0x08,0x08,0x06,0x00,0x00,0x40,0x20,0x00, + 0x70,0x88,0x88,0x88,0x70,0x05,0x08,0x08,0x06,0x00,0x00,0x10,0x20,0x00,0x70,0x88, + 0x88,0x88,0x70,0x05,0x08,0x08,0x06,0x00,0x00,0x20,0x50,0x00,0x70,0x88,0x88,0x88, + 0x70,0x05,0x08,0x08,0x06,0x00,0x00,0x68,0xb0,0x00,0x70,0x88,0x88,0x88,0x70,0x05, + 0x07,0x07,0x06,0x00,0x00,0x50,0x00,0x70,0x88,0x88,0x88,0x70,0x05,0x05,0x05,0x06, + 0x00,0x01,0x20,0x00,0xf8,0x00,0x20,0x05,0x05,0x05,0x06,0x00,0x00,0x78,0x98,0xa8, + 0xc8,0xf0,0x05,0x08,0x08,0x06,0x00,0x00,0x40,0x20,0x00,0x88,0x88,0x88,0x88,0x70, + 0x05,0x08,0x08,0x06,0x00,0x00,0x10,0x20,0x00,0x88,0x88,0x88,0x88,0x70,0x05,0x08, + 0x08,0x06,0x00,0x00,0x20,0x50,0x00,0x88,0x88,0x88,0x88,0x70,0x05,0x07,0x07,0x06, + 0x00,0x00,0x50,0x00,0x88,0x88,0x88,0x88,0x70,0x05,0x0a,0x0a,0x06,0x00,0xfe,0x10, + 0x20,0x00,0x88,0x88,0x88,0x50,0x20,0x40,0x80,0x05,0x09,0x09,0x06,0x00,0xfe,0x80, + 0x80,0xf0,0x88,0x88,0x88,0xf0,0x80,0x80,0x05,0x09,0x09,0x06,0x00,0xfe,0x50,0x00, + 0x88,0x88,0x88,0x50,0x20,0x40,0x80}; #endif diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_ru.h b/Marlin/src/lcd/dogm/fontdata/langdata_ru.h index cd0efda12f..87e3d422a5 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_ru.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_ru.h @@ -5,8 +5,8 @@ */ #include -const u8g_fntpgm_uint8_t fontpage_8_144_152[135] U8G_FONT_SECTION("fontpage_8_144_152") = { - 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x90,0x98,0x00,0x07,0xff,0x00, +const u8g_fntpgm_uint8_t fontpage_8_144_168[348] U8G_FONT_SECTION("fontpage_8_144_168") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x90,0xa8,0x00,0x0a,0xfe,0x00, 0x00,0x05,0x07,0x07,0x06,0x00,0x00,0x70,0x88,0x88,0xf8,0x88,0x88,0x88,0x05,0x07, 0x07,0x06,0x00,0x00,0xf0,0x80,0x80,0xf0,0x88,0x88,0xf0,0x05,0x07,0x07,0x06,0x00, 0x00,0xf0,0x88,0x88,0xf0,0x88,0x88,0xf0,0x05,0x07,0x07,0x06,0x00,0x00,0xf8,0x80, @@ -14,29 +14,27 @@ const u8g_fntpgm_uint8_t fontpage_8_144_152[135] U8G_FONT_SECTION("fontpage_8_14 0x50,0xf8,0x88,0x05,0x07,0x07,0x06,0x00,0x00,0xf8,0x80,0x80,0xf0,0x80,0x80,0xf8, 0x05,0x07,0x07,0x06,0x00,0x00,0xa8,0xa8,0x70,0x20,0x70,0xa8,0xa8,0x05,0x07,0x07, 0x06,0x00,0x00,0x70,0x88,0x08,0x70,0x08,0x88,0x70,0x05,0x07,0x07,0x06,0x00,0x00, - 0x88,0x88,0x98,0xa8,0xc8,0x88,0x88}; -const u8g_fntpgm_uint8_t fontpage_8_154_168[214] U8G_FONT_SECTION("fontpage_8_154_168") = { - 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9a,0xa8,0x00,0x07,0xfe,0x00, - 0x00,0x05,0x07,0x07,0x06,0x00,0x00,0x88,0x90,0xa0,0xc0,0xa0,0x90,0x88,0x05,0x07, - 0x07,0x06,0x00,0x00,0x38,0x48,0x48,0x48,0x48,0x48,0x88,0x05,0x07,0x07,0x06,0x00, - 0x00,0x88,0xd8,0xa8,0x88,0x88,0x88,0x88,0x05,0x07,0x07,0x06,0x00,0x00,0x88,0x88, - 0x88,0xf8,0x88,0x88,0x88,0x05,0x07,0x07,0x06,0x00,0x00,0x70,0x88,0x88,0x88,0x88, - 0x88,0x70,0x05,0x07,0x07,0x06,0x00,0x00,0xf8,0x88,0x88,0x88,0x88,0x88,0x88,0x05, - 0x07,0x07,0x06,0x00,0x00,0xf0,0x88,0x88,0xf0,0x80,0x80,0x80,0x05,0x07,0x07,0x06, - 0x00,0x00,0x70,0x88,0x80,0x80,0x80,0x88,0x70,0x05,0x07,0x07,0x06,0x00,0x00,0xf8, - 0x20,0x20,0x20,0x20,0x20,0x20,0x05,0x07,0x07,0x06,0x00,0x00,0x88,0x88,0x88,0x88, - 0x78,0x08,0x70,0x05,0x07,0x07,0x06,0x00,0x00,0x20,0x70,0xa8,0xa8,0xa8,0x70,0x20, - 0x05,0x07,0x07,0x06,0x00,0x00,0x88,0x88,0x50,0x20,0x50,0x88,0x88,0x05,0x09,0x09, - 0x06,0x00,0xfe,0x90,0x90,0x90,0x90,0x90,0x90,0xf8,0x08,0x08,0x05,0x07,0x07,0x06, - 0x00,0x00,0x88,0x88,0x88,0x78,0x08,0x08,0x08,0x05,0x07,0x07,0x06,0x00,0x00,0xa8, - 0xa8,0xa8,0xa8,0xa8,0xa8,0xf8}; + 0x88,0x88,0x98,0xa8,0xc8,0x88,0x88,0x05,0x0a,0x0a,0x06,0x00,0x00,0x88,0x70,0x00, + 0x88,0x88,0x98,0xa8,0xc8,0x88,0x88,0x05,0x07,0x07,0x06,0x00,0x00,0x88,0x90,0xa0, + 0xc0,0xa0,0x90,0x88,0x05,0x07,0x07,0x06,0x00,0x00,0x38,0x48,0x48,0x48,0x48,0x48, + 0x88,0x05,0x07,0x07,0x06,0x00,0x00,0x88,0xd8,0xa8,0x88,0x88,0x88,0x88,0x05,0x07, + 0x07,0x06,0x00,0x00,0x88,0x88,0x88,0xf8,0x88,0x88,0x88,0x05,0x07,0x07,0x06,0x00, + 0x00,0x70,0x88,0x88,0x88,0x88,0x88,0x70,0x05,0x07,0x07,0x06,0x00,0x00,0xf8,0x88, + 0x88,0x88,0x88,0x88,0x88,0x05,0x07,0x07,0x06,0x00,0x00,0xf0,0x88,0x88,0xf0,0x80, + 0x80,0x80,0x05,0x07,0x07,0x06,0x00,0x00,0x70,0x88,0x80,0x80,0x80,0x88,0x70,0x05, + 0x07,0x07,0x06,0x00,0x00,0xf8,0x20,0x20,0x20,0x20,0x20,0x20,0x05,0x07,0x07,0x06, + 0x00,0x00,0x88,0x88,0x88,0x88,0x78,0x08,0x70,0x05,0x07,0x07,0x06,0x00,0x00,0x20, + 0x70,0xa8,0xa8,0xa8,0x70,0x20,0x05,0x07,0x07,0x06,0x00,0x00,0x88,0x88,0x50,0x20, + 0x50,0x88,0x88,0x05,0x09,0x09,0x06,0x00,0xfe,0x90,0x90,0x90,0x90,0x90,0x90,0xf8, + 0x08,0x08,0x05,0x07,0x07,0x06,0x00,0x00,0x88,0x88,0x88,0x78,0x08,0x08,0x08,0x05, + 0x07,0x07,0x06,0x00,0x00,0xa8,0xa8,0xa8,0xa8,0xa8,0xa8,0xf8}; const u8g_fntpgm_uint8_t fontpage_8_171_173[56] U8G_FONT_SECTION("fontpage_8_171_173") = { 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xab,0xad,0x00,0x07,0x00,0x00, 0x00,0x05,0x07,0x07,0x06,0x00,0x00,0x88,0x88,0x88,0xc8,0xa8,0xa8,0xc8,0x04,0x07, 0x07,0x06,0x01,0x00,0x80,0x80,0x80,0xe0,0x90,0x90,0xe0,0x05,0x07,0x07,0x06,0x00, 0x00,0x70,0x88,0x08,0x78,0x08,0x88,0x70}; -const u8g_fntpgm_uint8_t fontpage_8_175_201[334] U8G_FONT_SECTION("fontpage_8_175_201") = { - 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xaf,0xc9,0x00,0x08,0xfe,0x00, +const u8g_fntpgm_uint8_t fontpage_8_175_207[400] U8G_FONT_SECTION("fontpage_8_175_207") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xaf,0xcf,0x00,0x08,0xfe,0x00, 0x00,0x05,0x07,0x07,0x06,0x00,0x00,0x78,0x88,0x88,0x78,0x28,0x48,0x88,0x05,0x05, 0x05,0x06,0x00,0x00,0x70,0x08,0x78,0x88,0x78,0x05,0x07,0x07,0x06,0x00,0x00,0x70, 0x80,0xf0,0x88,0x88,0x88,0x70,0x05,0x05,0x05,0x06,0x00,0x00,0xf0,0x88,0xf0,0x88, @@ -56,23 +54,20 @@ const u8g_fntpgm_uint8_t fontpage_8_175_201[334] U8G_FONT_SECTION("fontpage_8_17 0x70,0x20,0x20,0x05,0x05,0x05,0x06,0x00,0x00,0x88,0x50,0x20,0x50,0x88,0x05,0x07, 0x07,0x06,0x00,0xfe,0x90,0x90,0x90,0x90,0xf8,0x08,0x08,0x05,0x05,0x05,0x06,0x00, 0x00,0x88,0x88,0x78,0x08,0x08,0x05,0x05,0x05,0x06,0x00,0x00,0xa8,0xa8,0xa8,0xa8, - 0xf8,0x05,0x07,0x07,0x06,0x00,0xfe,0xa8,0xa8,0xa8,0xa8,0xf8,0x08,0x08}; -const u8g_fntpgm_uint8_t fontpage_8_203_207[72] U8G_FONT_SECTION("fontpage_8_203_207") = { - 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcb,0xcf,0x00,0x05,0x00,0x00, - 0x00,0x05,0x05,0x05,0x06,0x00,0x00,0x88,0x88,0xc8,0xa8,0xc8,0x04,0x05,0x05,0x06, - 0x01,0x00,0x80,0x80,0xe0,0x90,0xe0,0x04,0x05,0x05,0x06,0x01,0x00,0xe0,0x10,0x70, - 0x10,0xe0,0x05,0x05,0x05,0x06,0x00,0x00,0x90,0xa8,0xe8,0xa8,0x90,0x04,0x05,0x05, - 0x06,0x01,0x00,0x70,0x90,0x70,0x50,0x90}; + 0xf8,0x05,0x07,0x07,0x06,0x00,0xfe,0xa8,0xa8,0xa8,0xa8,0xf8,0x08,0x08,0x05,0x05, + 0x05,0x06,0x00,0x00,0xc0,0x40,0x70,0x48,0x70,0x05,0x05,0x05,0x06,0x00,0x00,0x88, + 0x88,0xc8,0xa8,0xc8,0x04,0x05,0x05,0x06,0x01,0x00,0x80,0x80,0xe0,0x90,0xe0,0x04, + 0x05,0x05,0x06,0x01,0x00,0xe0,0x10,0x70,0x10,0xe0,0x05,0x05,0x05,0x06,0x00,0x00, + 0x90,0xa8,0xe8,0xa8,0x90,0x04,0x05,0x05,0x06,0x01,0x00,0x70,0x90,0x70,0x50,0x90 + }; const u8g_fntpgm_uint8_t fontpage_8_209_209[30] U8G_FONT_SECTION("fontpage_8_209_209") = { 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd1,0xd1,0x00,0x07,0x00,0x00, 0x00,0x05,0x07,0x07,0x06,0x00,0x00,0x50,0x00,0x70,0x88,0xf0,0x80,0x70}; #define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { - FONTDATA_ITEM(8, 144, 152, fontpage_8_144_152), // 'А' -- 'И' - FONTDATA_ITEM(8, 154, 168, fontpage_8_154_168), // 'К' -- 'Ш' + FONTDATA_ITEM(8, 144, 168, fontpage_8_144_168), // 'А' -- 'Ш' FONTDATA_ITEM(8, 171, 173, fontpage_8_171_173), // 'Ы' -- 'Э' - FONTDATA_ITEM(8, 175, 201, fontpage_8_175_201), // 'Я' -- 'щ' - FONTDATA_ITEM(8, 203, 207, fontpage_8_203_207), // 'ы' -- 'я' + FONTDATA_ITEM(8, 175, 207, fontpage_8_175_207), // 'Я' -- 'я' FONTDATA_ITEM(8, 209, 209, fontpage_8_209_209), // 'ё' -- 'ё' }; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_uk.h b/Marlin/src/lcd/dogm/fontdata/langdata_uk.h index 5d34d1b994..e3800eb6bb 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_uk.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_uk.h @@ -8,60 +8,55 @@ const u8g_fntpgm_uint8_t fontpage_8_134_134[30] U8G_FONT_SECTION("fontpage_8_134_134") = { 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x86,0x86,0x00,0x07,0x00,0x00, 0x00,0x03,0x07,0x07,0x06,0x01,0x00,0xe0,0x40,0x40,0x40,0x40,0x40,0xe0}; -const u8g_fntpgm_uint8_t fontpage_8_144_146[56] U8G_FONT_SECTION("fontpage_8_144_146") = { - 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x90,0x92,0x00,0x07,0x00,0x00, +const u8g_fntpgm_uint8_t fontpage_8_144_169[363] U8G_FONT_SECTION("fontpage_8_144_169") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x90,0xa9,0x00,0x0a,0xfe,0x00, 0x00,0x05,0x07,0x07,0x06,0x00,0x00,0x70,0x88,0x88,0xf8,0x88,0x88,0x88,0x05,0x07, 0x07,0x06,0x00,0x00,0xf0,0x80,0x80,0xf0,0x88,0x88,0xf0,0x05,0x07,0x07,0x06,0x00, - 0x00,0xf0,0x88,0x88,0xf0,0x88,0x88,0xf0}; -const u8g_fntpgm_uint8_t fontpage_8_148_149[44] U8G_FONT_SECTION("fontpage_8_148_149") = { - 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x94,0x95,0x00,0x07,0xff,0x00, - 0x00,0x05,0x08,0x08,0x06,0x00,0xff,0x30,0x50,0x50,0x50,0x50,0x50,0xf8,0x88,0x05, - 0x07,0x07,0x06,0x00,0x00,0xf8,0x80,0x80,0xf0,0x80,0x80,0xf8}; -const u8g_fntpgm_uint8_t fontpage_8_151_154[72] U8G_FONT_SECTION("fontpage_8_151_154") = { - 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x97,0x9a,0x00,0x0a,0x00,0x00, - 0x00,0x05,0x07,0x07,0x06,0x00,0x00,0x70,0x88,0x08,0x70,0x08,0x88,0x70,0x05,0x07, - 0x07,0x06,0x00,0x00,0x88,0x88,0x98,0xa8,0xc8,0x88,0x88,0x05,0x0a,0x0a,0x06,0x00, - 0x00,0x88,0x70,0x00,0x88,0x88,0x98,0xa8,0xc8,0x88,0x88,0x05,0x07,0x07,0x06,0x00, - 0x00,0x88,0x90,0xa0,0xc0,0xa0,0x90,0x88}; -const u8g_fntpgm_uint8_t fontpage_8_156_164[134] U8G_FONT_SECTION("fontpage_8_156_164") = { - 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9c,0xa4,0x00,0x07,0x00,0x00, - 0x00,0x05,0x07,0x07,0x06,0x00,0x00,0x88,0xd8,0xa8,0x88,0x88,0x88,0x88,0x05,0x07, + 0x00,0xf0,0x88,0x88,0xf0,0x88,0x88,0xf0,0x05,0x07,0x07,0x06,0x00,0x00,0xf8,0x80, + 0x80,0x80,0x80,0x80,0x80,0x05,0x08,0x08,0x06,0x00,0xff,0x30,0x50,0x50,0x50,0x50, + 0x50,0xf8,0x88,0x05,0x07,0x07,0x06,0x00,0x00,0xf8,0x80,0x80,0xf0,0x80,0x80,0xf8, + 0x05,0x07,0x07,0x06,0x00,0x00,0xa8,0xa8,0x70,0x20,0x70,0xa8,0xa8,0x05,0x07,0x07, + 0x06,0x00,0x00,0x70,0x88,0x08,0x70,0x08,0x88,0x70,0x05,0x07,0x07,0x06,0x00,0x00, + 0x88,0x88,0x98,0xa8,0xc8,0x88,0x88,0x05,0x0a,0x0a,0x06,0x00,0x00,0x88,0x70,0x00, + 0x88,0x88,0x98,0xa8,0xc8,0x88,0x88,0x05,0x07,0x07,0x06,0x00,0x00,0x88,0x90,0xa0, + 0xc0,0xa0,0x90,0x88,0x05,0x07,0x07,0x06,0x00,0x00,0x38,0x48,0x48,0x48,0x48,0x48, + 0x88,0x05,0x07,0x07,0x06,0x00,0x00,0x88,0xd8,0xa8,0x88,0x88,0x88,0x88,0x05,0x07, 0x07,0x06,0x00,0x00,0x88,0x88,0x88,0xf8,0x88,0x88,0x88,0x05,0x07,0x07,0x06,0x00, 0x00,0x70,0x88,0x88,0x88,0x88,0x88,0x70,0x05,0x07,0x07,0x06,0x00,0x00,0xf8,0x88, 0x88,0x88,0x88,0x88,0x88,0x05,0x07,0x07,0x06,0x00,0x00,0xf0,0x88,0x88,0xf0,0x80, 0x80,0x80,0x05,0x07,0x07,0x06,0x00,0x00,0x70,0x88,0x80,0x80,0x80,0x88,0x70,0x05, 0x07,0x07,0x06,0x00,0x00,0xf8,0x20,0x20,0x20,0x20,0x20,0x20,0x05,0x07,0x07,0x06, 0x00,0x00,0x88,0x88,0x88,0x88,0x78,0x08,0x70,0x05,0x07,0x07,0x06,0x00,0x00,0x20, - 0x70,0xa8,0xa8,0xa8,0x70,0x20}; -const u8g_fntpgm_uint8_t fontpage_8_166_166[32] U8G_FONT_SECTION("fontpage_8_166_166") = { - 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa6,0xa6,0x00,0x07,0xfe,0x00, - 0x00,0x05,0x09,0x09,0x06,0x00,0xfe,0x90,0x90,0x90,0x90,0x90,0x90,0xf8,0x08,0x08 - }; -const u8g_fntpgm_uint8_t fontpage_8_168_168[30] U8G_FONT_SECTION("fontpage_8_168_168") = { - 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xa8,0xa8,0x00,0x07,0x00,0x00, - 0x00,0x05,0x07,0x07,0x06,0x00,0x00,0xa8,0xa8,0xa8,0xa8,0xa8,0xa8,0xf8}; -const u8g_fntpgm_uint8_t fontpage_8_176_201[321] U8G_FONT_SECTION("fontpage_8_176_201") = { - 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb0,0xc9,0x00,0x08,0xfe,0x00, - 0x00,0x05,0x05,0x05,0x06,0x00,0x00,0x70,0x08,0x78,0x88,0x78,0x05,0x07,0x07,0x06, - 0x00,0x00,0x70,0x80,0xf0,0x88,0x88,0x88,0x70,0x05,0x05,0x05,0x06,0x00,0x00,0xf0, - 0x88,0xf0,0x88,0xf0,0x05,0x05,0x05,0x06,0x00,0x00,0xf8,0x80,0x80,0x80,0x80,0x05, - 0x06,0x06,0x06,0x00,0xff,0x30,0x50,0x50,0x50,0xf8,0x88,0x05,0x05,0x05,0x06,0x00, - 0x00,0x70,0x88,0xf0,0x80,0x70,0x05,0x05,0x05,0x06,0x00,0x00,0xa8,0x70,0x20,0x70, - 0xa8,0x05,0x05,0x05,0x06,0x00,0x00,0x70,0x88,0x30,0x88,0x70,0x05,0x05,0x05,0x06, - 0x00,0x00,0x88,0x98,0xa8,0xc8,0x88,0x05,0x08,0x08,0x06,0x00,0x00,0x88,0x70,0x00, - 0x88,0x98,0xa8,0xc8,0x88,0x04,0x05,0x05,0x06,0x01,0x00,0x90,0xa0,0xc0,0xa0,0x90, - 0x05,0x05,0x05,0x06,0x00,0x00,0x38,0x48,0x48,0x48,0x88,0x05,0x05,0x05,0x06,0x00, - 0x00,0x88,0xd8,0xa8,0x88,0x88,0x05,0x05,0x05,0x06,0x00,0x00,0x88,0x88,0xf8,0x88, - 0x88,0x05,0x05,0x05,0x06,0x00,0x00,0x70,0x88,0x88,0x88,0x70,0x05,0x05,0x05,0x06, - 0x00,0x00,0xf8,0x88,0x88,0x88,0x88,0x05,0x07,0x07,0x06,0x00,0xfe,0xf0,0x88,0x88, - 0x88,0xf0,0x80,0x80,0x05,0x05,0x05,0x06,0x00,0x00,0x70,0x88,0x80,0x88,0x70,0x05, - 0x05,0x05,0x06,0x00,0x00,0xf8,0x20,0x20,0x20,0x20,0x05,0x07,0x07,0x06,0x00,0xfe, - 0x88,0x88,0x88,0x88,0x78,0x08,0x70,0x05,0x09,0x09,0x06,0x00,0xfe,0x20,0x20,0x70, - 0xa8,0xa8,0xa8,0x70,0x20,0x20,0x05,0x05,0x05,0x06,0x00,0x00,0x88,0x50,0x20,0x50, - 0x88,0x05,0x07,0x07,0x06,0x00,0xfe,0x90,0x90,0x90,0x90,0xf8,0x08,0x08,0x05,0x05, - 0x05,0x06,0x00,0x00,0x88,0x88,0x78,0x08,0x08,0x05,0x05,0x05,0x06,0x00,0x00,0xa8, - 0xa8,0xa8,0xa8,0xf8,0x05,0x07,0x07,0x06,0x00,0xfe,0xa8,0xa8,0xa8,0xa8,0xf8,0x08, - 0x08}; + 0x70,0xa8,0xa8,0xa8,0x70,0x20,0x05,0x07,0x07,0x06,0x00,0x00,0x88,0x88,0x50,0x20, + 0x50,0x88,0x88,0x05,0x09,0x09,0x06,0x00,0xfe,0x90,0x90,0x90,0x90,0x90,0x90,0xf8, + 0x08,0x08,0x05,0x07,0x07,0x06,0x00,0x00,0x88,0x88,0x88,0x78,0x08,0x08,0x08,0x05, + 0x07,0x07,0x06,0x00,0x00,0xa8,0xa8,0xa8,0xa8,0xa8,0xa8,0xf8,0x05,0x09,0x09,0x06, + 0x00,0xfe,0xa8,0xa8,0xa8,0xa8,0xa8,0xa8,0xf8,0x08,0x08}; +const u8g_fntpgm_uint8_t fontpage_8_172_172[30] U8G_FONT_SECTION("fontpage_8_172_172") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xac,0xac,0x00,0x07,0x00,0x00, + 0x00,0x04,0x07,0x07,0x06,0x01,0x00,0x80,0x80,0x80,0xe0,0x90,0x90,0xe0}; +const u8g_fntpgm_uint8_t fontpage_8_175_201[334] U8G_FONT_SECTION("fontpage_8_175_201") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xaf,0xc9,0x00,0x08,0xfe,0x00, + 0x00,0x05,0x07,0x07,0x06,0x00,0x00,0x78,0x88,0x88,0x78,0x28,0x48,0x88,0x05,0x05, + 0x05,0x06,0x00,0x00,0x70,0x08,0x78,0x88,0x78,0x05,0x07,0x07,0x06,0x00,0x00,0x70, + 0x80,0xf0,0x88,0x88,0x88,0x70,0x05,0x05,0x05,0x06,0x00,0x00,0xf0,0x88,0xf0,0x88, + 0xf0,0x05,0x05,0x05,0x06,0x00,0x00,0xf8,0x80,0x80,0x80,0x80,0x05,0x06,0x06,0x06, + 0x00,0xff,0x30,0x50,0x50,0x50,0xf8,0x88,0x05,0x05,0x05,0x06,0x00,0x00,0x70,0x88, + 0xf0,0x80,0x70,0x05,0x05,0x05,0x06,0x00,0x00,0xa8,0x70,0x20,0x70,0xa8,0x05,0x05, + 0x05,0x06,0x00,0x00,0x70,0x88,0x30,0x88,0x70,0x05,0x05,0x05,0x06,0x00,0x00,0x88, + 0x98,0xa8,0xc8,0x88,0x05,0x08,0x08,0x06,0x00,0x00,0x88,0x70,0x00,0x88,0x98,0xa8, + 0xc8,0x88,0x04,0x05,0x05,0x06,0x01,0x00,0x90,0xa0,0xc0,0xa0,0x90,0x05,0x05,0x05, + 0x06,0x00,0x00,0x38,0x48,0x48,0x48,0x88,0x05,0x05,0x05,0x06,0x00,0x00,0x88,0xd8, + 0xa8,0x88,0x88,0x05,0x05,0x05,0x06,0x00,0x00,0x88,0x88,0xf8,0x88,0x88,0x05,0x05, + 0x05,0x06,0x00,0x00,0x70,0x88,0x88,0x88,0x70,0x05,0x05,0x05,0x06,0x00,0x00,0xf8, + 0x88,0x88,0x88,0x88,0x05,0x07,0x07,0x06,0x00,0xfe,0xf0,0x88,0x88,0x88,0xf0,0x80, + 0x80,0x05,0x05,0x05,0x06,0x00,0x00,0x70,0x88,0x80,0x88,0x70,0x05,0x05,0x05,0x06, + 0x00,0x00,0xf8,0x20,0x20,0x20,0x20,0x05,0x07,0x07,0x06,0x00,0xfe,0x88,0x88,0x88, + 0x88,0x78,0x08,0x70,0x05,0x09,0x09,0x06,0x00,0xfe,0x20,0x20,0x70,0xa8,0xa8,0xa8, + 0x70,0x20,0x20,0x05,0x05,0x05,0x06,0x00,0x00,0x88,0x50,0x20,0x50,0x88,0x05,0x07, + 0x07,0x06,0x00,0xfe,0x90,0x90,0x90,0x90,0xf8,0x08,0x08,0x05,0x05,0x05,0x06,0x00, + 0x00,0x88,0x88,0x78,0x08,0x08,0x05,0x05,0x05,0x06,0x00,0x00,0xa8,0xa8,0xa8,0xa8, + 0xf8,0x05,0x07,0x07,0x06,0x00,0xfe,0xa8,0xa8,0xa8,0xa8,0xf8,0x08,0x08}; const u8g_fntpgm_uint8_t fontpage_8_204_204[28] U8G_FONT_SECTION("fontpage_8_204_204") = { 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcc,0xcc,0x00,0x05,0x00,0x00, 0x00,0x04,0x05,0x05,0x06,0x01,0x00,0x80,0x80,0xe0,0x90,0xe0}; @@ -72,22 +67,19 @@ const u8g_fntpgm_uint8_t fontpage_8_206_207[39] U8G_FONT_SECTION("fontpage_8_206 const u8g_fntpgm_uint8_t fontpage_8_212_212[28] U8G_FONT_SECTION("fontpage_8_212_212") = { 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd4,0xd4,0x00,0x05,0x00,0x00, 0x00,0x04,0x05,0x05,0x06,0x01,0x00,0x70,0x80,0xe0,0x80,0x70}; -const u8g_fntpgm_uint8_t fontpage_8_214_214[29] U8G_FONT_SECTION("fontpage_8_214_214") = { - 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd6,0xd6,0x00,0x06,0x00,0x00, - 0x00,0x03,0x06,0x06,0x06,0x01,0x00,0x40,0x00,0xc0,0x40,0x40,0xe0}; +const u8g_fntpgm_uint8_t fontpage_8_214_215[41] U8G_FONT_SECTION("fontpage_8_214_215") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd6,0xd7,0x00,0x06,0x00,0x00, + 0x00,0x03,0x06,0x06,0x06,0x01,0x00,0x40,0x00,0xc0,0x40,0x40,0xe0,0x03,0x06,0x06, + 0x06,0x01,0x00,0xa0,0x00,0xc0,0x40,0x40,0xe0}; #define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { FONTDATA_ITEM(8, 134, 134, fontpage_8_134_134), // 'І' -- 'І' - FONTDATA_ITEM(8, 144, 146, fontpage_8_144_146), // 'А' -- 'В' - FONTDATA_ITEM(8, 148, 149, fontpage_8_148_149), // 'Д' -- 'Е' - FONTDATA_ITEM(8, 151, 154, fontpage_8_151_154), // 'З' -- 'К' - FONTDATA_ITEM(8, 156, 164, fontpage_8_156_164), // 'М' -- 'Ф' - FONTDATA_ITEM(8, 166, 166, fontpage_8_166_166), // 'Ц' -- 'Ц' - FONTDATA_ITEM(8, 168, 168, fontpage_8_168_168), // 'Ш' -- 'Ш' - FONTDATA_ITEM(8, 176, 201, fontpage_8_176_201), // 'а' -- 'щ' + FONTDATA_ITEM(8, 144, 169, fontpage_8_144_169), // 'А' -- 'Щ' + FONTDATA_ITEM(8, 172, 172, fontpage_8_172_172), // 'Ь' -- 'Ь' + FONTDATA_ITEM(8, 175, 201, fontpage_8_175_201), // 'Я' -- 'щ' FONTDATA_ITEM(8, 204, 204, fontpage_8_204_204), // 'ь' -- 'ь' FONTDATA_ITEM(8, 206, 207, fontpage_8_206_207), // 'ю' -- 'я' FONTDATA_ITEM(8, 212, 212, fontpage_8_212_212), // 'є' -- 'є' - FONTDATA_ITEM(8, 214, 214, fontpage_8_214_214), // 'і' -- 'і' + FONTDATA_ITEM(8, 214, 215, fontpage_8_214_215), // 'і' -- 'ї' }; diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_zh_CN.h b/Marlin/src/lcd/dogm/fontdata/langdata_zh_CN.h index de697cbef4..af39ce5c48 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_zh_CN.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_zh_CN.h @@ -5,6 +5,9 @@ */ #include +const u8g_fntpgm_uint8_t fontpage_64_157_157[26] U8G_FONT_SECTION("fontpage_64_157_157") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x9d,0x9d,0x00,0x07,0x00,0x00, + 0x00,0x05,0x03,0x03,0x06,0x00,0x04,0xd8,0x48,0x90}; const u8g_fntpgm_uint8_t fontpage_69_191_191[28] U8G_FONT_SECTION("fontpage_69_191_191") = { 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xbf,0xbf,0x00,0x05,0x00,0x00, 0x00,0x05,0x05,0x05,0x06,0x00,0x00,0x08,0x18,0x28,0x48,0xf8}; @@ -381,6 +384,10 @@ const u8g_fntpgm_uint8_t fontpage_172_232_232[45] U8G_FONT_SECTION("fontpage_172 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe8,0xe8,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x7b,0xc0,0x4a,0x40,0x4a,0x40,0x7b,0xc0,0x04, 0x80,0xff,0xe0,0x11,0x00,0xfb,0xe0,0x4a,0x40,0x4a,0x40,0x7b,0xc0}; +const u8g_fntpgm_uint8_t fontpage_172_244_244[45] U8G_FONT_SECTION("fontpage_172_244_244") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf4,0xf4,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x01,0x00,0xef,0xe0,0xa5,0x40,0xaf,0xe0,0xa4, + 0x40,0xa7,0xc0,0xe4,0x40,0x07,0xc0,0x04,0x40,0x07,0xc0,0x0c,0x60}; const u8g_fntpgm_uint8_t fontpage_173_222_222[45] U8G_FONT_SECTION("fontpage_173_222_222") = { 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xde,0xde,0x00,0x0a,0xff,0x00, 0x00,0x0a,0x0b,0x16,0x0c,0x01,0xff,0xff,0xc0,0x80,0x40,0x80,0x40,0x9e,0x40,0x92, @@ -941,6 +948,10 @@ const u8g_fntpgm_uint8_t fontpage_221_209_209[45] U8G_FONT_SECTION("fontpage_221 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd1,0xd1,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x47,0xc0,0x24,0x40,0x07,0x40,0x85,0x40,0x5f, 0xe0,0x34,0x60,0x27,0xc0,0xc4,0x40,0x47,0xc0,0x44,0x40,0x44,0xc0}; +const u8g_fntpgm_uint8_t fontpage_222_143_143[45] U8G_FONT_SECTION("fontpage_222_143_143") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0x8f,0x8f,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x4f,0xe0,0x28,0x20,0x0f,0xe0,0x98,0x00,0x5f, + 0xe0,0x29,0x00,0x2f,0xe0,0xcd,0xa0,0x4b,0x60,0x5d,0xa0,0x49,0x60}; const u8g_fntpgm_uint8_t fontpage_223_192_192[45] U8G_FONT_SECTION("fontpage_223_192_192") = { 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc0,0xc0,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x44,0x80,0x3e,0x80,0x12,0xe0,0x9e,0xa0,0x53, @@ -1145,6 +1156,10 @@ const u8g_fntpgm_uint8_t fontpage_259_234_234[34] U8G_FONT_SECTION("fontpage_259 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xea,0xea,0x00,0x0a,0xff,0x00, 0x00,0x07,0x0b,0x0b,0x0c,0x02,0xff,0x20,0xfe,0x82,0x82,0xfe,0x82,0xfe,0x82,0x82, 0xfe,0x82}; +const u8g_fntpgm_uint8_t fontpage_259_243_243[45] U8G_FONT_SECTION("fontpage_259_243_243") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xf3,0xf3,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x7f,0xc0,0x08,0x00,0x11,0x00,0x20,0x80,0x7f, + 0xc0,0x04,0x00,0x04,0x00,0x3f,0x80,0x04,0x00,0x04,0x00,0xff,0xe0}; const u8g_fntpgm_uint8_t fontpage_263_220_220[45] U8G_FONT_SECTION("fontpage_263_220_220") = { 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xdc,0xdc,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x11,0x00,0xff,0xe0,0x11,0x00,0x01,0xc0,0x7e, @@ -1257,6 +1272,10 @@ const u8g_fntpgm_uint8_t fontpage_287_185_185[45] U8G_FONT_SECTION("fontpage_287 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xb9,0xb9,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x41,0x00,0x21,0x00,0x2f,0xe0,0x01,0x20,0xe1, 0x20,0x21,0x20,0x22,0x20,0x24,0x20,0x28,0xc0,0x50,0x00,0x8f,0xe0}; +const u8g_fntpgm_uint8_t fontpage_287_193_193[45] U8G_FONT_SECTION("fontpage_287_193_193") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xc1,0xc1,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x40,0xc0,0x27,0x00,0x21,0x00,0x01,0x00,0xef, + 0xe0,0x21,0x00,0x21,0x00,0x21,0x00,0x21,0x00,0x50,0x00,0x8f,0xe0}; const u8g_fntpgm_uint8_t fontpage_287_208_209[73] U8G_FONT_SECTION("fontpage_287_208_209") = { 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd0,0xd1,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0x47,0xc0,0x20,0x00,0x20,0x00,0x0f,0xe0,0xe2, @@ -1355,6 +1374,10 @@ const u8g_fntpgm_uint8_t fontpage_300_205_205[45] U8G_FONT_SECTION("fontpage_300 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xcd,0xcd,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0xf2,0x00,0x93,0xe0,0xa6,0x40,0xc1,0x80,0xa6, 0x60,0x91,0x00,0x97,0xe0,0xd5,0x00,0xaf,0xe0,0x81,0x00,0x81,0x00}; +const u8g_fntpgm_uint8_t fontpage_300_208_208[45] U8G_FONT_SECTION("fontpage_300_208_208") = { + 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xd0,0xd0,0x00,0x0a,0xff,0x00, + 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0xf7,0xc0,0x94,0x40,0xa7,0xc0,0xc4,0x40,0xa7, + 0xc0,0x95,0x00,0x95,0x20,0xd5,0x40,0xa4,0x80,0x85,0x40,0x86,0x20}; const u8g_fntpgm_uint8_t fontpage_300_228_228[45] U8G_FONT_SECTION("fontpage_300_228_228") = { 0x00,0x0c,0x0f,0x00,0xfe,0x00,0x00,0x00,0x00,0x00,0xe4,0xe4,0x00,0x0a,0xff,0x00, 0x00,0x0b,0x0b,0x16,0x0c,0x00,0xff,0xf1,0x00,0x92,0x80,0xa4,0x40,0xcb,0xa0,0xa1, @@ -1445,6 +1468,7 @@ const u8g_fntpgm_uint8_t fontpage_510_154_154[30] U8G_FONT_SECTION("fontpage_510 #define FONTDATA_ITEM(page, begin, end, data) { page, begin, end, COUNT(data), data } static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { + FONTDATA_ITEM(64, 157, 157, fontpage_64_157_157), // '”' -- '”' FONTDATA_ITEM(69, 191, 191, fontpage_69_191_191), // '⊿' -- '⊿' FONTDATA_ITEM(156, 128, 128, fontpage_156_128_128), // '一' -- '一' FONTDATA_ITEM(156, 137, 139, fontpage_156_137_139), // '三' -- '下' @@ -1533,6 +1557,7 @@ static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { FONTDATA_ITEM(171, 183, 183, fontpage_171_183_183), // '喷' -- '喷' FONTDATA_ITEM(172, 180, 180, fontpage_172_180_180), // '嘴' -- '嘴' FONTDATA_ITEM(172, 232, 232, fontpage_172_232_232), // '器' -- '器' + FONTDATA_ITEM(172, 244, 244, fontpage_172_244_244), // '噴' -- '噴' FONTDATA_ITEM(173, 222, 222, fontpage_173_222_222), // '回' -- '回' FONTDATA_ITEM(173, 224, 224, fontpage_173_224_224), // '因' -- '因' FONTDATA_ITEM(173, 250, 250, fontpage_173_250_250), // '固' -- '固' @@ -1671,6 +1696,7 @@ static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { FONTDATA_ITEM(221, 144, 144, fontpage_221_144_144), // '源' -- '源' FONTDATA_ITEM(221, 162, 162, fontpage_221_162_162), // '溢' -- '溢' FONTDATA_ITEM(221, 209, 209, fontpage_221_209_209), // '滑' -- '滑' + FONTDATA_ITEM(222, 143, 143, fontpage_222_143_143), // '漏' -- '漏' FONTDATA_ITEM(223, 192, 192, fontpage_223_192_192), // '激' -- '激' FONTDATA_ITEM(224, 239, 239, fontpage_224_239_239), // '灯' -- '灯' FONTDATA_ITEM(225, 185, 185, fontpage_225_185_185), // '点' -- '点' @@ -1722,6 +1748,7 @@ static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { FONTDATA_ITEM(256, 234, 234, fontpage_256_234_234), // '聪' -- '聪' FONTDATA_ITEM(257, 253, 253, fontpage_257_253_253), // '能' -- '能' FONTDATA_ITEM(259, 234, 234, fontpage_259_234_234), // '自' -- '自' + FONTDATA_ITEM(259, 243, 243, fontpage_259_243_243), // '至' -- '至' FONTDATA_ITEM(263, 220, 220, fontpage_263_220_220), // '菜' -- '菜' FONTDATA_ITEM(265, 221, 221, fontpage_265_221_221), // '蓝' -- '蓝' FONTDATA_ITEM(269, 199, 199, fontpage_269_199_199), // '蛇' -- '蛇' @@ -1750,6 +1777,7 @@ static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { FONTDATA_ITEM(287, 145, 145, fontpage_287_145_145), // '辑' -- '辑' FONTDATA_ITEM(287, 147, 147, fontpage_287_147_147), // '输' -- '输' FONTDATA_ITEM(287, 185, 185, fontpage_287_185_185), // '边' -- '边' + FONTDATA_ITEM(287, 193, 193, fontpage_287_193_193), // '迁' -- '迁' FONTDATA_ITEM(287, 208, 209, fontpage_287_208_209), // '运' -- '近' FONTDATA_ITEM(287, 212, 212, fontpage_287_212_212), // '返' -- '返' FONTDATA_ITEM(287, 216, 216, fontpage_287_216_216), // '还' -- '还' @@ -1774,6 +1802,7 @@ static const uxg_fontinfo_t g_fontinfo[] PROGMEM = { FONTDATA_ITEM(299, 244, 244, fontpage_299_244_244), // '间' -- '间' FONTDATA_ITEM(300, 136, 136, fontpage_300_136_136), // '阈' -- '阈' FONTDATA_ITEM(300, 205, 205, fontpage_300_205_205), // '降' -- '降' + FONTDATA_ITEM(300, 208, 208, fontpage_300_208_208), // '限' -- '限' FONTDATA_ITEM(300, 228, 228, fontpage_300_228_228), // '除' -- '除' FONTDATA_ITEM(300, 233, 233, fontpage_300_233_233), // '险' -- '险' FONTDATA_ITEM(301, 246, 246, fontpage_301_246_246), // '零' -- '零' diff --git a/Marlin/src/lcd/dogm/lcdprint_u8g.cpp b/Marlin/src/lcd/dogm/lcdprint_u8g.cpp index c9a55a16e3..a6bdb373dd 100644 --- a/Marlin/src/lcd/dogm/lcdprint_u8g.cpp +++ b/Marlin/src/lcd/dogm/lcdprint_u8g.cpp @@ -9,7 +9,7 @@ #include "../../inc/MarlinConfigPre.h" -#if HAS_GRAPHICAL_LCD +#if HAS_MARLINUI_U8GLIB #include "ultralcd_DOGM.h" @@ -53,4 +53,4 @@ int lcd_put_u8str_max_P(PGM_P utf8_str_P, pixel_len_t max_length) { return ret; } -#endif // HAS_GRAPHICAL_LCD +#endif // HAS_MARLINUI_U8GLIB diff --git a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp index bdd9f25703..82b6e768c6 100644 --- a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp +++ b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp @@ -27,7 +27,7 @@ #include "../../inc/MarlinConfigPre.h" -#if HAS_GRAPHICAL_LCD && DISABLED(LIGHTWEIGHT_UI) +#if HAS_MARLINUI_U8GLIB && DISABLED(LIGHTWEIGHT_UI) #include "dogm_Statusscreen.h" #include "ultralcd_DOGM.h" @@ -178,17 +178,17 @@ FORCE_INLINE void _draw_centered_temp(const int16_t temp, const uint8_t tx, cons #if DO_DRAW_HOTENDS // Draw hotend bitmap with current and target temperatures - FORCE_INLINE void _draw_hotend_status(const heater_ind_t heater, const bool blink) { + FORCE_INLINE void _draw_hotend_status(const heater_id_t heater_id, const bool blink) { #if !HEATER_IDLE_HANDLER UNUSED(blink); #endif - const bool isHeat = HOTEND_ALT(heater); + const bool isHeat = HOTEND_ALT(heater_id); - const uint8_t tx = STATUS_HOTEND_TEXT_X(heater); + const uint8_t tx = STATUS_HOTEND_TEXT_X(heater_id); - const float temp = thermalManager.degHotend(heater), - target = thermalManager.degTargetHotend(heater); + const float temp = thermalManager.degHotend(heater_id), + target = thermalManager.degTargetHotend(heater_id); #if DISABLED(STATUS_HOTEND_ANIM) #define STATIC_HOTEND true @@ -237,24 +237,24 @@ FORCE_INLINE void _draw_centered_temp(const int16_t temp, const uint8_t tx, cons #if ANIM_HOTEND // Draw hotend bitmap, either whole or split by the heating percent - const uint8_t hx = STATUS_HOTEND_X(heater), - bw = STATUS_HOTEND_BYTEWIDTH(heater); + const uint8_t hx = STATUS_HOTEND_X(heater_id), + bw = STATUS_HOTEND_BYTEWIDTH(heater_id); #if ENABLED(STATUS_HEAT_PERCENT) if (isHeat && tall <= BAR_TALL) { const uint8_t ph = STATUS_HEATERS_HEIGHT - 1 - tall; - u8g.drawBitmapP(hx, STATUS_HEATERS_Y, bw, ph, HOTEND_BITMAP(heater, false)); - u8g.drawBitmapP(hx, STATUS_HEATERS_Y + ph, bw, tall + 1, HOTEND_BITMAP(heater, true) + ph * bw); + u8g.drawBitmapP(hx, STATUS_HEATERS_Y, bw, ph, HOTEND_BITMAP(heater_id, false)); + u8g.drawBitmapP(hx, STATUS_HEATERS_Y + ph, bw, tall + 1, HOTEND_BITMAP(heater_id, true) + ph * bw); } else #endif - u8g.drawBitmapP(hx, STATUS_HEATERS_Y, bw, STATUS_HEATERS_HEIGHT, HOTEND_BITMAP(heater, isHeat)); + u8g.drawBitmapP(hx, STATUS_HEATERS_Y, bw, STATUS_HEATERS_HEIGHT, HOTEND_BITMAP(heater_id, isHeat)); #endif } // PAGE_CONTAINS if (PAGE_UNDER(7)) { #if HEATER_IDLE_HANDLER - const bool dodraw = (blink || !thermalManager.hotend_idle[heater].timed_out); + const bool dodraw = (blink || !thermalManager.heater_idle[heater_id].timed_out); #else constexpr bool dodraw = true; #endif @@ -327,7 +327,7 @@ FORCE_INLINE void _draw_centered_temp(const int16_t temp, const uint8_t tx, cons if (PAGE_UNDER(7)) { #if HEATER_IDLE_HANDLER - const bool dodraw = (blink || !thermalManager.bed_idle.timed_out); + const bool dodraw = (blink || !thermalManager.heater_idle[thermalManager.IDLE_INDEX_BED].timed_out); #else constexpr bool dodraw = true; #endif @@ -597,7 +597,7 @@ void MarlinUI::draw_status_screen() { // Extruders #if DO_DRAW_HOTENDS LOOP_L_N(e, MAX_HOTEND_DRAW) - _draw_hotend_status((heater_ind_t)e, blink); + _draw_hotend_status((heater_id_t)e, blink); #endif // Laser / Spindle @@ -913,4 +913,4 @@ void MarlinUI::draw_status_message(const bool blink) { #endif } -#endif // HAS_GRAPHICAL_LCD && !LIGHTWEIGHT_UI +#endif // HAS_MARLINUI_U8GLIB && !LIGHTWEIGHT_UI diff --git a/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp b/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp index 211acc86c6..806f370db3 100644 --- a/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp +++ b/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp @@ -11,7 +11,6 @@ * any later version. The code is distributed WITHOUT ANY WARRANTY; * without even the implied warranty of MERCHANTABILITY or FITNESS * FOR A PARTICULAR PURPOSE. See the GNU GPL for more details. - * */ /** diff --git a/Marlin/src/lcd/dogm/status_screen_lite_ST7920.h b/Marlin/src/lcd/dogm/status_screen_lite_ST7920.h index 9f0815d099..b217246484 100644 --- a/Marlin/src/lcd/dogm/status_screen_lite_ST7920.h +++ b/Marlin/src/lcd/dogm/status_screen_lite_ST7920.h @@ -11,7 +11,6 @@ * any later version. The code is distributed WITHOUT ANY WARRANTY; * without even the implied warranty of MERCHANTABILITY or FITNESS * FOR A PARTICULAR PURPOSE. See the GNU GPL for more details. - * */ #pragma once diff --git a/Marlin/src/lcd/dogm/u8g_dev_ssd1306_sh1106_128x64_I2C.cpp b/Marlin/src/lcd/dogm/u8g_dev_ssd1306_sh1106_128x64_I2C.cpp index 70cb7c66d7..f97a323350 100644 --- a/Marlin/src/lcd/dogm/u8g_dev_ssd1306_sh1106_128x64_I2C.cpp +++ b/Marlin/src/lcd/dogm/u8g_dev_ssd1306_sh1106_128x64_I2C.cpp @@ -67,7 +67,7 @@ #include "../../inc/MarlinConfigPre.h" -#if HAS_GRAPHICAL_LCD +#if HAS_MARLINUI_U8GLIB #include "HAL_LCD_com_defines.h" @@ -300,4 +300,4 @@ uint8_t u8g_WriteEscSeqP_2_wire(u8g_t *u8g, u8g_dev_t *dev, const uint8_t *esc_s return 1; } -#endif // HAS_GRAPHICAL_LCD +#endif // HAS_MARLINUI_U8GLIB diff --git a/Marlin/src/lcd/dogm/u8g_dev_st7565_64128n_HAL.cpp b/Marlin/src/lcd/dogm/u8g_dev_st7565_64128n_HAL.cpp index e70b3671b5..84c10dbb4d 100644 --- a/Marlin/src/lcd/dogm/u8g_dev_st7565_64128n_HAL.cpp +++ b/Marlin/src/lcd/dogm/u8g_dev_st7565_64128n_HAL.cpp @@ -55,7 +55,7 @@ #include "../../inc/MarlinConfig.h" -#if HAS_GRAPHICAL_LCD +#if HAS_MARLINUI_U8GLIB #include #include "HAL_LCD_com_defines.h" @@ -233,4 +233,4 @@ u8g_dev_t u8g_dev_st7565_64128n_HAL_2x_sw_spi = { u8g_dev_st7565_64128n_HAL_2x_f U8G_PB_DEV(u8g_dev_st7565_64128n_HAL_hw_spi, WIDTH, HEIGHT, PAGE_HEIGHT, u8g_dev_st7565_64128n_HAL_fn, U8G_COM_HAL_HW_SPI_FN); u8g_dev_t u8g_dev_st7565_64128n_HAL_2x_hw_spi = { u8g_dev_st7565_64128n_HAL_2x_fn, &u8g_dev_st7565_64128n_HAL_2x_pb, U8G_COM_HAL_HW_SPI_FN }; -#endif // HAS_GRAPHICAL_LCD +#endif // HAS_MARLINUI_U8GLIB diff --git a/Marlin/src/lcd/dogm/u8g_dev_st7920_128x64_HAL.cpp b/Marlin/src/lcd/dogm/u8g_dev_st7920_128x64_HAL.cpp index 838bee0ffc..740436d93c 100644 --- a/Marlin/src/lcd/dogm/u8g_dev_st7920_128x64_HAL.cpp +++ b/Marlin/src/lcd/dogm/u8g_dev_st7920_128x64_HAL.cpp @@ -55,7 +55,7 @@ #include "../../inc/MarlinConfigPre.h" -#if HAS_GRAPHICAL_LCD +#if HAS_MARLINUI_U8GLIB #include "HAL_LCD_com_defines.h" @@ -205,4 +205,4 @@ u8g_dev_t u8g_dev_st7920_128x64_HAL_4x_hw_spi = { u8g_dev_st7920_128x64_HAL_4x_f u8g_dev_t u8g_dev_st7920_128x64_rrd_sw_spi = { u8g_dev_st7920_128x64_HAL_4x_fn, &u8g_dev_st7920_128x64_HAL_4x_pb, U8G_COM_ST7920_HAL_SW_SPI }; #endif -#endif // HAS_GRAPHICAL_LCD +#endif // HAS_MARLINUI_U8GLIB diff --git a/Marlin/src/lcd/dogm/u8g_dev_tft_320x240_upscale_from_128x64.cpp b/Marlin/src/lcd/dogm/u8g_dev_tft_320x240_upscale_from_128x64.cpp index 39c294defe..0f53e45a27 100644 --- a/Marlin/src/lcd/dogm/u8g_dev_tft_320x240_upscale_from_128x64.cpp +++ b/Marlin/src/lcd/dogm/u8g_dev_tft_320x240_upscale_from_128x64.cpp @@ -51,12 +51,11 @@ * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF * ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - * */ #include "../../inc/MarlinConfig.h" -#if HAS_GRAPHICAL_LCD && (PIN_EXISTS(FSMC_CS) || ENABLED(SPI_GRAPHICAL_TFT)) +#if HAS_MARLINUI_U8GLIB && (PIN_EXISTS(FSMC_CS) || ENABLED(SPI_GRAPHICAL_TFT)) #include "HAL_LCD_com_defines.h" #include "ultralcd_DOGM.h" @@ -813,4 +812,4 @@ uint8_t u8g_com_hal_tft_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_p U8G_PB_DEV(u8g_dev_tft_320x240_upscale_from_128x64, WIDTH, HEIGHT, PAGE_HEIGHT, u8g_dev_tft_320x240_upscale_from_128x64_fn, U8G_COM_HAL_TFT_FN); -#endif // HAS_GRAPHICAL_LCD && FSMC_CS +#endif // HAS_MARLINUI_U8GLIB && FSMC_CS diff --git a/Marlin/src/lcd/dogm/u8g_dev_uc1701_mini12864_HAL.cpp b/Marlin/src/lcd/dogm/u8g_dev_uc1701_mini12864_HAL.cpp index 85339e8349..172afbd766 100644 --- a/Marlin/src/lcd/dogm/u8g_dev_uc1701_mini12864_HAL.cpp +++ b/Marlin/src/lcd/dogm/u8g_dev_uc1701_mini12864_HAL.cpp @@ -55,7 +55,7 @@ #include "../../inc/MarlinConfigPre.h" -#if HAS_GRAPHICAL_LCD +#if HAS_MARLINUI_U8GLIB #include "HAL_LCD_com_defines.h" @@ -112,6 +112,7 @@ static const uint8_t u8g_dev_uc1701_mini12864_HAL_init_seq[] PROGMEM = { U8G_ESC_CS(1), // enable chip UC1701_ALL_PIX(0), // normal display U8G_ESC_CS(0), // disable chip + U8G_ESC_DLY(150), // delay 150 ms before sending any data U8G_ESC_END // end of sequence }; @@ -209,4 +210,4 @@ u8g_pb_t u8g_dev_uc1701_mini12864_HAL_2x_pb = { {16, HEIGHT, 0, 0, 0}, WIDTH, u u8g_dev_t u8g_dev_uc1701_mini12864_HAL_2x_sw_spi = { u8g_dev_uc1701_mini12864_HAL_2x_fn, &u8g_dev_uc1701_mini12864_HAL_2x_pb, U8G_COM_HAL_SW_SPI_FN }; u8g_dev_t u8g_dev_uc1701_mini12864_HAL_2x_hw_spi = { u8g_dev_uc1701_mini12864_HAL_2x_fn, &u8g_dev_uc1701_mini12864_HAL_2x_pb, U8G_COM_HAL_HW_SPI_FN }; -#endif // HAS_GRAPHICAL_LCD +#endif // HAS_MARLINUI_U8GLIB diff --git a/Marlin/src/lcd/dogm/u8g_fontutf8.cpp b/Marlin/src/lcd/dogm/u8g_fontutf8.cpp index 370b177470..89bdb09e1b 100644 --- a/Marlin/src/lcd/dogm/u8g_fontutf8.cpp +++ b/Marlin/src/lcd/dogm/u8g_fontutf8.cpp @@ -9,7 +9,7 @@ #include "../../inc/MarlinConfigPre.h" -#if HAS_GRAPHICAL_LCD +#if HAS_MARLINUI_U8GLIB #include #include "../fontutils.h" @@ -312,4 +312,4 @@ int uxg_GetUtf8StrPixelWidthP(u8g_t *pu8g, PGM_P utf8_msg) { return data.adv; } -#endif // HAS_GRAPHICAL_LCD +#endif // HAS_MARLINUI_U8GLIB diff --git a/Marlin/src/lcd/dogm/ultralcd_DOGM.cpp b/Marlin/src/lcd/dogm/ultralcd_DOGM.cpp index 7ebabd6950..c48abac810 100644 --- a/Marlin/src/lcd/dogm/ultralcd_DOGM.cpp +++ b/Marlin/src/lcd/dogm/ultralcd_DOGM.cpp @@ -37,7 +37,7 @@ #include "../../inc/MarlinConfigPre.h" -#if HAS_GRAPHICAL_LCD +#if HAS_MARLINUI_U8GLIB #include "ultralcd_DOGM.h" #include "u8g_fontutf8.h" @@ -240,39 +240,35 @@ bool MarlinUI::detected() { return true; } // Initialize or re-initialize the LCD void MarlinUI::init_lcd() { - #if DISABLED(MKS_LCD12864) - - #if PIN_EXISTS(LCD_BACKLIGHT) - OUT_WRITE(LCD_BACKLIGHT_PIN, DISABLED(DELAYED_BACKLIGHT_INIT)); // Illuminate after reset or right away - #endif - - #if ANY(MKS_12864OLED, MKS_12864OLED_SSD1306, FYSETC_242_OLED_12864, ZONESTAR_12864OLED) - SET_OUTPUT(LCD_PINS_DC); - #ifndef LCD_RESET_PIN - #define LCD_RESET_PIN LCD_PINS_RS - #endif + #if PIN_EXISTS(LCD_BACKLIGHT) + OUT_WRITE(LCD_BACKLIGHT_PIN, DISABLED(DELAYED_BACKLIGHT_INIT)); // Illuminate after reset or right away + #endif + + #if ANY(MKS_12864OLED, MKS_12864OLED_SSD1306, FYSETC_242_OLED_12864, ZONESTAR_12864OLED) + SET_OUTPUT(LCD_PINS_DC); + #ifndef LCD_RESET_PIN + #define LCD_RESET_PIN LCD_PINS_RS #endif + #endif - #if PIN_EXISTS(LCD_RESET) - // Perform a clean hardware reset with needed delays - OUT_WRITE(LCD_RESET_PIN, LOW); - _delay_ms(5); - WRITE(LCD_RESET_PIN, HIGH); - _delay_ms(5); - u8g.begin(); - #endif - - #if PIN_EXISTS(LCD_BACKLIGHT) && ENABLED(DELAYED_BACKLIGHT_INIT) - WRITE(LCD_BACKLIGHT_PIN, HIGH); - #endif + #if PIN_EXISTS(LCD_RESET) + // Perform a clean hardware reset with needed delays + OUT_WRITE(LCD_RESET_PIN, LOW); + _delay_ms(5); + WRITE(LCD_RESET_PIN, HIGH); + _delay_ms(5); + u8g.begin(); + #endif - TERN_(HAS_LCD_CONTRAST, refresh_contrast()); + #if PIN_EXISTS(LCD_BACKLIGHT) && ENABLED(DELAYED_BACKLIGHT_INIT) + WRITE(LCD_BACKLIGHT_PIN, HIGH); + #endif - TERN_(LCD_SCREEN_ROT_90, u8g.setRot90()); - TERN_(LCD_SCREEN_ROT_180, u8g.setRot180()); - TERN_(LCD_SCREEN_ROT_270, u8g.setRot270()); + TERN_(HAS_LCD_CONTRAST, refresh_contrast()); - #endif // !MKS_LCD12864 + TERN_(LCD_SCREEN_ROT_90, u8g.setRot90()); + TERN_(LCD_SCREEN_ROT_180, u8g.setRot180()); + TERN_(LCD_SCREEN_ROT_270, u8g.setRot270()); uxg_SetUtf8Fonts(g_fontinfo, COUNT(g_fontinfo)); } @@ -312,7 +308,7 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop lcd_put_u8str(i16tostr3rj(thermalManager.degHotend(extruder))); lcd_put_wchar('/'); - if (get_blink() || !thermalManager.hotend_idle[extruder].timed_out) + if (get_blink() || !thermalManager.heater_idle[extruder].timed_out) lcd_put_u8str(i16tostr3rj(thermalManager.degTargetHotend(extruder))); } @@ -691,4 +687,4 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop #endif // HAS_LCD_MENU -#endif // HAS_GRAPHICAL_LCD +#endif // HAS_MARLINUI_U8GLIB diff --git a/Marlin/src/lcd/dwin/dwin.cpp b/Marlin/src/lcd/dwin/dwin.cpp deleted file mode 100644 index d82efc5689..0000000000 --- a/Marlin/src/lcd/dwin/dwin.cpp +++ /dev/null @@ -1,3567 +0,0 @@ -/** - * Marlin 3D Printer Firmware - * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * - * Based on Sprinter and grbl. - * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - * - */ - -/** - * DWIN by Creality3D - */ - -#include "../../inc/MarlinConfigPre.h" - -#if ENABLED(DWIN_CREALITY_LCD) - -#include "dwin.h" - -#include -#include -#include - -#include "../fontutils.h" -#include "../ultralcd.h" - -#include "../../sd/cardreader.h" - -#include "../../MarlinCore.h" -#include "../../core/serial.h" -#include "../../core/macros.h" -#include "../../gcode/queue.h" - -#include "../../feature/powerloss.h" -#include "../../feature/babystep.h" - -#include "../../module/settings.h" -#include "../../module/temperature.h" -#include "../../module/printcounter.h" -#include "../../module/motion.h" -#include "../../module/planner.h" - -#if ENABLED(HOST_ACTION_COMMANDS) - #include "../../feature/host_actions.h" -#endif - -#if HAS_LEVELING - #include "../../feature/bedlevel/bedlevel.h" -#endif - -#if HAS_BED_PROBE - #include "../../module/probe.h" -#endif - -#ifndef MACHINE_SIZE - #define MACHINE_SIZE "220x220x250" -#endif -#ifndef CORP_WEBSITE_C - #define CORP_WEBSITE_C "www.cxsw3d.com" -#endif -#ifndef CORP_WEBSITE_E - #define CORP_WEBSITE_E "www.creality.com" -#endif - -#define PAUSE_HEAT true - -#define USE_STRING_HEADINGS - -#define MENU_FONT font8x16 -#define STAT_FONT font10x20 -#define HEADER_FONT font10x20 - -#define MENU_CHAR_LIMIT 24 - -// Fan speed limit -#define FANON 255 -#define FANOFF 0 - -// Print speed limit -#define MAX_PRINT_SPEED 999 -#define MIN_PRINT_SPEED 10 - -// Temp limits -#if HAS_HOTEND - #define MAX_E_TEMP (HEATER_0_MAXTEMP - (HOTEND_OVERSHOOT)) - #define MIN_E_TEMP HEATER_0_MINTEMP -#endif - -#if HAS_HEATED_BED - #define MIN_BED_TEMP BED_MINTEMP -#endif - -// Feedspeed limit (max feedspeed = DEFAULT_MAX_FEEDRATE * 2) -#define MIN_MAXFEEDSPEED 1 -#define MIN_MAXACCELERATION 1 -#define MIN_MAXCORNER 0.1 -#define MIN_STEP 1 - -#define FEEDRATE_E (60) - -// Mininum unit (0.1) : multiple (10) -#define MINUNITMULT 10 - -#define ENCODER_WAIT 20 -#define DWIN_SCROLL_UPDATE_INTERVAL 2000 -#define DWIN_REMAIN_TIME_UPDATE_INTERVAL 20000 - -constexpr uint16_t TROWS = 6, MROWS = TROWS - 1, // Total rows, and other-than-Back - TITLE_HEIGHT = 30, // Title bar height - MLINE = 53, // Menu line height - LBLX = 60, // Menu item label X - MENU_CHR_W = 8, STAT_CHR_W = 10; - -#define MBASE(L) (49 + (L)*MLINE) - -#define BABY_Z_VAR TERN(HAS_BED_PROBE, probe.offset.z, zprobe_zoffset) - -/* Value Init */ -HMI_value_t HMI_ValueStruct; -HMI_Flag HMI_flag{0}; - -millis_t Encoder_ms = 0; -millis_t Wait_ms = 0; -millis_t dwin_heat_time = 0; - -int checkkey = 0, last_checkkey = 0; - -typedef struct { - uint8_t now, last; - void set(uint8_t v) { now = last = v; } - void reset() { set(0); } - bool changed() { bool c = (now != last); if (c) last = now; return c; } - bool dec() { if (now) now--; return changed(); } - bool inc(uint8_t v) { if (now < v) now++; else now = v; return changed(); } -} select_t; - -select_t select_page{0}, select_file{0}, select_print{0}, select_prepare{0} - , select_control{0}, select_axis{0}, select_temp{0}, select_motion{0}, select_tune{0} - , select_PLA{0}, select_ABS{0} - , select_speed{0} - , select_acc{0} - , select_corner{0} - , select_step{0} - // , select_leveling{0} - ; - -uint8_t index_file = MROWS, - index_prepare = MROWS, - index_control = MROWS, - index_leveling = MROWS, - index_tune = 5; - -// char filebuf[50]; - -uint8_t countbuf = 0; - -bool recovery_flag = false, abort_flag = false; - -constexpr float default_max_feedrate[] = DEFAULT_MAX_FEEDRATE; -constexpr float default_max_acceleration[] = DEFAULT_MAX_ACCELERATION; -constexpr float default_max_jerk[] = { DEFAULT_XJERK, DEFAULT_YJERK, DEFAULT_ZJERK, DEFAULT_EJERK }; -constexpr float default_axis_steps_per_unit[] = DEFAULT_AXIS_STEPS_PER_UNIT; - -uint8_t Percentrecord = 0; -uint16_t last_Printtime = 0, remain_time = 0; -float last_temp_hotend_target = 0, last_temp_bed_target = 0; -float last_temp_hotend_current = 0, last_temp_bed_current = 0; -uint8_t last_fan_speed = 0; -uint16_t last_speed = 0; -float last_E_scale = 0; -bool DWIN_lcd_sd_status = 0; -bool pause_action_flag = 0; -int temphot = 0, tempbed = 0; -float zprobe_zoffset = 0; -float last_zoffset = 0, last_probe_zoffset = 0; - -#define DWIN_LANGUAGE_EEPROM_ADDRESS 0x01 // Between 0x01 and 0x63 (EEPROM_OFFSET-1) - // BL24CXX::check() uses 0x00 - -void HMI_SetLanguage(void) { - BL24CXX::read(DWIN_LANGUAGE_EEPROM_ADDRESS, (uint8_t*)&HMI_flag.language_chinese, sizeof(HMI_flag.language_chinese)); - if (HMI_flag.language_chinese) - DWIN_JPG_CacheTo1(Language_Chinese); - else - DWIN_JPG_CacheTo1(Language_English); -} - -void HMI_SetAndSaveLanguageWestern(void) { - HMI_flag.language_chinese = false; - DWIN_JPG_CacheTo1(Language_English); - BL24CXX::write(DWIN_LANGUAGE_EEPROM_ADDRESS, (uint8_t*)&HMI_flag.language_chinese, sizeof(HMI_flag.language_chinese)); -} -void HMI_SetAndSaveLanguageChinese(void) { - HMI_flag.language_chinese = true; - DWIN_JPG_CacheTo1(Language_Chinese); - BL24CXX::write(DWIN_LANGUAGE_EEPROM_ADDRESS, (uint8_t*)&HMI_flag.language_chinese, sizeof(HMI_flag.language_chinese)); -} - -void show_plus_or_minus(uint8_t size, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value) { - if (value < 0) { - DWIN_Draw_String(false, true, size, White, bColor, x - 6, y, (char*)"-"); - DWIN_Draw_FloatValue(true, true, 0, size, White, bColor, iNum, fNum, x, y, -value); - } - else { - DWIN_Draw_String(false, true, size, White, bColor, x - 6, y, (char*)" "); - DWIN_Draw_FloatValue(true, true, 0, size, White, bColor, iNum, fNum, x, y, value); - } -} - -void ICON_Print() { - if (select_page.now == 0) { - DWIN_ICON_Show(ICON, ICON_Print_1, 17, 130); - if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 1, 447, 271 - 243, 479 - 19, 58, 201); - else - DWIN_Frame_AreaCopy(1, 1, 451, 271 - 240, 479 - 16, 72 - 15, 201); - } - else { - DWIN_ICON_Show(ICON, ICON_Print_0, 17, 130); - if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 1, 405, 271 - 243, 420, 58, 201); - else - DWIN_Frame_AreaCopy(1, 1, 423, 271 - 240, 423 + 12, 72 - 15, 201); - } -} - -void ICON_Prepare() { - if (select_page.now == 1) { - DWIN_ICON_Show(ICON, ICON_Prepare_1, 145, 130); - if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 31, 447, 271 - 213, 479 - 19, 186, 201); - else - DWIN_Frame_AreaCopy(1, 33, 451, 271 - 189, 479 - 13, 200 - 25, 201); - } - else { - DWIN_ICON_Show(ICON, ICON_Prepare_0, 145, 130); - if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 31, 405, 271 - 213, 420, 186, 201); - else - DWIN_Frame_AreaCopy(1, 33, 423, 271 - 189, 423 + 15, 200 - 25, 201); - } -} - -void ICON_Control() { - if (select_page.now == 2) { - DWIN_ICON_Show(ICON, ICON_Control_1, 17, 246); - if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 61, 447, 271 - 183, 479 - 19, 58, 318); - else - DWIN_Frame_AreaCopy(1, 85, 451, 271 - 139, 479 - 16, 72 - 24, 318); - } - else { - DWIN_ICON_Show(ICON, ICON_Control_0, 17, 246); - if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 61, 405, 271 - 183, 420, 58, 318); - else - DWIN_Frame_AreaCopy(1, 85, 423, 271 - 139, 479 - 45, 72 - 24, 318); - } -} - -void ICON_StartInfo(bool show) { - if (show) { - DWIN_ICON_Show(ICON, ICON_Info_1, 145, 246); - if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 91, 447, 271 - 153, 479 - 19, 186, 318); - else - DWIN_Frame_AreaCopy(1, 132, 451, 159, 479 - 13, 186, 318); - } - else { - DWIN_ICON_Show(ICON, ICON_Info_0, 145, 246); - if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 91, 405, 271 - 153, 420, 186, 318); - else - DWIN_Frame_AreaCopy(1, 132, 423, 159, 423 + 12, 186, 318); - } -} - -void ICON_Leveling(bool show) { - if (show) { - DWIN_ICON_Show(ICON, ICON_Leveling_1, 145, 246); - if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 211, 447, 238, 479 - 19, 186, 318); - else - DWIN_Frame_AreaCopy(1, 84, 437, 120, 449, 200 - 18, 318); - } - else { - DWIN_ICON_Show(ICON, ICON_Leveling_0, 145, 246); - if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 211, 405, 238, 420, 186, 318); - else - DWIN_Frame_AreaCopy(1, 84, 465, 120, 478, 200 - 18, 318); - } -} - -void ICON_Tune() { - if (select_print.now == 0) { - DWIN_ICON_Show(ICON, ICON_Setup_1, 8, 252); - if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 121, 447, 271 - 123, 479 - 21, 34, 325); - else - DWIN_Frame_AreaCopy(1, 1, 465, 271 - 237, 479 - 2, 48 - 17, 325); - } - else { - DWIN_ICON_Show(ICON, ICON_Setup_0, 8, 252); - if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 121, 405, 271 - 123, 420, 34, 325); - else - DWIN_Frame_AreaCopy(1, 1, 438, 271 - 239, 479 - 31, 48 - 17, 325); - } -} - -void ICON_Pause() { - if (select_print.now == 1) { - DWIN_ICON_Show(ICON, ICON_Pause_1, 96, 252); - if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 181, 447, 271 - 63, 479 - 20, 124, 325); - else - DWIN_Frame_AreaCopy(1, 177, 451, 271 - 55, 479 - 17, 136 - 20, 325); - } - else { - DWIN_ICON_Show(ICON, ICON_Pause_0, 96, 252); - if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 181, 405, 271 - 63, 420, 124, 325); - else - DWIN_Frame_AreaCopy(1, 177, 423, 271 - 56, 479 - 46, 136 - 20, 325); - } -} - -void ICON_Continue() { - if (select_print.now == 1) { - DWIN_ICON_Show(ICON, ICON_Continue_1, 96, 252); - if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 1, 447, 271 - 243, 479 - 19, 124, 325); - else - DWIN_Frame_AreaCopy(1, 1, 451, 271 - 239, 479 - 16, 136 - 15, 325); - } - else { - DWIN_ICON_Show(ICON, ICON_Continue_0, 96, 252); - if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 1, 405, 271 - 243, 420, 124, 325); - else - DWIN_Frame_AreaCopy(1, 1, 424, 271 - 240, 479 - 45, 136 - 15, 325); - } -} - -void ICON_Stop() { - if (select_print.now == 2) { - DWIN_ICON_Show(ICON, ICON_Stop_1, 184, 252); - if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 151, 447, 271 - 93, 479 - 20, 210, 325); - else - DWIN_Frame_AreaCopy(1, 218, 451, 271 - 22, 479 - 14, 224 - 15, 325); - } - else { - DWIN_ICON_Show(ICON, ICON_Stop_0, 184, 252); - if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 151, 405, 271 - 93, 420, 210, 325); - else - DWIN_Frame_AreaCopy(1, 218, 423, 271 - 24, 479 - 43, 224 - 15, 325); - } -} - -inline void Clear_Title_Bar(void) { - DWIN_Draw_Rectangle(1, Background_blue, 0, 0, DWIN_WIDTH, 30); -} - -inline void Draw_Title(const char * const title) { - DWIN_Draw_String(false, false, HEADER_FONT, White, Background_blue, 14, 4, (char*)title); -} - -inline void Draw_Title(const __FlashStringHelper * title) { - DWIN_Draw_String(false, false, HEADER_FONT, White, Background_blue, 14, 4, (char*)title); -} - -inline void Clear_Menu_Area(void) { - DWIN_Draw_Rectangle(1, Background_black, 0, 31, 272, 360); -} - -inline void Clear_Main_Window(void) { - Clear_Title_Bar(); - Clear_Menu_Area(); -} - -inline void Clear_Popup_Area(void) { - Clear_Title_Bar(); - DWIN_Draw_Rectangle(1, Background_black, 0, 31, 272, 480); -} - -void Draw_Popup_Bkgd_105(void) { - DWIN_Draw_Rectangle(1, Background_window, 14, 105, 271 - 13, 479 - 105); -} - -inline void Draw_More_Icon(const uint8_t line) { - DWIN_ICON_Show(ICON, ICON_More, 226, 46 + line * MLINE); -} - -inline void Draw_Menu_Cursor(const uint8_t line) { - // DWIN_ICON_Show(ICON,ICON_Rectangle, 0, 31 + line * MLINE); - DWIN_Draw_Rectangle(1, Rectangle_Color, 0, 31 + line * MLINE, 14, 31 + (line + 1) * MLINE - 2); -} - -inline void Erase_Menu_Cursor(const uint8_t line) { - DWIN_Draw_Rectangle(1, Background_black, 0, 31 + line * MLINE, 14, 31 + (line + 1) * MLINE - 2); -} - -inline void Move_Highlight(const int16_t from, const uint16_t newline) { - Erase_Menu_Cursor(newline - from); - Draw_Menu_Cursor(newline); -} - -inline void Add_Menu_Line() { - Move_Highlight(1, MROWS); - DWIN_Draw_Line(Line_Color, 16, 82 + MROWS * MLINE, 256, 83 + MROWS * MLINE); -} - -inline void Scroll_Menu(const uint8_t dir) { - DWIN_Frame_AreaMove(1, dir, MLINE, Background_black, 0, 31, 272, 349); - switch (dir) { - case DWIN_SCROLL_DOWN: Move_Highlight(-1, 0); break; - case DWIN_SCROLL_UP: Add_Menu_Line(); break; - } -} - -inline uint16_t nr_sd_menu_items() { - return card.get_num_Files() + !card.flag.workDirIsRoot; -} - -inline void Draw_Menu_Icon(const uint8_t line, const uint8_t icon) { - DWIN_ICON_Show(ICON, icon, 26, 46 + line * MLINE); -} - -inline void Erase_Menu_Text(const uint8_t line) { - DWIN_Draw_Rectangle(1, Background_black, LBLX, 31 + line * MLINE + 4, 271, 28 + (line + 1) * MLINE - 4); -} - -inline void Draw_Menu_Line(const uint8_t line, const uint8_t icon=0, const char * const label=nullptr) { - if (label) DWIN_Draw_String(false, false, font8x16, White, Background_black, LBLX, 48 + line * MLINE, (char*)label); - if (icon) Draw_Menu_Icon(line, icon); - DWIN_Draw_Line(Line_Color, 16, 29 + (line + 1) * MLINE, 256, 30 + (line + 1) * MLINE); -} - -// The "Back" label is always on the first line -inline void Draw_Back_Label(void) { - if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 129, 72, 271 - 115, 479 - 395, LBLX, MBASE(0)); - else - DWIN_Frame_AreaCopy(1, 226, 179, 271 - 15, 479 - 290, LBLX, MBASE(0)); -} - -// Draw "Back" line at the top -inline void Draw_Back_First(const bool is_sel=true) { - Draw_Menu_Line(0, ICON_Back); - Draw_Back_Label(); - if (is_sel) Draw_Menu_Cursor(0); -} - -// -// Draw Menus -// - -inline void draw_move_en(const uint16_t line) { - DWIN_Frame_AreaCopy(1, 69, 61, 271 - 169, 479 - 408, LBLX, line); // "Move" -} - -inline void Prepare_Item_Move(const uint8_t row) { - if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 159, 70, 271 - 71, 479 - 395, LBLX, MBASE(row)); - else - draw_move_en(MBASE(row)); // "Move >" - Draw_Menu_Line(row, ICON_Axis); - Draw_More_Icon(row); -} - -inline void Prepare_Item_Disable(const uint8_t row) { - if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 204, 70, 271 - 12, 479 - 397, LBLX, MBASE(row)); - else - DWIN_Frame_AreaCopy(1, 103, 59, 271 - 71, 479 - 405, LBLX, MBASE(row)); // "Disable Stepper" - Draw_Menu_Line(row, ICON_CloseMotor); -} - -inline void Prepare_Item_Home(const uint8_t row) { - if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 0, 89, 271 - 230, 479 - 378, LBLX, MBASE(row)); - else - DWIN_Frame_AreaCopy(1, 202, 61, 271 - 0, 479 - 408, LBLX, MBASE(row)); // "Auto Home" - Draw_Menu_Line(row, ICON_Homing); -} - -inline void Prepare_Item_Offset(const uint8_t row) { - if (HMI_flag.language_chinese) { - #if HAS_BED_PROBE - DWIN_Frame_AreaCopy(1, 174, 164, 271 - 48, 479 - 302, LBLX, MBASE(row)); - show_plus_or_minus(font8x16, Background_black, 2, 2, 202, MBASE(row), probe.offset.z * 100); - #else - DWIN_Frame_AreaCopy(1, 43, 89, 271 - 173, 479 - 378, LBLX, MBASE(row)); - #endif - } - else { - #if HAS_BED_PROBE - DWIN_Frame_AreaCopy(1, 93, 179, 271 - 130, 479 - 290, LBLX, MBASE(row)); // "Z-Offset" - show_plus_or_minus(font8x16, Background_black, 2, 2, 202, MBASE(row), probe.offset.z * 100); - #else - DWIN_Frame_AreaCopy(1, 1, 76, 271 - 165, 479 - 393, LBLX, MBASE(row)); // "..." - #endif - } - Draw_Menu_Line(row, ICON_SetHome); -} - -inline void Prepare_Item_PLA(const uint8_t row) { - if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 100, 89, 271 - 93 - 27, 479 - 378, LBLX, MBASE(row)); - } - else { - DWIN_Frame_AreaCopy(1, 107, 76, 271 - 115, 479 - 393, LBLX, MBASE(row)); // "Preheat" - DWIN_Frame_AreaCopy(1, 157, 76, 181, 479 - 393, LBLX + 49 + 3, MBASE(row)); // "PLA" - } - Draw_Menu_Line(row, ICON_PLAPreheat); -} - -inline void Prepare_Item_ABS(const uint8_t row) { - if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 180, 89, 271 - 11 - 27, 479 - 379, LBLX, MBASE(row)); - } - else { - DWIN_Frame_AreaCopy(1, 107, 76, 271 - 115, 479 - 393, LBLX, MBASE(row)); // "Preheat" - DWIN_Frame_AreaCopy(1, 172, 76, 198, 479 - 393, LBLX + 49 + 3, MBASE(row)); // "ABS" - } - Draw_Menu_Line(row, ICON_ABSPreheat); -} - -inline void Prepare_Item_Cool(const uint8_t row) { - if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 1, 104, 271 - 215, 479 - 362, LBLX, MBASE(row)); - else - DWIN_Frame_AreaCopy(1, 200, 76, 271 - 7, 479 - 393, LBLX, MBASE(row));// "Cooldown" - Draw_Menu_Line(row, ICON_Cool); -} - -inline void Prepare_Item_Lang(const uint8_t row) { - if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 239, 134, 271 - 5, 479 - 333, LBLX, MBASE(row)); - DWIN_Draw_String(false, false, font8x16, White, Background_black, 226, MBASE(row), (char*)"CN"); - } - else { - DWIN_Frame_AreaCopy(1, 0, 194, 271 - 150, 479 - 272, LBLX, MBASE(row)); // "Language selection" - DWIN_Draw_String(false, false, font8x16, White, Background_black, 226, MBASE(row), (char*)"EN"); - } - Draw_Menu_Icon(row, ICON_Language); -} - -inline void Draw_Prepare_Menu() { - Clear_Main_Window(); - - const int16_t scroll = MROWS - index_prepare; // Scrolled-up lines - #define PSCROL(L) (scroll + (L)) - #define PVISI(L) WITHIN(PSCROL(L), 0, MROWS) - - if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 133, 1, 271 - 111, 479 - 465 - 1, 14, 8); // "Prepare" - } - else { - #ifdef USE_STRING_HEADINGS - Draw_Title(GET_TEXT_F(MSG_PREPARE)); - #else - DWIN_Frame_AreaCopy(1, 178, 2, 271 - 42, 479 - 464 - 1, 14, 8); // "Prepare" - #endif - } - - if (PVISI(0)) Draw_Back_First(select_prepare.now == 0); // < Back - if (PVISI(1)) Prepare_Item_Move(PSCROL(1)); // Move > - if (PVISI(2)) Prepare_Item_Disable(PSCROL(2)); // Disable Stepper - if (PVISI(3)) Prepare_Item_Home(PSCROL(3)); // Auto Home - if (PVISI(4)) Prepare_Item_Offset(PSCROL(4)); // Z-Offset - if (PVISI(5)) Prepare_Item_PLA(PSCROL(5)); // Preheat PLA - if (PVISI(6)) Prepare_Item_ABS(PSCROL(6)); // Preheat ABS - if (PVISI(7)) Prepare_Item_Cool(PSCROL(7)); // Cooldown - if (PVISI(8)) Prepare_Item_Lang(PSCROL(8)); // Language CN/EN - - if (select_prepare.now) Draw_Menu_Cursor(PSCROL(select_prepare.now)); -} - -inline void Draw_Control_Menu() { - Clear_Main_Window(); - - const int16_t scroll = TERN(HAS_LEVELING, MROWS - index_control, 0); // Scrolled-up lines - - #define CSCROL(L) (scroll + (L)) - #define CLINE(L) MBASE(CSCROL(L)) - #define CVISI(L) WITHIN(CSCROL(L), 0, MROWS) - - if (CVISI(0)) Draw_Back_First(select_control.now == 0); // < Back - - if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 103, 1, 271 - 141, 479 - 465, 14, 8); - DWIN_Frame_AreaCopy(1, 57, 104, 271 - 187, 479 - 363, LBLX, CLINE(1)); // Temperature > - DWIN_Frame_AreaCopy(1, 87, 104, 271 - 157, 479 - 363, LBLX, CLINE(2)); // Motion > - DWIN_Frame_AreaCopy(1, 117, 104, 271 - 99, 479 - 363, LBLX, CLINE(3)); // Store Config - DWIN_Frame_AreaCopy(1, 174, 103, 271 - 42, 479 - 363, LBLX, CLINE(4)); // Read Config - DWIN_Frame_AreaCopy(1, 1, 118, 271 - 215, 479 - 348, LBLX, CLINE(5)); // Reset Config - - if (CVISI(6)) - DWIN_Frame_AreaCopy(1, 231, 104, 271 - 13, 479 - 363, LBLX, CLINE(6)); // Info > - } - else { - #ifdef USE_STRING_HEADINGS - Draw_Title(GET_TEXT_F(MSG_CONTROL)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 0), (char*)GET_TEXT_F(MSG_TEMPERATURE)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 1), (char*)GET_TEXT_F(MSG_MOTION)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 2), (char*)GET_TEXT_F(MSG_STORE_EEPROM)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 3), (char*)GET_TEXT_F(MSG_LOAD_EEPROM)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 4), (char*)GET_TEXT_F(MSG_RESTORE_DEFAULTS)); - if (CVISI(6)) - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 5), (char*)"Info"); - #else - DWIN_Frame_AreaCopy(1, 128, 2, 271 - 95, 479 - 467, 14, 8); - DWIN_Frame_AreaCopy(1, 1, 89, 271 - 188, 479 - 377 - 1, LBLX, CLINE(1));// Temperature > - DWIN_Frame_AreaCopy(1, 84, 89, 271 - 143, 479 - 380, LBLX, CLINE(2));// Motion > - DWIN_Frame_AreaCopy(1, 131 + 17, 89, 271 - 3, 479 - 377 - 1, LBLX, CLINE(3));// "Store Configuration" - DWIN_Frame_AreaCopy(1, 26, 104, 271 - 214, 479 - 365, LBLX, CLINE(4)); // "Read" - DWIN_Frame_AreaCopy(1, 131 + 51, 89, 271 - 3, 479 - 377 - 1, LBLX + 31 + 3, CLINE(4)); // "Configuration" - DWIN_Frame_AreaCopy(1, 59, 104, 271 - 178, 479 - 365, LBLX, CLINE(5)); // "Reset" - DWIN_Frame_AreaCopy(1, 131 + 51, 89, 271 - 3, 479 - 377 - 1, LBLX + 34 + 3, CLINE(5)); // "Configuration" - if (CVISI(6)) - DWIN_Frame_AreaCopy(1, 0, 104, 25, 115, LBLX, CLINE(6)); // Info > - #endif - } - - if (select_control.now && CVISI(select_control.now)) - Draw_Menu_Cursor(CSCROL(select_control.now)); - - // Draw icons and lines - LOOP_L_N(i, 6) - if (CVISI(i + 1)) Draw_Menu_Line(CSCROL(i + 1), ICON_Temperature + i); - - Draw_More_Icon(CSCROL(1)); - Draw_More_Icon(CSCROL(2)); - if (CVISI(6)) Draw_More_Icon(CSCROL(6)); -} - -inline void Draw_Tune_Menu() { - Clear_Main_Window(); - - if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 73, 2, 271 - 171, 479 - 466, 14, 9); - DWIN_Frame_AreaCopy(1, 116, 164, 271 - 100, 479 - 303, LBLX, MBASE(1)); - DWIN_Frame_AreaCopy(1, 1, 134, 271 - 215, 479 - 333, LBLX, MBASE(2)); - DWIN_Frame_AreaCopy(1, 58, 134, 271 - 158, 479 - 333, LBLX, MBASE(3)); - DWIN_Frame_AreaCopy(1, 115, 134, 271 - 101, 479 - 333, LBLX, MBASE(4)); - DWIN_Frame_AreaCopy(1, 174, 164, 271 - 48, 479 - 302, LBLX, MBASE(5)); - } - else { - #ifdef USE_STRING_HEADINGS - Draw_Title(GET_TEXT_F(MSG_TUNE)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 0), (char*)GET_TEXT_F(MSG_SPEED)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 1), (char*)GET_TEXT_F(MSG_UBL_SET_TEMP_HOTEND)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 2), (char*)GET_TEXT_F(MSG_UBL_SET_TEMP_BED)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 3), (char*)GET_TEXT_F(MSG_FAN_SPEED)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 4), (char*)GET_TEXT_F(MSG_ZPROBE_ZOFFSET)); - #else - DWIN_Frame_AreaCopy(1, 94, 2, 271 - 145, 479 - 467, 14, 9); - DWIN_Frame_AreaCopy(1, 1, 179, 271 - 179, 479 - 287 - 2, LBLX, MBASE(1)); // print speed - DWIN_Frame_AreaCopy(1, 197, 104, 271 - 33, 479 - 365, LBLX, MBASE(2)); // Hotend... - DWIN_Frame_AreaCopy(1, 1, 89, 271 - 188, 479 - 377 - 1, LBLX + 41 + 3, MBASE(2)); // ...Temperature - DWIN_Frame_AreaCopy(1, 240, 104, 271 - 7, 479 - 365, LBLX, MBASE(3)); // Bed... - DWIN_Frame_AreaCopy(1, 1, 89, 271 - 188, 479 - 377 - 1, LBLX + 24 + 3, MBASE(3)); // ...Temperature - DWIN_Frame_AreaCopy(1, 0, 119, 271 - 207, 479 - 347, LBLX, MBASE(4)); // fan speed - DWIN_Frame_AreaCopy(1, 93, 179, 271 - 130, 479 - 290, LBLX, MBASE(5)); // Z-offset - #endif - } - - Draw_Back_First(select_tune.now == 0); - if (select_tune.now) Draw_Menu_Cursor(select_tune.now); - - Draw_Menu_Line(1, ICON_Speed); - Draw_Menu_Line(2, ICON_HotendTemp); - Draw_Menu_Line(3, ICON_BedTemp); - Draw_Menu_Line(4, ICON_FanSpeed); - Draw_Menu_Line(5, ICON_Zoffset); - - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(1), feedrate_percentage); - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(2), thermalManager.temp_hotend[0].target); - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(3), thermalManager.temp_bed.target); - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(4), thermalManager.fan_speed[0]); - show_plus_or_minus(font8x16, Background_black, 2, 2, 202, MBASE(5), BABY_Z_VAR * 100); -} - -inline void draw_max_en(const uint16_t line) { - DWIN_Frame_AreaCopy(1, 245, 119, 271 - 2, 479 - 350, LBLX, line); // "Max" -} -inline void draw_max_accel_en(const uint16_t line) { - draw_max_en(line); - DWIN_Frame_AreaCopy(1, 1, 135, 271 - 192, 479 - 334, LBLX + 24 + 3, line); // "Acceleration" -} -inline void draw_speed_en(const uint16_t inset, const uint16_t line) { - DWIN_Frame_AreaCopy(1, 184, 119, 224, 479 - 347, LBLX + inset, line); // "Speed" -} -inline void draw_corner_en(const uint16_t line) { - DWIN_Frame_AreaCopy(1, 64, 119, 271 - 165, 479 - 350, LBLX + 24 + 3, line); // "Corner" -} -inline void draw_steps_per_mm(const uint16_t line) { - DWIN_Frame_AreaCopy(1, 1, 151, 271 - 170, 479 - 318, LBLX, line); // "Steps-per-mm" -} -inline void say_x(const uint16_t inset, const uint16_t line) { - DWIN_Frame_AreaCopy(1, 95, 104, 271 - 169, 479 - 365, LBLX + inset, line); // "X" -} -inline void say_y(const uint16_t inset, const uint16_t line) { - DWIN_Frame_AreaCopy(1, 104, 104, 271 - 161, 479 - 365, LBLX + inset, line); // "Y" -} -inline void say_z(const uint16_t inset, const uint16_t line) { - DWIN_Frame_AreaCopy(1, 112, 104, 271 - 151, 479 - 365, LBLX + inset, line); // "Z" -} -inline void say_e(const uint16_t inset, const uint16_t line) { - DWIN_Frame_AreaCopy(1, 237, 119, 271 - 27, 479 - 350, LBLX + inset, line); // "E" -} - -inline void Draw_Motion_Menu() { - Clear_Main_Window(); - - if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 1, 16, 271 - 243, 479 - 451, 14, 8); - - DWIN_Frame_AreaCopy(1, 173, 133, 228, 479 - 332, LBLX, MBASE(1)); // max speed - DWIN_Frame_AreaCopy(1, 173, 133, 200, 479 - 332, LBLX, MBASE(2)); // max... - DWIN_Frame_AreaCopy(1, 28, 149, 271 - 202, 479 - 318, LBLX + 27, MBASE(2) + 1); // ...acceleration - DWIN_Frame_AreaCopy(1, 173, 133, 200, 479 - 332, LBLX, MBASE(3)); // max... - DWIN_Frame_AreaCopy(1, 1, 180, 271 - 243, 479 - 287, LBLX + 27, MBASE(3) + 1); // ... - DWIN_Frame_AreaCopy(1, 202, 133, 228, 479 - 332, LBLX + 54, MBASE(3)); // ...jerk - DWIN_Frame_AreaCopy(1, 153, 148, 271 - 77, 479 - 318, LBLX, MBASE(4)); // flow ratio - } - else { - #ifdef USE_STRING_HEADINGS - Draw_Title(GET_TEXT_F(MSG_MOTION)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 0), (char*)"Feedrate"); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 1), (char*)GET_TEXT_F(MSG_ACCELERATION)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 2), (char*)GET_TEXT_F(MSG_JERK)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 3), (char*)GET_TEXT_F(MSG_STEPS_PER_MM)); - #else - DWIN_Frame_AreaCopy(1, 144, 16, 271 - 82, 479 - 453, 14, 8); - draw_max_en(MBASE(1)); draw_speed_en(24 + 3, MBASE(1)); // "Max Speed" - draw_max_accel_en(MBASE(2)); // "Max Acceleration" - draw_max_en(MBASE(3)); draw_corner_en(MBASE(3)); // "Max Corner" - draw_steps_per_mm(MBASE(4)); // "Steps-per-mm" - #endif - } - - Draw_Back_First(select_motion.now == 0); - if (select_motion.now) Draw_Menu_Cursor(select_motion.now); - - LOOP_L_N(i, 4) Draw_Menu_Line(i + 1, ICON_MaxSpeed + i); - - Draw_More_Icon(1); - Draw_More_Icon(2); - Draw_More_Icon(3); - Draw_More_Icon(4); -} - -// -// Draw Popup Windows -// - -void Popup_Window_Temperature(const bool toohigh) { - Clear_Popup_Area(); - Draw_Popup_Bkgd_105(); - if (toohigh) { - DWIN_ICON_Show(ICON, ICON_TempTooHigh, 102, 165); - if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 103, 371, 237, 479 - 93, 52, 285); - DWIN_Frame_AreaCopy(1, 151, 389, 185, 402, 187, 285); - DWIN_Frame_AreaCopy(1, 189, 389, 271 - 0, 402, 95, 310); - } - else { - DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, 36, 300, (char*)"Nozzle or Bed temperature"); - DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, 92, 300, (char*)"is too high"); - } - } - else { - DWIN_ICON_Show(ICON, ICON_TempTooLow, 102, 165); - if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 103, 371, 271 - 1, 479 - 93, 52, 285); - DWIN_Frame_AreaCopy(1, 189, 389, 271 - 0, 402, 95, 310); - } - else { - DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, 36, 300, (char*)"Nozzle or Bed temperature"); - DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, 92, 300, (char*)"is too low"); - } - } -} - -inline void Draw_Popup_Bkgd_60() { - DWIN_Draw_Rectangle(1, Background_window, 14, 60, 271 - 13, 330); -} - -#if HAS_HOTEND - - void Popup_Window_ETempTooLow(void) { - Clear_Main_Window(); - Draw_Popup_Bkgd_60(); - DWIN_ICON_Show(ICON, ICON_TempTooLow, 102, 105); - if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 103, 371, 136, 479 - 93, 69, 240); - DWIN_Frame_AreaCopy(1, 170, 371, 271 - 1, 479 - 93, 69 + 33, 240); - DWIN_ICON_Show(ICON, ICON_Confirm_C, 86, 280); - } - else { - DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, 20, 235, (char*)"Nozzle is too cold"); - DWIN_ICON_Show(ICON, ICON_Confirm_E, 86, 280); - } - } - -#endif - -void Popup_Window_Resume(void) { - Clear_Popup_Area(); - Draw_Popup_Bkgd_105(); - if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 160, 338, 271 - 36, 479 - 125, 98, 135); - DWIN_Frame_AreaCopy(1, 103, 321, 271 - 0, 479 - 144, 52, 192); - DWIN_ICON_Show(ICON, ICON_Continue_C, 26, 307); - DWIN_ICON_Show(ICON, ICON_Cancel_C, 146, 307); - } - else { - DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, 120, 115, (char*)"Tips"); - DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, 24, 192, (char*)"I see the file stopped"); - DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, 68, 212, (char*)"unexpectedly last time"); - DWIN_ICON_Show(ICON, ICON_Continue_E, 26, 307); - DWIN_ICON_Show(ICON, ICON_Cancel_E, 146, 307); - } -} - -void Popup_Window_Home(void) { - Clear_Main_Window(); - Draw_Popup_Bkgd_60(); - DWIN_ICON_Show(ICON, ICON_BLTouch, 101, 105); - if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 0, 371, 33, 386, 85, 240); - DWIN_Frame_AreaCopy(1, 203, 286, 271, 302, 118, 240); - DWIN_Frame_AreaCopy(1, 0, 389, 150, 402, 61, 280); - } - else { - DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, 80, 230, (char*)GET_TEXT_F(MSG_LEVEL_BED_HOMING)); - DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, 24, 260, (char*)"Please wait until completed"); - } -} - -void Popup_Window_Leveling(void) { - Clear_Main_Window(); - Draw_Popup_Bkgd_60(); - DWIN_ICON_Show(ICON, ICON_AutoLeveling, 101, 105); - if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 0, 371, 100, 386, 84, 240); - DWIN_Frame_AreaCopy(1, 0, 389, 150, 402, 61, 280); - } - else { - DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, 76, 230, (char*)GET_TEXT_F(MSG_BED_LEVELING)); - DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, 24, 260, (char*)"Please wait until completed"); - } -} - -void Draw_Select_Highlight(const bool sel) { - HMI_flag.select_flag = sel; - const uint16_t c1 = sel ? Select_Color : Background_window, - c2 = sel ? Background_window : Select_Color; - DWIN_Draw_Rectangle(0, c1, 25, 279, 126, 318); - DWIN_Draw_Rectangle(0, c1, 24, 278, 127, 319); - DWIN_Draw_Rectangle(0, c2, 145, 279, 246, 318); - DWIN_Draw_Rectangle(0, c2, 144, 278, 247, 319); -} - -void Popup_window_PauseOrStop(void) { - Clear_Main_Window(); - Draw_Popup_Bkgd_60(); - if (HMI_flag.language_chinese) { - if (select_print.now == 1) DWIN_Frame_AreaCopy(1, 237, 338, 269, 356, 98, 150); - else if (select_print.now == 2) DWIN_Frame_AreaCopy(1, 221, 320, 253, 336, 98, 150); - DWIN_Frame_AreaCopy(1, 220, 304, 264, 319, 130, 150); - DWIN_ICON_Show(ICON, ICON_Confirm_C, 26, 280); - DWIN_ICON_Show(ICON, ICON_Cancel_C, 146, 280); - } - else { - if (select_print.now == 1) DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, 88, 150, (char*)GET_TEXT_F(MSG_PAUSE_PRINT)); - else if (select_print.now == 2) DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, 92, 150, (char*)GET_TEXT_F(MSG_STOP_PRINT)); - DWIN_ICON_Show(ICON, ICON_Confirm_E, 26, 280); - DWIN_ICON_Show(ICON, ICON_Cancel_E, 146, 280); - } - Draw_Select_Highlight(true); -} - -void Draw_Printing_Screen(void) { - if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 30, 1, 271 - 200, 479 - 465, 14, 9);// Tune - DWIN_Frame_AreaCopy(1, 0, 72, 271 - 208, 479 - 393, 41, 188);// Pause - DWIN_Frame_AreaCopy(1, 65, 72, 271 - 143, 479 - 393, 176, 188); // Stop - } - else { - DWIN_Frame_AreaCopy(1, 40, 2, 271 - 179, 479 - 464 - 1, 14, 9);// Tune - DWIN_Frame_AreaCopy(1, 0, 44, 271 - 175, 479 - 420 - 1, 41, 188);// Pause - DWIN_Frame_AreaCopy(1, 98, 44, 271 - 119, 479 - 420 - 1, 176, 188); // Stop - } -} - -void Draw_Print_ProgressBar() { - DWIN_ICON_Show(ICON, ICON_Bar, 15, 93); - DWIN_Draw_Rectangle(1, BarFill_Color, 16 + Percentrecord * 240 / 100, 93, 256, 113); - DWIN_Draw_IntValue(true, true, 0, font8x16, Percent_Color, Background_black, 2, 117, 133, Percentrecord); - DWIN_Draw_String(false, false, font8x16, Percent_Color, Background_black, 117 + 16, 133, (char*)"%"); -} - -void Draw_Print_ProgressElapsed() { - duration_t elapsed = print_job_timer.duration(); // print timer - DWIN_Draw_IntValue(true, true, 1, font8x16, White, Background_black, 2, 42, 212, elapsed.value / 3600); - DWIN_Draw_String(false, false, font8x16, White, Background_black, 42 + 16, 212, (char*)":"); - DWIN_Draw_IntValue(true, true, 1, font8x16, White, Background_black, 2, 42 + 24, 212, (elapsed.value % 3600) / 60); -} - -void Draw_Print_ProgressRemain() { - DWIN_Draw_IntValue(true, true, 1, font8x16, White, Background_black, 2, 176, 212, remain_time / 3600); - DWIN_Draw_String(false, false, font8x16, White, Background_black, 176 + 16, 212, (char*)":"); - DWIN_Draw_IntValue(true, true, 1, font8x16, White, Background_black, 2, 176 + 24, 212, (remain_time % 3600) / 60); -} - -void Goto_PrintProcess(void) { - checkkey = PrintProcess; - - Clear_Main_Window(); - Draw_Printing_Screen(); - - ICON_Tune(); - if (printingIsPaused()) ICON_Continue(); else ICON_Pause(); - ICON_Stop(); - - // Copy into filebuf string before entry - char * const name = card.longest_filename(); - const int8_t npos = _MAX(0, DWIN_WIDTH - strlen(name) * MENU_CHR_W) / 2; - DWIN_Draw_String(false, false, font8x16, White, Background_black, npos, 60, name); - - DWIN_ICON_Show(ICON, ICON_PrintTime, 17, 193); - DWIN_ICON_Show(ICON, ICON_RemainTime, 150, 191); - - Draw_Print_ProgressBar(); - Draw_Print_ProgressElapsed(); - Draw_Print_ProgressRemain(); -} - -void Goto_MainMenu(void) { - checkkey = MainMenu; - - Clear_Main_Window(); - - if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 2, 2, 271 - 244, 479 - 465, 14, 9); // "Home" - } - else { - #ifdef USE_STRING_HEADINGS - Draw_Title(GET_TEXT_F(MSG_MAIN)); - #else - DWIN_Frame_AreaCopy(1, 0, 2, 271 - 232, 479 - 467, 14, 9); - #endif - } - - DWIN_ICON_Show(ICON, ICON_LOGO, 71, 52); - - ICON_Print(); - ICON_Prepare(); - ICON_Control(); - TERN(HAS_LEVELING, ICON_Leveling, ICON_StartInfo)(select_page.now == 3); -} - -inline ENCODER_DiffState get_encoder_state() { - const millis_t ms = millis(); - if (PENDING(ms, Encoder_ms)) return ENCODER_DIFF_NO; - const ENCODER_DiffState state = Encoder_ReceiveAnalyze(); - if (state != ENCODER_DIFF_NO) Encoder_ms = ms + ENCODER_WAIT; - return state; -} - -void HMI_Move_X(void) { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - if (encoder_diffState == ENCODER_DIFF_CW) { - HMI_ValueStruct.Move_X_scale += EncoderRate.encoderMoveValue; - } - else if (encoder_diffState == ENCODER_DIFF_CCW) { - HMI_ValueStruct.Move_X_scale -= EncoderRate.encoderMoveValue; - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { - checkkey = AxisMove; - EncoderRate.encoderRateEnabled = 0; - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 216, MBASE(1), HMI_ValueStruct.Move_X_scale); - if (!planner.is_full()) { - // Wait for planner moves to finish! - planner.synchronize(); - planner.buffer_line(current_position, MMM_TO_MMS(HOMING_FEEDRATE_XY), active_extruder); - } - DWIN_UpdateLCD(); - return; - } - NOLESS(HMI_ValueStruct.Move_X_scale, (X_MIN_POS) * MINUNITMULT); - NOMORE(HMI_ValueStruct.Move_X_scale, (X_MAX_POS) * MINUNITMULT); - current_position[X_AXIS] = HMI_ValueStruct.Move_X_scale / 10; - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 216, MBASE(1), HMI_ValueStruct.Move_X_scale); - DWIN_UpdateLCD(); - } -} - -void HMI_Move_Y(void) { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - if (encoder_diffState == ENCODER_DIFF_CW) { - HMI_ValueStruct.Move_Y_scale += EncoderRate.encoderMoveValue; - } - else if (encoder_diffState == ENCODER_DIFF_CCW) { - HMI_ValueStruct.Move_Y_scale -= EncoderRate.encoderMoveValue; - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { - checkkey = AxisMove; - EncoderRate.encoderRateEnabled = 0; - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 216, MBASE(2), HMI_ValueStruct.Move_Y_scale); - if (!planner.is_full()) { - // Wait for planner moves to finish! - planner.synchronize(); - planner.buffer_line(current_position, MMM_TO_MMS(HOMING_FEEDRATE_XY), active_extruder); - } - DWIN_UpdateLCD(); - return; - } - NOLESS(HMI_ValueStruct.Move_Y_scale, (Y_MIN_POS) * MINUNITMULT); - NOMORE(HMI_ValueStruct.Move_Y_scale, (Y_MAX_POS) * MINUNITMULT); - current_position[Y_AXIS] = HMI_ValueStruct.Move_Y_scale / 10; - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 216, MBASE(2), HMI_ValueStruct.Move_Y_scale); - DWIN_UpdateLCD(); - } -} - -void HMI_Move_Z(void) { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - if (encoder_diffState == ENCODER_DIFF_CW) { - HMI_ValueStruct.Move_Z_scale += EncoderRate.encoderMoveValue; - } - else if (encoder_diffState == ENCODER_DIFF_CCW) { - HMI_ValueStruct.Move_Z_scale -= EncoderRate.encoderMoveValue; - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { - checkkey = AxisMove; - EncoderRate.encoderRateEnabled = 0; - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 216, MBASE(3), HMI_ValueStruct.Move_Z_scale); - if (!planner.is_full()) { - // Wait for planner moves to finish! - planner.synchronize(); - planner.buffer_line(current_position, MMM_TO_MMS(HOMING_FEEDRATE_Z), active_extruder); - } - DWIN_UpdateLCD(); - return; - } - NOLESS(HMI_ValueStruct.Move_Z_scale, Z_MIN_POS * MINUNITMULT); - NOMORE(HMI_ValueStruct.Move_Z_scale, Z_MAX_POS * MINUNITMULT); - current_position[Z_AXIS] = HMI_ValueStruct.Move_Z_scale / 10; - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 216, MBASE(3), HMI_ValueStruct.Move_Z_scale); - DWIN_UpdateLCD(); - } -} - -#if EXTRUDERS - - void HMI_Move_E(void) { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - if (encoder_diffState == ENCODER_DIFF_CW) { - HMI_ValueStruct.Move_E_scale += EncoderRate.encoderMoveValue; - } - else if (encoder_diffState == ENCODER_DIFF_CCW) { - HMI_ValueStruct.Move_E_scale -= EncoderRate.encoderMoveValue; - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { - checkkey = AxisMove; - EncoderRate.encoderRateEnabled = 0; - last_E_scale = HMI_ValueStruct.Move_E_scale; - show_plus_or_minus(font8x16, Background_black, 3, 1, 216, MBASE(4), HMI_ValueStruct.Move_E_scale); - if (!planner.is_full()) { - planner.synchronize(); // Wait for planner moves to finish! - planner.buffer_line(current_position, MMM_TO_MMS(FEEDRATE_E), active_extruder); - } - DWIN_UpdateLCD(); - return; - } - if ((HMI_ValueStruct.Move_E_scale - last_E_scale) > (EXTRUDE_MAXLENGTH) * MINUNITMULT) - HMI_ValueStruct.Move_E_scale = last_E_scale + (EXTRUDE_MAXLENGTH) * MINUNITMULT; - else if ((last_E_scale - HMI_ValueStruct.Move_E_scale) > (EXTRUDE_MAXLENGTH) * MINUNITMULT) - HMI_ValueStruct.Move_E_scale = last_E_scale - (EXTRUDE_MAXLENGTH) * MINUNITMULT; - current_position.e = HMI_ValueStruct.Move_E_scale / 10; - show_plus_or_minus(font8x16, Select_Color, 3, 1, 216, MBASE(4), HMI_ValueStruct.Move_E_scale); - DWIN_UpdateLCD(); - } - } - -#endif - -void HMI_Zoffset(void) { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - last_zoffset = zprobe_zoffset; - if (encoder_diffState == ENCODER_DIFF_CW) { - HMI_ValueStruct.offset_value += EncoderRate.encoderMoveValue; - } - else if (encoder_diffState == ENCODER_DIFF_CCW) { - HMI_ValueStruct.offset_value -= EncoderRate.encoderMoveValue; - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { - EncoderRate.encoderRateEnabled = 0; - zprobe_zoffset = HMI_ValueStruct.offset_value / 100; - #if HAS_BED_PROBE - if (WITHIN(zprobe_zoffset - last_zoffset, Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX)) - probe.offset.z = zprobe_zoffset; - settings.save(); - #elif ENABLED(BABYSTEPPING) - babystep.add_mm(Z_AXIS, (zprobe_zoffset - last_zoffset)); - #else - UNUSED(zprobe_zoffset - last_zoffset); - #endif - - if (HMI_ValueStruct.show_mode == -4) { - checkkey = Prepare; - show_plus_or_minus(font8x16, Background_black, 2, 2, 202, MBASE(4 + MROWS - index_prepare), TERN(HAS_BED_PROBE, probe.offset.z * 100, HMI_ValueStruct.offset_value)); - } - else { - checkkey = Tune; - show_plus_or_minus(font8x16, Background_black, 2, 2, 202, MBASE(5 + MROWS - index_tune), TERN(HAS_BED_PROBE, probe.offset.z * 100, HMI_ValueStruct.offset_value)); - } - DWIN_UpdateLCD(); - return; - } - NOLESS(HMI_ValueStruct.offset_value, (Z_PROBE_OFFSET_RANGE_MIN) * 100); - NOMORE(HMI_ValueStruct.offset_value, (Z_PROBE_OFFSET_RANGE_MAX) * 100); - if (HMI_ValueStruct.show_mode == -4) - show_plus_or_minus(font8x16, Select_Color, 2, 2, 202, MBASE(4 + MROWS - index_prepare), HMI_ValueStruct.offset_value); - else - show_plus_or_minus(font8x16, Select_Color, 2, 2, 202, MBASE(5 + MROWS - index_tune), HMI_ValueStruct.offset_value); - DWIN_UpdateLCD(); - } -} - -#if HAS_HOTEND - - void HMI_ETemp(void) { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - if (encoder_diffState == ENCODER_DIFF_CW) { - HMI_ValueStruct.E_Temp += EncoderRate.encoderMoveValue; - } - else if (encoder_diffState == ENCODER_DIFF_CCW) { - HMI_ValueStruct.E_Temp -= EncoderRate.encoderMoveValue; - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { // return - EncoderRate.encoderRateEnabled = 0; - if (HMI_ValueStruct.show_mode == -1) { // temperature - checkkey = TemperatureID; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(1), HMI_ValueStruct.E_Temp); - } - else if (HMI_ValueStruct.show_mode == -2) { - checkkey = PLAPreheat; - ui.material_preset[0].hotend_temp = HMI_ValueStruct.E_Temp; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(1), ui.material_preset[0].hotend_temp); - return; - } - else if (HMI_ValueStruct.show_mode == -3) { - checkkey = ABSPreheat; - ui.material_preset[1].hotend_temp = HMI_ValueStruct.E_Temp; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(1), ui.material_preset[1].hotend_temp); - return; - } - else { // tune - checkkey = Tune; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(2 + MROWS - index_tune), HMI_ValueStruct.E_Temp); - } - thermalManager.setTargetHotend(HMI_ValueStruct.E_Temp, 0); - return; - } - // E_Temp limit - NOMORE(HMI_ValueStruct.E_Temp, MAX_E_TEMP); - NOLESS(HMI_ValueStruct.E_Temp, MIN_E_TEMP); - // E_Temp value - if (HMI_ValueStruct.show_mode >= 0) // tune - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(2 + MROWS - index_tune), HMI_ValueStruct.E_Temp); - else // other page - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(1), HMI_ValueStruct.E_Temp); - } - } - -#endif // if HAS_HOTEND - -#if HAS_HEATED_BED - - void HMI_BedTemp(void) { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - if (encoder_diffState == ENCODER_DIFF_CW) { - HMI_ValueStruct.Bed_Temp += EncoderRate.encoderMoveValue; - } - else if (encoder_diffState == ENCODER_DIFF_CCW) { - HMI_ValueStruct.Bed_Temp -= EncoderRate.encoderMoveValue; - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { // return - EncoderRate.encoderRateEnabled = 0; - if (HMI_ValueStruct.show_mode == -1) { - checkkey = TemperatureID; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(2), HMI_ValueStruct.Bed_Temp); - } - else if (HMI_ValueStruct.show_mode == -2) { - checkkey = PLAPreheat; - ui.material_preset[0].bed_temp = HMI_ValueStruct.Bed_Temp; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(2), ui.material_preset[0].bed_temp); - return; - } - else if (HMI_ValueStruct.show_mode == -3) { - checkkey = ABSPreheat; - ui.material_preset[1].bed_temp = HMI_ValueStruct.Bed_Temp; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(2), ui.material_preset[1].bed_temp); - return; - } - else { - checkkey = Tune; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(3 + MROWS - index_tune), HMI_ValueStruct.Bed_Temp); - } - thermalManager.setTargetBed(HMI_ValueStruct.Bed_Temp); - return; - } - // Bed_Temp limit - NOMORE(HMI_ValueStruct.Bed_Temp, BED_MAX_TARGET); - NOLESS(HMI_ValueStruct.Bed_Temp, MIN_BED_TEMP); - // Bed_Temp value - if (HMI_ValueStruct.show_mode >= 0) // tune page - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(3 + MROWS - index_tune), HMI_ValueStruct.Bed_Temp); - else // other page - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(2), HMI_ValueStruct.Bed_Temp); - } - } - -#endif // if HAS_HEATED_BED - -#if HAS_FAN - - void HMI_FanSpeed(void) { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - if (encoder_diffState == ENCODER_DIFF_CW) { - HMI_ValueStruct.Fan_speed += EncoderRate.encoderMoveValue; - } - else if (encoder_diffState == ENCODER_DIFF_CCW) { - HMI_ValueStruct.Fan_speed -= EncoderRate.encoderMoveValue; - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { // return - EncoderRate.encoderRateEnabled = 0; - if (HMI_ValueStruct.show_mode == -1) { - checkkey = TemperatureID; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(3), HMI_ValueStruct.Fan_speed); - } - else if (HMI_ValueStruct.show_mode == -2) { - checkkey = PLAPreheat; - ui.material_preset[0].fan_speed = HMI_ValueStruct.Fan_speed; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(3), ui.material_preset[0].fan_speed); - return; - } - else if (HMI_ValueStruct.show_mode == -3) { - checkkey = ABSPreheat; - ui.material_preset[1].fan_speed = HMI_ValueStruct.Fan_speed; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(3), ui.material_preset[1].fan_speed); - return; - } - else { - checkkey = Tune; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(4 + MROWS - index_tune), HMI_ValueStruct.Fan_speed); - } - thermalManager.set_fan_speed(0, HMI_ValueStruct.Fan_speed); - return; - } - // Fan_speed limit - NOMORE(HMI_ValueStruct.Fan_speed, FANON); - NOLESS(HMI_ValueStruct.Fan_speed, FANOFF); - // Fan_speed value - if (HMI_ValueStruct.show_mode >= 0) // tune page - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(4 + MROWS - index_tune), HMI_ValueStruct.Fan_speed); - else // other page - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(3), HMI_ValueStruct.Fan_speed); - } - } - -#endif // if HAS_FAN - -void HMI_PrintSpeed(void) { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - if (encoder_diffState == ENCODER_DIFF_CW) { - HMI_ValueStruct.print_speed += EncoderRate.encoderMoveValue; - } - else if (encoder_diffState == ENCODER_DIFF_CCW) { - HMI_ValueStruct.print_speed -= EncoderRate.encoderMoveValue; - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { // return - checkkey = Tune; - EncoderRate.encoderRateEnabled = 0; - feedrate_percentage = HMI_ValueStruct.print_speed; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(1 + MROWS - index_tune), HMI_ValueStruct.print_speed); - return; - } - // print_speed limit - NOMORE(HMI_ValueStruct.print_speed, MAX_PRINT_SPEED); - NOLESS(HMI_ValueStruct.print_speed, MIN_PRINT_SPEED); - // print_speed value - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(1 + MROWS - index_tune), HMI_ValueStruct.print_speed); - } -} - -void HMI_MaxFeedspeedXYZE(void) { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - if (encoder_diffState == ENCODER_DIFF_CW) { - HMI_ValueStruct.Max_Feedspeed += EncoderRate.encoderMoveValue; - } - else if (encoder_diffState == ENCODER_DIFF_CCW) { - HMI_ValueStruct.Max_Feedspeed -= EncoderRate.encoderMoveValue; - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { // return - checkkey = MaxSpeed; - EncoderRate.encoderRateEnabled = 0; - if (HMI_flag.feedspeed_flag == X_AXIS) planner.set_max_feedrate(X_AXIS, HMI_ValueStruct.Max_Feedspeed); - else if (HMI_flag.feedspeed_flag == Y_AXIS) planner.set_max_feedrate(Y_AXIS, HMI_ValueStruct.Max_Feedspeed); - else if (HMI_flag.feedspeed_flag == Z_AXIS) planner.set_max_feedrate(Z_AXIS, HMI_ValueStruct.Max_Feedspeed); - #if HAS_HOTEND - else if (HMI_flag.feedspeed_flag == E_AXIS) planner.set_max_feedrate(E_AXIS, HMI_ValueStruct.Max_Feedspeed); - #endif - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 4, 210, MBASE(select_speed.now), HMI_ValueStruct.Max_Feedspeed); - return; - } - // MaxFeedspeed limit - if (HMI_flag.feedspeed_flag == X_AXIS) {if (HMI_ValueStruct.Max_Feedspeed > default_max_feedrate[X_AXIS] * 2) HMI_ValueStruct.Max_Feedspeed = default_max_feedrate[X_AXIS] * 2; } - else if (HMI_flag.feedspeed_flag == Y_AXIS) {if (HMI_ValueStruct.Max_Feedspeed > default_max_feedrate[Y_AXIS] * 2) HMI_ValueStruct.Max_Feedspeed = default_max_feedrate[Y_AXIS] * 2; } - else if (HMI_flag.feedspeed_flag == Z_AXIS) {if (HMI_ValueStruct.Max_Feedspeed > default_max_feedrate[Z_AXIS] * 2) HMI_ValueStruct.Max_Feedspeed = default_max_feedrate[Z_AXIS] * 2; } - #if HAS_HOTEND - else if (HMI_flag.feedspeed_flag == E_AXIS) {if (HMI_ValueStruct.Max_Feedspeed > default_max_feedrate[E_AXIS] * 2) HMI_ValueStruct.Max_Feedspeed = default_max_feedrate[E_AXIS] * 2; } - #endif - if (HMI_ValueStruct.Max_Feedspeed < MIN_MAXFEEDSPEED) HMI_ValueStruct.Max_Feedspeed = MIN_MAXFEEDSPEED; - // MaxFeedspeed value - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 4, 210, MBASE(select_speed.now), HMI_ValueStruct.Max_Feedspeed); - } -} - -void HMI_MaxAccelerationXYZE(void) { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - if (encoder_diffState == ENCODER_DIFF_CW) { HMI_ValueStruct.Max_Acceleration += EncoderRate.encoderMoveValue;} - else if (encoder_diffState == ENCODER_DIFF_CCW) { HMI_ValueStruct.Max_Acceleration -= EncoderRate.encoderMoveValue;} - else if (encoder_diffState == ENCODER_DIFF_ENTER) { // return - checkkey = MaxAcceleration; - EncoderRate.encoderRateEnabled = 0; - if (HMI_flag.acc_flag == X_AXIS) planner.set_max_acceleration(X_AXIS, HMI_ValueStruct.Max_Acceleration); - else if (HMI_flag.acc_flag == Y_AXIS) planner.set_max_acceleration(Y_AXIS, HMI_ValueStruct.Max_Acceleration); - else if (HMI_flag.acc_flag == Z_AXIS) planner.set_max_acceleration(Z_AXIS, HMI_ValueStruct.Max_Acceleration); - #if HAS_HOTEND - else if (HMI_flag.acc_flag == E_AXIS) planner.set_max_acceleration(E_AXIS, HMI_ValueStruct.Max_Acceleration); - #endif - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 4, 210, MBASE(select_acc.now), HMI_ValueStruct.Max_Acceleration); - return; - } - // MaxAcceleration limit - if (HMI_flag.acc_flag == X_AXIS) {if (HMI_ValueStruct.Max_Acceleration > default_max_acceleration[X_AXIS] * 2) HMI_ValueStruct.Max_Acceleration = default_max_acceleration[X_AXIS] * 2; } - else if (HMI_flag.acc_flag == Y_AXIS) {if (HMI_ValueStruct.Max_Acceleration > default_max_acceleration[Y_AXIS] * 2) HMI_ValueStruct.Max_Acceleration = default_max_acceleration[Y_AXIS] * 2; } - else if (HMI_flag.acc_flag == Z_AXIS) {if (HMI_ValueStruct.Max_Acceleration > default_max_acceleration[Z_AXIS] * 2) HMI_ValueStruct.Max_Acceleration = default_max_acceleration[Z_AXIS] * 2; } - #if HAS_HOTEND - else if (HMI_flag.acc_flag == E_AXIS) {if (HMI_ValueStruct.Max_Acceleration > default_max_acceleration[E_AXIS] * 2) HMI_ValueStruct.Max_Acceleration = default_max_acceleration[E_AXIS] * 2; } - #endif - if (HMI_ValueStruct.Max_Acceleration < MIN_MAXACCELERATION) HMI_ValueStruct.Max_Acceleration = MIN_MAXACCELERATION; - // MaxAcceleration value - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 4, 210, MBASE(select_acc.now), HMI_ValueStruct.Max_Acceleration); - } -} - -void HMI_MaxCornerXYZE(void) { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - if (encoder_diffState == ENCODER_DIFF_CW) { - HMI_ValueStruct.Max_Corner += EncoderRate.encoderMoveValue; - } - else if (encoder_diffState == ENCODER_DIFF_CCW) { - HMI_ValueStruct.Max_Corner -= EncoderRate.encoderMoveValue; - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { // return - checkkey = MaxCorner; - EncoderRate.encoderRateEnabled = 0; - if (HMI_flag.corner_flag == X_AXIS) planner.set_max_jerk(X_AXIS, HMI_ValueStruct.Max_Corner / 10); - else if (HMI_flag.corner_flag == Y_AXIS) planner.set_max_jerk(Y_AXIS, HMI_ValueStruct.Max_Corner / 10); - else if (HMI_flag.corner_flag == Z_AXIS) planner.set_max_jerk(Z_AXIS, HMI_ValueStruct.Max_Corner / 10); - else if (HMI_flag.corner_flag == E_AXIS) planner.set_max_jerk(E_AXIS, HMI_ValueStruct.Max_Corner / 10); - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 210, MBASE(select_corner.now), HMI_ValueStruct.Max_Corner); - return; - } - // MaxCorner limit - if (HMI_flag.corner_flag == X_AXIS) - NOMORE(HMI_ValueStruct.Max_Corner, default_max_jerk[X_AXIS] * 2 * MINUNITMULT); - else if (HMI_flag.corner_flag == Y_AXIS) - NOMORE(HMI_ValueStruct.Max_Corner, default_max_jerk[Y_AXIS] * 2 * MINUNITMULT); - else if (HMI_flag.corner_flag == Z_AXIS) - NOMORE(HMI_ValueStruct.Max_Corner, default_max_jerk[Z_AXIS] * 2 * MINUNITMULT); - else if (HMI_flag.corner_flag == E_AXIS) - NOMORE(HMI_ValueStruct.Max_Corner, default_max_jerk[E_AXIS] * 2 * MINUNITMULT); - NOLESS(HMI_ValueStruct.Max_Corner, (MIN_MAXCORNER) * MINUNITMULT); - // MaxCorner value - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 210, MBASE(select_corner.now), HMI_ValueStruct.Max_Corner); - } -} - -void HMI_StepXYZE(void) { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - if (encoder_diffState == ENCODER_DIFF_CW) { - HMI_ValueStruct.Max_Step += EncoderRate.encoderMoveValue; - } - else if (encoder_diffState == ENCODER_DIFF_CCW) { - HMI_ValueStruct.Max_Step -= EncoderRate.encoderMoveValue; - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { // return - checkkey = Step; - EncoderRate.encoderRateEnabled = 0; - if (HMI_flag.step_flag == X_AXIS) planner.settings.axis_steps_per_mm[X_AXIS] = HMI_ValueStruct.Max_Step / 10; - else if (HMI_flag.step_flag == Y_AXIS) planner.settings.axis_steps_per_mm[Y_AXIS] = HMI_ValueStruct.Max_Step / 10; - else if (HMI_flag.step_flag == Z_AXIS) planner.settings.axis_steps_per_mm[Z_AXIS] = HMI_ValueStruct.Max_Step / 10; - else if (HMI_flag.step_flag == E_AXIS) planner.settings.axis_steps_per_mm[E_AXIS] = HMI_ValueStruct.Max_Step / 10; - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 210, MBASE(select_step.now), HMI_ValueStruct.Max_Step); - return; - } - // Step limit - if (HMI_flag.step_flag == X_AXIS) - NOMORE(HMI_ValueStruct.Max_Step, default_axis_steps_per_unit[X_AXIS] * 2 * MINUNITMULT); - else if (HMI_flag.step_flag == Y_AXIS) - NOMORE(HMI_ValueStruct.Max_Step, default_axis_steps_per_unit[Y_AXIS] * 2 * MINUNITMULT); - else if (HMI_flag.step_flag == Z_AXIS) - NOMORE(HMI_ValueStruct.Max_Step, default_axis_steps_per_unit[Z_AXIS] * 2 * MINUNITMULT); - else if (HMI_flag.step_flag == E_AXIS) - NOMORE(HMI_ValueStruct.Max_Step, default_axis_steps_per_unit[E_AXIS] * 2 * MINUNITMULT); - NOLESS(HMI_ValueStruct.Max_Step, MIN_STEP); - // Step value - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 210, MBASE(select_step.now), HMI_ValueStruct.Max_Step); - } -} - -void update_variable(void) { - /* Tune page temperature update */ - if (checkkey == Tune) { - if (last_temp_hotend_target != thermalManager.temp_hotend[0].target) - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(2 + MROWS - index_tune), thermalManager.temp_hotend[0].target); - if (last_temp_bed_target != thermalManager.temp_bed.target) - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(3 + MROWS - index_tune), thermalManager.temp_bed.target); - if (last_fan_speed != thermalManager.fan_speed[0]) { - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(4 + MROWS - index_tune), thermalManager.fan_speed[0]); - last_fan_speed = thermalManager.fan_speed[0]; - } - } - - /* Temperature page temperature update */ - if (checkkey == TemperatureID) { - if (last_temp_hotend_target != thermalManager.temp_hotend[0].target) - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(1), thermalManager.temp_hotend[0].target); - if (last_temp_bed_target != thermalManager.temp_bed.target) - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(2), thermalManager.temp_bed.target); - if (last_fan_speed != thermalManager.fan_speed[0]) { - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(3), thermalManager.fan_speed[0]); - last_fan_speed = thermalManager.fan_speed[0]; - } - } - - /* Bottom temperature update */ - if (last_temp_hotend_current != thermalManager.temp_hotend[0].celsius) { - DWIN_Draw_IntValue(true, true, 0, STAT_FONT, White, Background_black, 3, 33, 382, thermalManager.temp_hotend[0].celsius); - last_temp_hotend_current = thermalManager.temp_hotend[0].celsius; - } - if (last_temp_hotend_target != thermalManager.temp_hotend[0].target) { - DWIN_Draw_IntValue(true, true, 0, STAT_FONT, White, Background_black, 3, 33 + 4 * STAT_CHR_W + 6, 382, thermalManager.temp_hotend[0].target); - last_temp_hotend_target = thermalManager.temp_hotend[0].target; - } - if (last_temp_bed_current != thermalManager.temp_bed.celsius) { - DWIN_Draw_IntValue(true, true, 0, STAT_FONT, White, Background_black, 3, 178, 382, thermalManager.temp_bed.celsius); - last_temp_bed_current = thermalManager.temp_bed.celsius; - } - if (last_temp_bed_target != thermalManager.temp_bed.target) { - DWIN_Draw_IntValue(true, true, 0, STAT_FONT, White, Background_black, 3, 178 + 4 * STAT_CHR_W + 6, 382, thermalManager.temp_bed.target); - last_temp_bed_target = thermalManager.temp_bed.target; - } - if (last_speed != feedrate_percentage) { - DWIN_Draw_IntValue(true, true, 0, STAT_FONT, White, Background_black, 3, 33 + 2 * STAT_CHR_W, 429, feedrate_percentage); - last_speed = feedrate_percentage; - } - #if HAS_BED_PROBE - if (last_probe_zoffset != probe.offset.z) { - show_plus_or_minus(STAT_FONT, Background_black, 2, 2, 178 + STAT_CHR_W, 429, probe.offset.z * 100); - last_probe_zoffset = probe.offset.z; - } - #else - if (last_zoffset != zprobe_zoffset) { - show_plus_or_minus(STAT_FONT, Background_black, 2, 2, 178 + STAT_CHR_W, 429, zprobe_zoffset * 100); - last_zoffset = zprobe_zoffset; - } - #endif -} - -/** -* Read and cache the working directory. -* -* TODO: New code can follow the pattern of menu_media.cpp -* and rely on Marlin caching for performance. No need to -* cache files here. -* -*/ - -#ifndef strcasecmp_P - #define strcasecmp_P(a, b) strcasecmp((a), (b)) -#endif - -inline void make_name_without_ext(char *dst, char *src, int maxlen=MENU_CHAR_LIMIT) { - char * const name = card.longest_filename(); - size_t pos = strlen(name); // index of ending nul - - // For files, remove the extension - // which may be .gcode, .gco, or .g - if (!card.flag.filenameIsDir) - while (pos && src[pos] != '.') pos--; // find last '.' (stop at 0) - - size_t len = pos; // nul or '.' - if (len > maxlen) { // Keep the name short - pos = len = maxlen; // move nul down - dst[--pos] = '.'; // insert dots - dst[--pos] = '.'; - dst[--pos] = '.'; - } - - dst[len] = '\0'; // end it - - // Copy down to 0 - while (pos--) dst[pos] = src[pos]; -} - -inline void HMI_SDCardInit(void) { card.cdroot(); } - -void MarlinUI::refresh() { - // The card was mounted or unmounted - // or some other status change occurred - // DWIN_lcd_sd_status = false; // On next DWIN_Update - // HMI_SDCardUpdate(); -} - -#define ICON_Folder ICON_More - -char shift_name[LONG_FILENAME_LENGTH + 1]; -int8_t shift_amt; // = 0 -millis_t shift_ms; // = 0 - -// Init the shift name based on the highlighted item -inline void Init_Shift_Name() { - const bool is_subdir = !card.flag.workDirIsRoot; - const int8_t filenum = select_file.now - 1 - is_subdir; // Skip "Back" and ".." - const uint16_t fileCnt = card.get_num_Files(); - if (WITHIN(filenum, 0, fileCnt - 1)) { - card.getfilename_sorted(SD_ORDER(filenum, fileCnt)); - char * const name = card.longest_filename(); - make_name_without_ext(shift_name, name, 100); - } -} - -inline void Init_SDItem_Shift() { - shift_amt = 0; - shift_ms = select_file.now > 0 && strlen(shift_name) > MENU_CHAR_LIMIT - ? millis() + 750UL : 0; -} - -/** - * Display an SD item, adding a CDUP for subfolders. - */ -inline void Draw_SDItem(const uint16_t item, int16_t row=-1) { - if (row < 0) row = item + 1 + MROWS - index_file; - const bool is_subdir = !card.flag.workDirIsRoot; - if (is_subdir && item == 0) { - Draw_Menu_Line(row, ICON_Folder, (char*)".."); - return; - } - - card.getfilename_sorted(item - is_subdir); - char * const name = card.longest_filename(); - - // Init the current selected name - // This is used during scroll drawing - if (item == select_file.now - 1) { - make_name_without_ext(shift_name, name, 100); - Init_SDItem_Shift(); - } - - char str[strlen(name) + 1]; - - make_name_without_ext(str, name); - - Draw_Menu_Line(row, card.flag.filenameIsDir ? ICON_Folder : ICON_File, str); -} - -inline void Draw_SDItem_Shifted(int8_t &shift) { - // Limit to the number of chars past the cutoff - const size_t len = strlen(shift_name); - NOMORE(shift, _MAX((signed)len - MENU_CHAR_LIMIT, 0)); - - // Shorten to the available space - const size_t lastchar = _MIN((signed)len, shift + MENU_CHAR_LIMIT); - - const char c = shift_name[lastchar]; - shift_name[lastchar] = '\0'; - - const uint8_t row = select_file.now + MROWS - index_file; // skip "Back" and scroll - Erase_Menu_Text(row); - Draw_Menu_Line(row, 0, &shift_name[shift]); - - shift_name[lastchar] = c; -} - -// Redraw the first set of SD Files -inline void Redraw_SD_List() { - select_file.reset(); - index_file = MROWS; - - Clear_Menu_Area(); // Leave title bar unchanged - - Draw_Back_First(); - - // As many files as will fit - LOOP_L_N(i, _MIN(nr_sd_menu_items(), MROWS)) - Draw_SDItem(i, i + 1); - - Init_SDItem_Shift(); -} - -inline void SDCard_Up(void) { - card.cdup(); - Redraw_SD_List(); - DWIN_lcd_sd_status = false; // On next DWIN_Update -} - -inline void SDCard_Folder(char * const dirname) { - card.cd(dirname); - Redraw_SD_List(); - DWIN_lcd_sd_status = false; // On next DWIN_Update -} - -// -// Watch for media mount / unmount -// -void HMI_SDCardUpdate(void) { - if (HMI_flag.home_flag) return; - if (DWIN_lcd_sd_status != card.isMounted()) { - DWIN_lcd_sd_status = card.isMounted(); - // SERIAL_ECHOLNPAIR("HMI_SDCardUpdate: ", int(DWIN_lcd_sd_status)); - if (card.isMounted()) { - if (checkkey == SelectFile) - Redraw_SD_List(); - } - else { - // clean file icon - if (checkkey == SelectFile) { - Redraw_SD_List(); - } - else if (checkkey == PrintProcess || checkkey == Tune || printingIsActive()) { - // TODO: Move card removed abort handling - // to CardReader::manage_media. - card.flag.abort_sd_printing = true; - wait_for_heatup = false; - abort_flag = true; - } - } - DWIN_UpdateLCD(); - } -} - -/* Start */ -void HMI_StartFrame(const bool with_update) { - Goto_MainMenu(); - - DWIN_Draw_Rectangle(1, Background_black, 0, 360, 272, 479); - - DWIN_ICON_Show(ICON, ICON_HotendTemp, 13, 381); - #if HOTENDS > 1 - // DWIN_ICON_Show(ICON,ICON_HotendTemp, 13, 381); - #endif - DWIN_ICON_Show(ICON, ICON_BedTemp, 158, 381); - DWIN_ICON_Show(ICON, ICON_Speed, 13, 429); - DWIN_ICON_Show(ICON, ICON_Zoffset, 158, 428); - - // Draw initial Status Area - DWIN_Draw_IntValue(true, true, 0, STAT_FONT, White, Background_black, 3, 33, 382, thermalManager.temp_hotend[0].celsius); - DWIN_Draw_IntValue(true, true, 0, STAT_FONT, White, Background_black, 3, 33 + 4 * STAT_CHR_W + 6, 382, thermalManager.temp_hotend[0].target); - DWIN_Draw_IntValue(true, true, 0, STAT_FONT, White, Background_black, 3, 178, 382, thermalManager.temp_bed.celsius); - DWIN_Draw_IntValue(true, true, 0, STAT_FONT, White, Background_black, 3, 178 + 4 * STAT_CHR_W + 6, 382, thermalManager.temp_bed.target); - - DWIN_Draw_IntValue(true, true, 0, STAT_FONT, White, Background_black, 3, 33 + 2 * STAT_CHR_W, 429, feedrate_percentage); - DWIN_Draw_String(false, false, STAT_FONT, White, Background_black, 33 + (2 + 3) * STAT_CHR_W + 2, 429, (char*)"%"); - - show_plus_or_minus(STAT_FONT, Background_black, 2, 2, 178, 429, BABY_Z_VAR * 100); - DWIN_Draw_String(false, false, STAT_FONT, White, Background_black, 33 + 3 * STAT_CHR_W + 5, 383, (char*)"/"); - DWIN_Draw_String(false, false, STAT_FONT, White, Background_black, 178 + 3 * STAT_CHR_W + 5, 383, (char*)"/"); - - if (with_update) { - DWIN_UpdateLCD(); - delay(5); - } -} - -inline void Draw_Info_Menu() { - Clear_Main_Window(); - - DWIN_Draw_String(false, false, font8x16, White, Background_black, (DWIN_WIDTH - strlen(MACHINE_SIZE) * MENU_CHR_W) / 2, 122, (char*)MACHINE_SIZE); - DWIN_Draw_String(false, false, font8x16, White, Background_black, (DWIN_WIDTH - strlen(SHORT_BUILD_VERSION) * MENU_CHR_W) / 2, 195, (char*)SHORT_BUILD_VERSION); - - if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 30, 17, 271 - 214, 479 - 450, 14, 8); - - DWIN_Frame_AreaCopy(1, 197, 149, 271 - 19, 479 - 318, 108, 102); - DWIN_Frame_AreaCopy(1, 1, 164, 271 - 215, 479 - 303, 108, 175); - DWIN_Frame_AreaCopy(1, 58, 164, 271 - 158, 479 - 303, 105, 248); - DWIN_Draw_String(false, false, font8x16, White, Background_black, (DWIN_WIDTH - strlen(CORP_WEBSITE_C) * MENU_CHR_W) / 2, 268, (char*)CORP_WEBSITE_C); - } - else { - #ifdef USE_STRING_HEADINGS - Draw_Title(GET_TEXT_F(MSG_INFO_SCREEN)); - #else - DWIN_Frame_AreaCopy(1, 190, 16, 271 - 56, 479 - 453, 14, 8); - #endif - - DWIN_Frame_AreaCopy(1, 120, 150, 146, 479 - 318, 124, 102); - DWIN_Frame_AreaCopy(1, 146, 151, 271 - 17, 479 - 318, 82, 175); - DWIN_Frame_AreaCopy(1, 0, 165, 271 - 177, 479 - 304, 89, 248); - DWIN_Draw_String(false, false, font8x16, White, Background_black, (DWIN_WIDTH - strlen(CORP_WEBSITE_E) * MENU_CHR_W) / 2, 268, (char*)CORP_WEBSITE_E); - } - - Draw_Back_First(); - LOOP_L_N(i, 3) { - DWIN_ICON_Show(ICON, ICON_PrintSize + i, 26, 99 + i * 73); - DWIN_Draw_Line(Line_Color, 16, MBASE(2) + i * 73, 256, 156 + i * 73); - } -} - -inline void Draw_Print_File_Menu() { - Clear_Title_Bar(); - - if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 0, 31, 271 - 216, 479 - 435, 14, 8); - } - else { - #ifdef USE_STRING_HEADINGS - Draw_Title("Print file"); // TODO: GET_TEXT_F - #else - DWIN_Frame_AreaCopy(1, 52, 31, 271 - 134, 479 - 438, 14, 8); // "Print file" - #endif - } - - Redraw_SD_List(); -} - -/* Main Process */ -void HMI_MainMenu(void) { - ENCODER_DiffState encoder_diffState = get_encoder_state(); - if (encoder_diffState == ENCODER_DIFF_NO) return; - - if (encoder_diffState == ENCODER_DIFF_CW) { - if (select_page.inc(3)) { - switch (select_page.now) { - case 0: ICON_Print(); break; - case 1: ICON_Print(); ICON_Prepare(); break; - case 2: ICON_Prepare(); ICON_Control(); break; - case 3: ICON_Control(); TERN(HAS_LEVELING, ICON_Leveling, ICON_StartInfo)(1); break; - } - } - } - else if (encoder_diffState == ENCODER_DIFF_CCW) { - if (select_page.dec()) { - switch (select_page.now) { - case 0: ICON_Print(); ICON_Prepare(); break; - case 1: ICON_Prepare(); ICON_Control(); break; - case 2: ICON_Control(); TERN(HAS_LEVELING, ICON_Leveling, ICON_StartInfo)(0); break; - case 3: TERN(HAS_LEVELING, ICON_Leveling, ICON_StartInfo)(1); break; - } - } - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { - switch (select_page.now) { - /* Print File */ - case 0: - checkkey = SelectFile; - Draw_Print_File_Menu(); - break; - - /* Prepare */ - case 1: - checkkey = Prepare; - select_prepare.reset(); - index_prepare = MROWS; - Draw_Prepare_Menu(); - break; - - /* Control */ - case 2: - checkkey = Control; - select_control.reset(); - index_control = MROWS; - Draw_Control_Menu(); - break; - - /* Leveling */ - case 3: - #if HAS_LEVELING - checkkey = Leveling; - HMI_Leveling(); - #else - checkkey = Info; - Draw_Info_Menu(); - #endif - break; - } - } - DWIN_UpdateLCD(); -} - -/* Select (and Print) File */ -void HMI_SelectFile(void) { - ENCODER_DiffState encoder_diffState = get_encoder_state(); - - const uint16_t hasUpDir = !card.flag.workDirIsRoot; - - if (encoder_diffState == ENCODER_DIFF_NO) { - if (shift_ms && select_file.now >= 1 + hasUpDir) { - // Scroll selected filename every second - const millis_t ms = millis(); - if (ELAPSED(ms, shift_ms)) { - const bool was_reset = shift_amt < 0; - shift_ms = ms + 375UL + was_reset * 250UL; // ms per character - int8_t shift_new = shift_amt + 1; // Try to shift by... - Draw_SDItem_Shifted(shift_new); // Draw the item - if (!was_reset && shift_new == 0) // Was it limited to 0? - shift_ms = 0; // No scrolling needed - else if (shift_new == shift_amt) // Scroll reached the end - shift_new = -1; // Reset - shift_amt = shift_new; // Set new scroll - } - } - return; - } - - // First pause is long. Easy. - // On reset, long pause must be after 0. - - const uint16_t fullCnt = nr_sd_menu_items(); - - if (encoder_diffState == ENCODER_DIFF_CW && fullCnt) { - if (select_file.inc(fullCnt)) { - const uint8_t itemnum = select_file.now - 1; // -1 for "Back" - if (shift_ms) { // If line was shifted - Erase_Menu_Text(select_file.now - 1 + MROWS - index_file); // Erase and - Draw_SDItem(itemnum - 1); // redraw - } - if (select_file.now > MROWS && select_file.now > index_file) { // Cursor past the bottom - index_file = select_file.now; // New bottom line - Scroll_Menu(DWIN_SCROLL_UP); - Draw_SDItem(itemnum, MROWS); // Draw and init the shift name - } - else { - Move_Highlight(1, select_file.now + MROWS - index_file); // Just move highlight - Init_Shift_Name(); // ...and init the shift name - } - Init_SDItem_Shift(); - } - } - else if (encoder_diffState == ENCODER_DIFF_CCW && fullCnt) { - if (select_file.dec()) { - const uint8_t itemnum = select_file.now - 1; // -1 for "Back" - if (shift_ms) { // If line was shifted - Erase_Menu_Text(select_file.now + 1 + MROWS - index_file); // Erase and - Draw_SDItem(itemnum + 1); // redraw - } - if (select_file.now < index_file - MROWS) { // Cursor past the top - index_file--; // New bottom line - Scroll_Menu(DWIN_SCROLL_DOWN); - if (index_file == MROWS) { - Draw_Back_First(); - shift_ms = 0; - } - else { - Draw_SDItem(itemnum, 0); // Draw the item (and init shift name) - } - } - else { - Move_Highlight(-1, select_file.now + MROWS - index_file); // Just move highlight - Init_Shift_Name(); // ...and init the shift name - } - Init_SDItem_Shift(); // Reset left. Init timer. - } - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { - if (select_file.now == 0) { - /* back */ - select_page.set(0); - Goto_MainMenu(); - } - else if (hasUpDir && select_file.now == 1) { - /* CDUP */ - SDCard_Up(); - goto HMI_SelectFileExit; - } - else { - const uint16_t filenum = select_file.now - 1 - hasUpDir; - card.getfilename_sorted(SD_ORDER(filenum, card.get_num_Files())); - - // Enter that folder! - if (card.flag.filenameIsDir) { - SDCard_Folder(card.filename); - goto HMI_SelectFileExit; - } - - // Reset highlight for next entry - select_print.reset(); - select_file.reset(); - - // Start choice and print SD file - HMI_flag.heat_flag = 1; - HMI_flag.print_finish = 0; - HMI_ValueStruct.show_mode = 0; - - card.openAndPrintFile(card.filename); - - #if FAN_COUNT > 0 - // All fans on for Ender 3 v2 ? - // The slicer should manage this for us. - // for (uint8_t i = 0; i < FAN_COUNT; i++) - // thermalManager.fan_speed[i] = FANON; - #endif - - Goto_PrintProcess(); - } - } -HMI_SelectFileExit: - DWIN_UpdateLCD(); -} - -/* Printing */ -void HMI_Printing(void) { - ENCODER_DiffState encoder_diffState = get_encoder_state(); - if (encoder_diffState == ENCODER_DIFF_NO) return; - - if (HMI_flag.confirm_flag) { - if (encoder_diffState == ENCODER_DIFF_ENTER) { - HMI_flag.confirm_flag = 0; - abort_flag = 1; - } - return; - } - - // Avoid flicker by updating only the previous menu - if (encoder_diffState == ENCODER_DIFF_CW) { - if (select_print.inc(2)) { - switch (select_print.now) { - case 0: ICON_Tune(); break; - case 1: - ICON_Tune(); - if (printingIsPaused()) ICON_Continue(); else ICON_Pause(); - break; - case 2: - if (printingIsPaused()) ICON_Continue(); else ICON_Pause(); - ICON_Stop(); - break; - } - } - } - else if (encoder_diffState == ENCODER_DIFF_CCW) { - if (select_print.dec()) { - switch (select_print.now) { - case 0: - ICON_Tune(); - if (printingIsPaused()) ICON_Continue(); else ICON_Pause(); - break; - case 1: - if (printingIsPaused()) ICON_Continue(); else ICON_Pause(); - ICON_Stop(); - break; - case 2: ICON_Stop(); break; - } - } - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { - switch (select_print.now) { - case 0: // setting - checkkey = Tune; - HMI_ValueStruct.show_mode = 0; - select_tune.reset(); - index_tune = 5; - Draw_Tune_Menu(); - break; - case 1: // pause - /* pause */ - if (HMI_flag.pause_flag) { - ICON_Pause(); - - char cmd[40]; - cmd[0] = '\0'; - - #if ENABLED(PAUSE_HEAT) - if (tempbed) sprintf_P(cmd, PSTR("M190 S%i\n"), tempbed); - if (temphot) sprintf_P(&cmd[strlen(cmd)], PSTR("M109 S%i\n"), temphot); - #endif - - strcat_P(cmd, PSTR("M24")); - queue.inject(cmd); - } - else { - HMI_flag.select_flag = 1; - checkkey = Print_window; - Popup_window_PauseOrStop(); - } - break; - - case 2: // stop - /* stop */ - HMI_flag.select_flag = 1; - checkkey = Print_window; - Popup_window_PauseOrStop(); - break; - - default: - break; - } - } - DWIN_UpdateLCD(); -} - -/* pause and stop window */ -void HMI_PauseOrStop(void) { - ENCODER_DiffState encoder_diffState = get_encoder_state(); - if (encoder_diffState == ENCODER_DIFF_NO) return; - - if (encoder_diffState == ENCODER_DIFF_CW) { - Draw_Select_Highlight(false); - } - else if (encoder_diffState == ENCODER_DIFF_CCW) { - Draw_Select_Highlight(true); - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { - if (select_print.now == 1) { // pause window - if (HMI_flag.select_flag) { - pause_action_flag = 1; - ICON_Continue(); - #if ENABLED(POWER_LOSS_RECOVERY) - if (recovery.enabled) recovery.save(true); - #endif - queue.inject_P(PSTR("M25")); - } - else { - // cancel pause - } - Goto_PrintProcess(); - } - else if (select_print.now == 2) { // stop window - if (HMI_flag.select_flag) { - wait_for_heatup = false; // Stop waiting for heater - - #if 0 - // TODO: In ExtUI or MarlinUI add a common stop event - // card.flag.abort_sd_printing = true; - #else - checkkey = Back_Main; - // Wait for planner moves to finish! - if (HMI_flag.home_flag) planner.synchronize(); - card.endFilePrint(); - #ifdef ACTION_ON_CANCEL - host_action_cancel(); - #endif - #ifdef EVENT_GCODE_SD_ABORT - Popup_Window_Home(); - queue.inject_P(PSTR(EVENT_GCODE_SD_ABORT)); - #endif - abort_flag = true; - #endif - } - else { - Goto_PrintProcess(); // cancel stop - } - } - } - DWIN_UpdateLCD(); -} - -inline void Draw_Move_Menu() { - Clear_Main_Window(); - - if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 192, 1, 271 - 38, 479 - 465, 14, 8); - DWIN_Frame_AreaCopy(1, 58, 118, 271 - 165, 479 - 347, LBLX, MBASE(1)); - DWIN_Frame_AreaCopy(1, 109, 118, 271 - 114, 479 - 347, LBLX, MBASE(2)); - DWIN_Frame_AreaCopy(1, 160, 118, 271 - 62, 479 - 347, LBLX, MBASE(3)); - #if HAS_HOTEND - DWIN_Frame_AreaCopy(1, 212, 118, 271 - 18, 479 - 348, LBLX, MBASE(4)); - #endif - } - else { - #ifdef USE_STRING_HEADINGS - Draw_Title(GET_TEXT_F(MSG_MOVE_AXIS)); - #else - DWIN_Frame_AreaCopy(1, 231, 2, 271 - 6, 479 - 467, 14, 8); - #endif - draw_move_en(MBASE(1)); say_x(33 + 3, MBASE(1)); // "Move X" - draw_move_en(MBASE(2)); say_y(33 + 3, MBASE(2)); // "Move Y" - draw_move_en(MBASE(3)); say_z(33 + 3, MBASE(3)); // "Move Z" - #if HAS_HOTEND - DWIN_Frame_AreaCopy(1, 123, 192, 271 - 95, 479 - 277, LBLX, MBASE(4)); // "Extruder" - #endif - } - - Draw_Back_First(select_axis.now == 0); - if (select_axis.now) Draw_Menu_Cursor(select_axis.now); - - LOOP_L_N(i, MROWS) Draw_Menu_Line(i + 1, ICON_MoveX + i); -} - -#include "../../libs/buzzer.h" - -void HMI_AudioFeedback(const bool success=true) { - if (success) { - buzzer.tone(100, 659); - buzzer.tone(10, 0); - buzzer.tone(100, 698); - } - else - buzzer.tone(40, 440); -} - -/* Prepare */ -void HMI_Prepare(void) { - ENCODER_DiffState encoder_diffState = get_encoder_state(); - if (encoder_diffState == ENCODER_DIFF_NO) return; - - // Avoid flicker by updating only the previous menu - if (encoder_diffState == ENCODER_DIFF_CW) { - if (select_prepare.inc(8)) { - if (select_prepare.now > MROWS && select_prepare.now > index_prepare) { - index_prepare = select_prepare.now; - - // Scroll up and draw a blank bottom line - Scroll_Menu(DWIN_SCROLL_UP); - Draw_Menu_Icon(MROWS, ICON_Axis + select_prepare.now - 1); - - // Draw "More" icon for sub-menus - if (index_prepare < 7) Draw_More_Icon(MROWS - index_prepare + 1); - - if (index_prepare == 6) Prepare_Item_ABS(MROWS); - else if (index_prepare == 7) Prepare_Item_Cool(MROWS); - else if (index_prepare == 8) Prepare_Item_Lang(MROWS); - } - else { - Move_Highlight(1, select_prepare.now + MROWS - index_prepare); - } - } - } - else if (encoder_diffState == ENCODER_DIFF_CCW) { - if (select_prepare.dec()) { - if (select_prepare.now < index_prepare - MROWS) { - index_prepare--; - Scroll_Menu(DWIN_SCROLL_DOWN); - - if (index_prepare == MROWS) - Draw_Back_First(); - else - Draw_Menu_Line(0, ICON_Axis + select_prepare.now - 1); - - if (index_prepare < 7) Draw_More_Icon(MROWS - index_prepare + 1); - - if (index_prepare == 6) Prepare_Item_Move(0); - else if (index_prepare == 7) Prepare_Item_Disable(0); - else if (index_prepare == 8) Prepare_Item_Home(0); - } - else { - Move_Highlight(-1, select_prepare.now + MROWS - index_prepare); - } - } - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { - switch (select_prepare.now) { - case 0: // back - select_page.set(1); - Goto_MainMenu(); - break; - case 1: // axis move - checkkey = AxisMove; - select_axis.reset(); - Draw_Move_Menu(); - - queue.inject_P(PSTR("G92 E0")); - current_position.e = HMI_ValueStruct.Move_E_scale = 0; - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 216, MBASE(1), current_position[X_AXIS] * MINUNITMULT); - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 216, MBASE(2), current_position[Y_AXIS] * MINUNITMULT); - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 216, MBASE(3), current_position[Z_AXIS] * MINUNITMULT); - show_plus_or_minus(font8x16, Background_black, 3, 1, 216, MBASE(4), current_position.e * MINUNITMULT); - break; - case 2: // close motion - queue.inject_P(PSTR("M84")); - break; - case 3: // homing - checkkey = Last_Prepare; - index_prepare = MROWS; - queue.inject_P(PSTR("G28")); // G28 will set home_flag - Popup_Window_Home(); - break; - case 4: // Z-offset - #if HAS_BED_PROBE - checkkey = Homeoffset; - HMI_ValueStruct.show_mode = -4; - HMI_ValueStruct.offset_value = probe.offset.z * 100; - show_plus_or_minus(font8x16, Select_Color, 2, 2, 202, MBASE(4 + MROWS - index_prepare), HMI_ValueStruct.offset_value); - EncoderRate.encoderRateEnabled = 1; - #else - // Apply workspace offset, making the current position 0,0,0 - queue.inject_P(PSTR("G92 X0 Y0 Z0")); - HMI_AudioFeedback(); - #endif - break; - case 5: // PLA preheat - thermalManager.setTargetHotend(ui.material_preset[0].hotend_temp, 0); - thermalManager.setTargetBed(ui.material_preset[0].bed_temp); - thermalManager.set_fan_speed(0, ui.material_preset[0].fan_speed); - break; - case 6: // ABS preheat - thermalManager.setTargetHotend(ui.material_preset[1].hotend_temp, 0); - thermalManager.setTargetBed(ui.material_preset[1].bed_temp); - thermalManager.set_fan_speed(0, ui.material_preset[1].fan_speed); - break; - case 7: // cool - thermalManager.zero_fan_speeds(); - thermalManager.disable_all_heaters(); - break; - case 8: // language - /* select language */ - HMI_flag.language_chinese ^= true; - if (HMI_flag.language_chinese) { - HMI_SetAndSaveLanguageChinese(); - DWIN_JPG_CacheTo1(Language_Chinese); - } - else { - HMI_SetAndSaveLanguageWestern(); - DWIN_JPG_CacheTo1(Language_English); - } - Draw_Prepare_Menu(); - break; - default: - break; - } - } - DWIN_UpdateLCD(); -} - -void Draw_Temperature_Menu() { - Clear_Main_Window(); - - if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 236, 2, 271 - 8, 479 - 466, 14, 8); - - DWIN_Frame_AreaCopy(1, 1, 134, 271 - 215, 479 - 333, LBLX, MBASE(1)); - DWIN_Frame_AreaCopy(1, 58, 134, 271 - 158, 479 - 333, LBLX, MBASE(2)); - DWIN_Frame_AreaCopy(1, 115, 134, 271 - 101, 479 - 333, LBLX, MBASE(3)); - DWIN_Frame_AreaCopy(1, 100, 89, 271 - 93, 479 - 378, LBLX, MBASE(4)); - DWIN_Frame_AreaCopy(1, 180, 89, 271 - 11, 479 - 379, LBLX, MBASE(5)); - } - else { - #ifdef USE_STRING_HEADINGS - Draw_Title(GET_TEXT_F(MSG_TEMPERATURE)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 0), (char*)GET_TEXT_F(MSG_UBL_SET_TEMP_HOTEND)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 1), (char*)GET_TEXT_F(MSG_UBL_SET_TEMP_BED)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 2), (char*)GET_TEXT_F(MSG_FAN_SPEED)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 3), (char*)"PLA Preheat Settings"); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 4), (char*)"ABS Preheat Settings"); - #else - DWIN_Frame_AreaCopy(1, 56, 16, 271 - 130, 479 - 450 - 1, 14, 8); - DWIN_Frame_AreaCopy(1, 197, 104, 271 - 33, 479 - 365, LBLX, MBASE(1)); // Nozzle... - DWIN_Frame_AreaCopy(1, 1, 89, 271 - 188, 479 - 377 - 1, LBLX + 41 + 3, MBASE(1)); // ...Temperature - DWIN_Frame_AreaCopy(1, 240, 104, 271 - 7, 479 - 365, LBLX, MBASE(2)); // Bed... - DWIN_Frame_AreaCopy(1, 1, 89, 271 - 188, 479 - 377 - 1, LBLX + 24 + 3, MBASE(2)); // ...Temperature - DWIN_Frame_AreaCopy(1, 0, 119, 271 - 207, 479 - 347, LBLX, MBASE(3)); // Fan speed - DWIN_Frame_AreaCopy(1, 107, 76, 271 - 115, 479 - 393, LBLX, MBASE(4)); // Preheat... - DWIN_Frame_AreaCopy(1, 157, 76, 181, 479 - 393, LBLX + 49 + 3, MBASE(4)); // ...PLA - DWIN_Frame_AreaCopy(1, 131, 119, 271 - 89, 479 - 347, LBLX + 49 + 24 + 6, MBASE(4)); // PLA setting - DWIN_Frame_AreaCopy(1, 107, 76, 271 - 115, 479 - 393, LBLX, MBASE(5)); // Preheat... - DWIN_Frame_AreaCopy(1, 172, 76, 198, 479 - 393, LBLX + 49 + 3, MBASE(5)); // ...ABS - DWIN_Frame_AreaCopy(1, 131, 119, 271 - 89, 479 - 347, LBLX + 49 + 3 + 26 + 3, MBASE(5)); // ABS setting - #endif - } - - Draw_Back_First(select_temp.now == 0); - if (select_temp.now) Draw_Menu_Cursor(select_temp.now); - - LOOP_L_N(i, 5) Draw_Menu_Line(i + 1, ICON_SetEndTemp + i); - - Draw_More_Icon(4); - Draw_More_Icon(5); - - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(1), thermalManager.temp_hotend[0].target); - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(2), thermalManager.temp_bed.target); - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(3), thermalManager.fan_speed[0]); -} - -/* Control */ -void HMI_Control(void) { - ENCODER_DiffState encoder_diffState = get_encoder_state(); - if (encoder_diffState == ENCODER_DIFF_NO) return; - - // Avoid flicker by updating only the previous menu - if (encoder_diffState == ENCODER_DIFF_CW) { - #define CONTROL_ITEMS (5 + ENABLED(HAS_LEVELING)) - if (select_control.inc(CONTROL_ITEMS)) { - if (select_control.now > MROWS && select_control.now > index_control) { - index_control = select_control.now; - Scroll_Menu(DWIN_SCROLL_UP); - Draw_Menu_Icon(MROWS, ICON_Temperature + select_control.now - 1); - Draw_More_Icon(1 + MROWS - index_control); // Temperature > - Draw_More_Icon(2 + MROWS - index_control); // Motion > - if (index_control > MROWS) { - Draw_More_Icon(6 + MROWS - index_control); // Info > - if (HMI_flag.language_chinese) - DWIN_Frame_AreaCopy(1, 231, 104, 271 - 13, 479 - 363, LBLX, MBASE(5)); - else - DWIN_Frame_AreaCopy(1, 0, 104, 271 - 247, 479 - 365, LBLX, MBASE(5)); - } - } - else { - Move_Highlight(1, select_control.now + MROWS - index_control); - } - } - } - else if (encoder_diffState == ENCODER_DIFF_CCW) { - if (select_control.dec()) { - if (select_control.now < index_control - MROWS) { - index_control--; - Scroll_Menu(DWIN_SCROLL_DOWN); - if (index_control == MROWS) - Draw_Back_First(); - else - Draw_Menu_Line(0, ICON_Temperature + select_control.now - 1); - Draw_More_Icon(0 + MROWS - index_control + 1); // Temperature > - Draw_More_Icon(1 + MROWS - index_control + 1); // Motion > - } - else { - Move_Highlight(-1, select_control.now + MROWS - index_control); - } - } - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { - switch (select_control.now) { - case 0: // back - select_page.set(2); - Goto_MainMenu(); - break; - case 1: // temperature - checkkey = TemperatureID; - HMI_ValueStruct.show_mode = -1; - select_temp.reset(); - Draw_Temperature_Menu(); - break; - case 2: // motion - checkkey = Motion; - select_motion.reset(); - Draw_Motion_Menu(); - break; - case 3: { // write EEPROM - const bool success = settings.save(); - HMI_AudioFeedback(success); - } break; - case 4: { // read EEPROM - const bool success = settings.load(); - HMI_AudioFeedback(success); - } break; - case 5: // resume EEPROM - settings.reset(); - HMI_AudioFeedback(); - break; - case 6: // info - checkkey = Info; - Draw_Info_Menu(); - break; - default: - break; - } - } - DWIN_UpdateLCD(); -} - -/* Leveling */ -void HMI_Leveling(void) { - Popup_Window_Leveling(); - DWIN_UpdateLCD(); - queue.inject_P(PSTR("G28O\nG29")); -} - -/* Axis Move */ -void HMI_AxisMove(void) { - ENCODER_DiffState encoder_diffState = get_encoder_state(); - if (encoder_diffState == ENCODER_DIFF_NO) return; - - #if HAS_HOTEND - // popup window resume - if (HMI_flag.ETempTooLow_flag) { - if (encoder_diffState == ENCODER_DIFF_ENTER) { - HMI_flag.ETempTooLow_flag = 0; - Draw_Move_Menu(); - current_position.e = HMI_ValueStruct.Move_E_scale = 0; - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 216, MBASE(1), HMI_ValueStruct.Move_X_scale); - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 216, MBASE(2), HMI_ValueStruct.Move_Y_scale); - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 216, MBASE(3), HMI_ValueStruct.Move_Z_scale); - show_plus_or_minus(font8x16, Background_black, 3, 1, 216, MBASE(4), HMI_ValueStruct.Move_E_scale); - DWIN_UpdateLCD(); - } - return; - } - #endif - - // Avoid flicker by updating only the previous menu - if (encoder_diffState == ENCODER_DIFF_CW) { - if (select_axis.inc(4)) Move_Highlight(1, select_axis.now); - } - else if (encoder_diffState == ENCODER_DIFF_CCW) { - if (select_axis.dec()) Move_Highlight(-1, select_axis.now); - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { - switch (select_axis.now) { - case 0: // back - checkkey = Prepare; - select_prepare.set(1); - index_prepare = MROWS; - Draw_Prepare_Menu(); - break; - case 1: // X axis move - checkkey = Move_X; - HMI_ValueStruct.Move_X_scale = current_position[X_AXIS] * MINUNITMULT; - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 216, MBASE(1), HMI_ValueStruct.Move_X_scale); - EncoderRate.encoderRateEnabled = 1; - break; - case 2: // Y axis move - checkkey = Move_Y; - HMI_ValueStruct.Move_Y_scale = current_position[Y_AXIS] * MINUNITMULT; - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 216, MBASE(2), HMI_ValueStruct.Move_Y_scale); - EncoderRate.encoderRateEnabled = 1; - break; - case 3: // Z axis move - checkkey = Move_Z; - HMI_ValueStruct.Move_Z_scale = current_position[Z_AXIS] * MINUNITMULT; - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 216, MBASE(3), HMI_ValueStruct.Move_Z_scale); - EncoderRate.encoderRateEnabled = 1; - break; - #if HAS_HOTEND - case 4: // Extruder - // window tips - #ifdef PREVENT_COLD_EXTRUSION - if (thermalManager.temp_hotend[0].celsius < EXTRUDE_MINTEMP) { - HMI_flag.ETempTooLow_flag = 1; - Popup_Window_ETempTooLow(); - DWIN_UpdateLCD(); - return; - } - #endif - checkkey = Extruder; - HMI_ValueStruct.Move_E_scale = current_position.e * MINUNITMULT; - show_plus_or_minus(font8x16, Select_Color, 3, 1, 216, MBASE(4), HMI_ValueStruct.Move_E_scale); - EncoderRate.encoderRateEnabled = 1; - break; - #endif - } - } - DWIN_UpdateLCD(); -} - -/* TemperatureID */ -void HMI_Temperature(void) { - ENCODER_DiffState encoder_diffState = get_encoder_state(); - if (encoder_diffState == ENCODER_DIFF_NO) return; - - // Avoid flicker by updating only the previous menu - if (encoder_diffState == ENCODER_DIFF_CW) { - if (select_temp.inc(5)) Move_Highlight(1, select_temp.now); - } - else if (encoder_diffState == ENCODER_DIFF_CCW) { - if (select_temp.dec()) Move_Highlight(-1, select_temp.now); - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { - switch (select_temp.now) { - case 0: // back - checkkey = Control; - select_control.set(1); - index_control = MROWS; - Draw_Control_Menu(); - break; - #if HAS_HOTEND - case 1: // nozzle temperature - checkkey = ETemp; - HMI_ValueStruct.E_Temp = thermalManager.temp_hotend[0].target; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(1), thermalManager.temp_hotend[0].target); - EncoderRate.encoderRateEnabled = 1; - break; - #endif - #if HAS_HEATED_BED - case 2: // bed temperature - checkkey = BedTemp; - HMI_ValueStruct.Bed_Temp = thermalManager.temp_bed.target; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(2), thermalManager.temp_bed.target); - EncoderRate.encoderRateEnabled = 1; - break; - #endif - #if HAS_FAN - case 3: // fan speed - checkkey = FanSpeed; - HMI_ValueStruct.Fan_speed = thermalManager.fan_speed[0]; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(3), thermalManager.fan_speed[0]); - EncoderRate.encoderRateEnabled = 1; - break; - #endif - #if HAS_HOTEND - case 4: // PLA preheat setting - checkkey = PLAPreheat; - select_PLA.reset(); - HMI_ValueStruct.show_mode = -2; - - Clear_Main_Window(); - - if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 59, 16, 271 - 132, 479 - 450, 14, 8); - - DWIN_Frame_AreaCopy(1, 100, 89, 124, 479 - 378, LBLX, MBASE(1)); - DWIN_Frame_AreaCopy(1, 1, 134, 271 - 215, 479 - 333, LBLX + 24, MBASE(1)); // PLA nozzle temp - DWIN_Frame_AreaCopy(1, 100, 89, 124, 479 - 378, LBLX, MBASE(2)); - DWIN_Frame_AreaCopy(1, 58, 134, 271 - 158, 479 - 333, LBLX + 24, MBASE(2)); // PLA bed temp - DWIN_Frame_AreaCopy(1, 100, 89, 124, 479 - 378, LBLX, MBASE(3)); - DWIN_Frame_AreaCopy(1, 115, 134, 271 - 101, 479 - 333, LBLX + 24, MBASE(3)); // PLA fan speed - DWIN_Frame_AreaCopy(1, 72, 148, 271 - 120, 479 - 317, LBLX, MBASE(4)); // save PLA configuration - } - else { - #ifdef USE_STRING_HEADINGS - Draw_Title("PLA Settings"); // TODO: GET_TEXT_F - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 0), (char*)"Nozzle Temp"); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 1), (char*)"Bed Temp"); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 2), (char*)GET_TEXT_F(MSG_FAN_SPEED)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 3), (char*)GET_TEXT_F(MSG_STORE_EEPROM)); - #else - DWIN_Frame_AreaCopy(1, 56, 16, 271 - 130, 479 - 450 - 1, 14, 8); - DWIN_Frame_AreaCopy(1, 157, 76, 181, 479 - 393, LBLX, MBASE(1)); - DWIN_Frame_AreaCopy(1, 197, 104, 271 - 33, 479 - 365, LBLX + 24 + 3, MBASE(1)); - DWIN_Frame_AreaCopy(1, 1, 89, 271 - 188, 479 - 377 - 1, LBLX + 24 + 41 + 6, MBASE(1)); // PLA nozzle temp - DWIN_Frame_AreaCopy(1, 157, 76, 181, 479 - 393, LBLX, MBASE(2) + 3); - DWIN_Frame_AreaCopy(1, 240, 104, 271 - 7, 479 - 365, LBLX + 24 + 3, MBASE(2) + 3); - DWIN_Frame_AreaCopy(1, 1, 89, 271 - 188, 479 - 377 - 1, LBLX + 24 + 24 + 6, MBASE(2) + 3); // PLA bed temp - DWIN_Frame_AreaCopy(1, 157, 76, 181, 479 - 393, LBLX, MBASE(3)); - DWIN_Frame_AreaCopy(1, 0, 119, 271 - 207, 479 - 347, LBLX + 24 + 3, MBASE(3)); // PLA fan speed - DWIN_Frame_AreaCopy(1, 97, 165, 271 - 42, 479 - 301 - 1, LBLX, MBASE(4)); // save PLA configuration - #endif - } - - Draw_Back_First(); - - Draw_Menu_Line(1, ICON_SetEndTemp); - Draw_Menu_Line(2, ICON_SetBedTemp); - Draw_Menu_Line(3, ICON_FanSpeed); - Draw_Menu_Line(4, ICON_WriteEEPROM); - - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(1), ui.material_preset[0].hotend_temp); - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(2), ui.material_preset[0].bed_temp); - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(3), ui.material_preset[0].fan_speed); - - break; - - case 5: // ABS preheat setting - checkkey = ABSPreheat; - select_ABS.reset(); - HMI_ValueStruct.show_mode = -3; - - Clear_Main_Window(); - - if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 142, 16, 271 - 48, 479 - 450, 14, 8); - - DWIN_Frame_AreaCopy(1, 180, 89, 204, 479 - 379, LBLX, MBASE(1)); - DWIN_Frame_AreaCopy(1, 1, 134, 271 - 215, 479 - 333, LBLX + 24, MBASE(1)); // ABS nozzle temp - DWIN_Frame_AreaCopy(1, 180, 89, 204, 479 - 379, LBLX, MBASE(2)); - DWIN_Frame_AreaCopy(1, 58, 134, 271 - 158, 479 - 333, LBLX + 24, MBASE(2)); // ABS bed temp - DWIN_Frame_AreaCopy(1, 180, 89, 204, 479 - 379, LBLX, MBASE(3)); - DWIN_Frame_AreaCopy(1, 115, 134, 271 - 101, 479 - 333, LBLX + 24, MBASE(3)); // ABS fan speed - DWIN_Frame_AreaCopy(1, 72, 148, 271 - 120, 479 - 317, LBLX, MBASE(4)); - DWIN_Frame_AreaCopy(1, 180, 89, 204, 479 - 379, LBLX + 28, MBASE(4) + 2); // save ABS configuration - } - else { - #ifdef USE_STRING_HEADINGS - Draw_Title("ABS Settings"); // TODO: GET_TEXT_F - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 0), (char*)"Nozzle Temp"); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 1), (char*)"Bed Temp"); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 2), (char*)GET_TEXT_F(MSG_FAN_SPEED)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 3), (char*)GET_TEXT_F(MSG_STORE_EEPROM)); - #else - DWIN_Frame_AreaCopy(1, 56, 16, 271 - 130, 479 - 450 - 1, 14, 8); - DWIN_Frame_AreaCopy(1, 172, 76, 198, 479 - 393, LBLX, MBASE(1)); - DWIN_Frame_AreaCopy(1, 197, 104, 271 - 33, 479 - 365, LBLX + 24 + 3, MBASE(1)); - DWIN_Frame_AreaCopy(1, 1, 89, 271 - 188, 479 - 377 - 1, LBLX + 24 + 41 + 6, MBASE(1)); // ABS nozzle temp - DWIN_Frame_AreaCopy(1, 172, 76, 198, 479 - 393, LBLX, MBASE(2) + 3); - DWIN_Frame_AreaCopy(1, 240, 104, 271 - 7, 479 - 365, LBLX + 24 + 3, MBASE(2) + 3); - DWIN_Frame_AreaCopy(1, 1, 89, 271 - 188, 479 - 377 - 1, LBLX + 24 + 24 + 6, MBASE(2) + 3); // ABS bed temp - DWIN_Frame_AreaCopy(1, 172, 76, 198, 479 - 393, LBLX, MBASE(3)); - DWIN_Frame_AreaCopy(1, 0, 119, 271 - 207, 479 - 347, LBLX + 24 + 3, MBASE(3)); // ABS fan speed - DWIN_Frame_AreaCopy(1, 97, 165, 271 - 42, 479 - 301 - 1, LBLX, MBASE(4)); - DWIN_Frame_AreaCopy(1, 172, 76, 198, 479 - 393, LBLX + 33, MBASE(4)); // save ABS configuration - #endif - } - - Draw_Back_First(); - - Draw_Menu_Line(1, ICON_SetEndTemp); - Draw_Menu_Line(2, ICON_SetBedTemp); - Draw_Menu_Line(3, ICON_FanSpeed); - Draw_Menu_Line(4, ICON_WriteEEPROM); - - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(1), ui.material_preset[1].hotend_temp); - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(2), ui.material_preset[1].bed_temp); - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 3, 216, MBASE(3), ui.material_preset[1].fan_speed); - - break; - #endif // if HAS_HOTEND - } - } - DWIN_UpdateLCD(); -} - -inline void Draw_Max_Speed_Menu() { - Clear_Main_Window(); - - if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 1, 16, 271 - 243, 479 - 451, 14, 8); - - auto say_max_speed = [](const uint16_t row) { - DWIN_Frame_AreaCopy(1, 173, 133, 228, 479 - 332, LBLX, row); // "Max speed" - }; - - say_max_speed(MBASE(1)); // "Max speed" - DWIN_Frame_AreaCopy(1, 229, 133, 236, 479 - 332, LBLX + 55 + 3, MBASE(1)); // X - say_max_speed(MBASE(2)); // "Max speed" - DWIN_Frame_AreaCopy(1, 1, 150, 271 - 264, 479 - 319, LBLX + 55 + 3, MBASE(2) + 3); // Y - say_max_speed(MBASE(3)); // "Max speed" - DWIN_Frame_AreaCopy(1, 9, 150, 271 - 255, 479 - 319, LBLX + 55 + 3, MBASE(3) + 3); // Z - say_max_speed(MBASE(4)); // "Max speed" - DWIN_Frame_AreaCopy(1, 18, 150, 271 - 246, 479 - 319, LBLX + 55 + 3, MBASE(4) + 3); // E - } - else { - #ifdef USE_STRING_HEADINGS - Draw_Title("Max Speed (mm/s)"); // TODO: GET_TEXT_F - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 0), (char*)"Max Feedrate X"); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 1), (char*)"Max Feedrate Y"); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 2), (char*)"Max Feedrate Z"); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 3), (char*)"Max Feedrate E"); - #else - DWIN_Frame_AreaCopy(1, 144, 16, 271 - 82, 479 - 453, 14, 8); - - draw_max_en(MBASE(1)); // "Max" - DWIN_Frame_AreaCopy(1, 184, 119, 271 - 37, 479 - 347, LBLX + 24 + 3, MBASE(1)); // "Speed X" - - draw_max_en(MBASE(2)); // "Max" - draw_speed_en(24 + 3, MBASE(2)); // "Speed" - say_y(24 + 40 + 6, MBASE(2)); // "Y" - - draw_max_en(MBASE(3)); // "Max" - draw_speed_en(24 + 3, MBASE(3)); // "Speed" - say_z(24 + 40 + 6, MBASE(3)); // "Z" - - draw_max_en(MBASE(4)); // "Max" - draw_speed_en(24 + 3, MBASE(4)); // "Speed" - say_e(24 + 40 + 6, MBASE(4)); // "E" - #endif - } - - Draw_Back_First(); - LOOP_L_N(i, 4) Draw_Menu_Line(i + 1, ICON_MaxSpeedX + i); - - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 4, 210, MBASE(1), planner.settings.max_feedrate_mm_s[X_AXIS]); - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 4, 210, MBASE(2), planner.settings.max_feedrate_mm_s[Y_AXIS]); - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 4, 210, MBASE(3), planner.settings.max_feedrate_mm_s[Z_AXIS]); - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 4, 210, MBASE(4), planner.settings.max_feedrate_mm_s[E_AXIS]); -} - -inline void Draw_Max_Accel_Menu() { - Clear_Main_Window(); - - if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 1, 16, 271 - 243, 479 - 451, 14, 8); - - DWIN_Frame_AreaCopy(1, 173, 133, 200, 479 - 332, LBLX, MBASE(1)); - DWIN_Frame_AreaCopy(1, 28, 149, 271 - 202, 479 - 318, LBLX + 27, MBASE(1) + 1); - DWIN_Frame_AreaCopy(1, 229, 133, 236, 479 - 332, LBLX + 27 + 41 + 3, MBASE(1)); // max acceleration X - DWIN_Frame_AreaCopy(1, 173, 133, 200, 479 - 332, LBLX, MBASE(2)); - DWIN_Frame_AreaCopy(1, 28, 149, 271 - 202, 479 - 318, LBLX + 27, MBASE(2) + 1); - DWIN_Frame_AreaCopy(1, 1, 150, 271 - 264, 479 - 319, LBLX + 27 + 41 + 3, MBASE(2) + 2); // max acceleration Y - DWIN_Frame_AreaCopy(1, 173, 133, 200, 479 - 332, LBLX, MBASE(3)); - DWIN_Frame_AreaCopy(1, 28, 149, 271 - 202, 479 - 318, LBLX + 27, MBASE(3) + 1); - DWIN_Frame_AreaCopy(1, 9, 150, 271 - 255, 479 - 319, LBLX + 27 + 41 + 3, MBASE(3) + 2); // max acceleration Z - DWIN_Frame_AreaCopy(1, 173, 133, 200, 479 - 332, LBLX, MBASE(4)); - DWIN_Frame_AreaCopy(1, 28, 149, 271 - 202, 479 - 318, LBLX + 27, MBASE(4) + 1); - DWIN_Frame_AreaCopy(1, 18, 150, 271 - 246, 479 - 319, LBLX + 27 + 41 + 3, MBASE(4) + 2); // max acceleration E - } - else { - #ifdef USE_STRING_HEADINGS - Draw_Title(GET_TEXT_F(MSG_ACCELERATION)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 0), (char*)"Max Accel X"); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 1), (char*)"Max Accel Y"); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 2), (char*)"Max Accel Z"); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 3), (char*)"Max Accel E"); - #else - DWIN_Frame_AreaCopy(1, 144, 16, 271 - 82, 479 - 453, 14, 8); - draw_max_accel_en(MBASE(1)); say_x(24 + 78 + 6, MBASE(1)); // "Max Acceleration X" - draw_max_accel_en(MBASE(2)); say_y(24 + 78 + 6, MBASE(2)); // "Max Acceleration Y" - draw_max_accel_en(MBASE(3)); say_z(24 + 78 + 6, MBASE(3)); // "Max Acceleration Z" - draw_max_accel_en(MBASE(4)); say_e(24 + 78 + 6, MBASE(4)); // "Max Acceleration E" - #endif - } - - Draw_Back_First(); - LOOP_L_N(i, 4) Draw_Menu_Line(i + 1, ICON_MaxAccX + i); - - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 4, 210, MBASE(1), planner.settings.max_acceleration_mm_per_s2[X_AXIS]); - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 4, 210, MBASE(2), planner.settings.max_acceleration_mm_per_s2[Y_AXIS]); - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 4, 210, MBASE(3), planner.settings.max_acceleration_mm_per_s2[Z_AXIS]); - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Background_black, 4, 210, MBASE(4), planner.settings.max_acceleration_mm_per_s2[E_AXIS]); -} - -inline void Draw_Max_Jerk_Menu() { - Clear_Main_Window(); - - if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 1, 16, 271 - 243, 479 - 451, 14, 8); - - DWIN_Frame_AreaCopy(1, 173, 133, 200, 479 - 332, LBLX, MBASE(1)); - DWIN_Frame_AreaCopy(1, 1, 180, 271 - 243, 479 - 287, LBLX + 27, MBASE(1) + 1); - DWIN_Frame_AreaCopy(1, 202, 133, 228, 479 - 332, LBLX + 53, MBASE(1)); - DWIN_Frame_AreaCopy(1, 229, 133, 236, 479 - 332, LBLX + 80 + 3, MBASE(1)); // max corner speed X - DWIN_Frame_AreaCopy(1, 173, 133, 200, 479 - 332, LBLX, MBASE(2)); - DWIN_Frame_AreaCopy(1, 1, 180, 271 - 243, 479 - 287, LBLX + 27, MBASE(2) + 1); - DWIN_Frame_AreaCopy(1, 202, 133, 228, 479 - 332, LBLX + 53, MBASE(2)); - DWIN_Frame_AreaCopy(1, 1, 150, 271 - 264, 479 - 319, LBLX + 80 + 3, MBASE(2) + 3); // max corner speed Y - DWIN_Frame_AreaCopy(1, 173, 133, 200, 479 - 332, LBLX, MBASE(3)); - DWIN_Frame_AreaCopy(1, 1, 180, 271 - 243, 479 - 287, LBLX + 27, MBASE(3) + 1); - DWIN_Frame_AreaCopy(1, 202, 133, 228, 479 - 332, LBLX + 53, MBASE(3)); - DWIN_Frame_AreaCopy(1, 9, 150, 271 - 255, 479 - 319, LBLX + 80 + 3, MBASE(3) + 3); // max corner speed Z - DWIN_Frame_AreaCopy(1, 173, 133, 200, 479 - 332, LBLX, MBASE(4)); - DWIN_Frame_AreaCopy(1, 1, 180, 271 - 243, 479 - 287, LBLX + 27, MBASE(4) + 1); - DWIN_Frame_AreaCopy(1, 202, 133, 228, 479 - 332, LBLX + 53, MBASE(4)); - DWIN_Frame_AreaCopy(1, 18, 150, 271 - 246, 479 - 319, LBLX + 80 + 3, MBASE(4) + 3); // max corner speed E - } - else { - #ifdef USE_STRING_HEADINGS - Draw_Title(GET_TEXT_F(MSG_JERK)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 0), (char*)"Max Jerk X"); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 1), (char*)"Max Jerk Y"); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 2), (char*)"Max Jerk Z"); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 3), (char*)"Max Jerk E"); - #else - DWIN_Frame_AreaCopy(1, 144, 16, 271 - 82, 479 - 453, 14, 8); - draw_max_en(MBASE(1)); // "Max" - draw_corner_en(MBASE(1)); // "Corner" - draw_speed_en(66 + 6, MBASE(1)); // "Speed" - say_x(106 + 9, MBASE(1)); // "X" - - draw_max_en(MBASE(2)); // "Max" - draw_corner_en(MBASE(2)); // "Corner" - draw_speed_en(66 + 6, MBASE(2)); // "Speed" - say_y(106 + 9, MBASE(2)); // "Y" - - draw_max_en(MBASE(3)); // "Max" - draw_corner_en(MBASE(3)); // "Corner" - draw_speed_en(66 + 6, MBASE(3)); // "Speed" - say_z(106 + 9, MBASE(3)); // "Z" - - draw_max_en(MBASE(4)); // "Max" - draw_corner_en(MBASE(4)); // "Corner" - draw_speed_en(66 + 6, MBASE(4)); // "Speed" - say_e(106 + 9, MBASE(4)); // "E" - #endif - } - - Draw_Back_First(); - LOOP_L_N(i, 4) Draw_Menu_Line(i + 1, ICON_MaxSpeedCornerX + i); - - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 210, MBASE(1), planner.max_jerk[X_AXIS] * MINUNITMULT); - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 210, MBASE(2), planner.max_jerk[Y_AXIS] * MINUNITMULT); - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 210, MBASE(3), planner.max_jerk[Z_AXIS] * MINUNITMULT); - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 210, MBASE(4), planner.max_jerk[E_AXIS] * MINUNITMULT); -} - -inline void Draw_Steps_Menu() { - Clear_Main_Window(); - - if (HMI_flag.language_chinese) { - DWIN_Frame_AreaCopy(1, 1, 16, 271 - 243, 479 - 451, 14, 8); - - DWIN_Frame_AreaCopy(1, 153, 148, 271 - 77, 479 - 318, LBLX, MBASE(1)); - DWIN_Frame_AreaCopy(1, 229, 133, 236, 479 - 332, LBLX + 41 + 3, MBASE(1)); // Transmission Ratio X - DWIN_Frame_AreaCopy(1, 153, 148, 271 - 77, 479 - 318, LBLX, MBASE(2)); - DWIN_Frame_AreaCopy(1, 1, 150, 271 - 264, 479 - 319, LBLX + 41 + 3, MBASE(2) + 3); // Transmission Ratio Y - DWIN_Frame_AreaCopy(1, 153, 148, 271 - 77, 479 - 318, LBLX, MBASE(3)); - DWIN_Frame_AreaCopy(1, 9, 150, 271 - 255, 479 - 319, LBLX + 41 + 3, MBASE(3) + 3); // Transmission Ratio Z - DWIN_Frame_AreaCopy(1, 153, 148, 271 - 77, 479 - 318, LBLX, MBASE(4)); - DWIN_Frame_AreaCopy(1, 18, 150, 271 - 246, 479 - 319, LBLX + 41 + 3, MBASE(4) + 3); // Transmission Ratio E - } - else { - #ifdef USE_STRING_HEADINGS - Draw_Title(GET_TEXT_F(MSG_STEPS_PER_MM)); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 0), (char*)"Steps/mm X"); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 1), (char*)"Steps/mm Y"); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 2), (char*)"Steps/mm Z"); - DWIN_Draw_String(false, true, font8x16, White, Background_black, 60, 102 + (MLINE * 3), (char*)"Steps/mm E"); - #else - DWIN_Frame_AreaCopy(1, 144, 16, 271 - 82, 479 - 453, 14, 8); - draw_steps_per_mm(MBASE(1)); say_x(100 + 3, MBASE(1)); // "Steps-per-mm X" - draw_steps_per_mm(MBASE(2)); say_y(100 + 3, MBASE(2)); // "Y" - draw_steps_per_mm(MBASE(3)); say_z(100 + 3, MBASE(3)); // "Z" - draw_steps_per_mm(MBASE(4)); say_e(100 + 3, MBASE(4)); // "E" - #endif - } - - Draw_Back_First(); - LOOP_L_N(i, 4) Draw_Menu_Line(i + 1, ICON_StepX + i); - - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 210, MBASE(1), planner.settings.axis_steps_per_mm[X_AXIS] * MINUNITMULT); - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 210, MBASE(2), planner.settings.axis_steps_per_mm[Y_AXIS] * MINUNITMULT); - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 210, MBASE(3), planner.settings.axis_steps_per_mm[Z_AXIS] * MINUNITMULT); - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Background_black, 3, 1, 210, MBASE(4), planner.settings.axis_steps_per_mm[E_AXIS] * MINUNITMULT); -} - -/* Motion */ -void HMI_Motion(void) { - ENCODER_DiffState encoder_diffState = get_encoder_state(); - if (encoder_diffState == ENCODER_DIFF_NO) return; - - // Avoid flicker by updating only the previous menu - if (encoder_diffState == ENCODER_DIFF_CW) { - if (select_motion.inc(4)) Move_Highlight(1, select_motion.now); - } - else if (encoder_diffState == ENCODER_DIFF_CCW) { - if (select_motion.dec()) Move_Highlight(-1, select_motion.now); - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { - switch (select_motion.now) { - case 0: // back - checkkey = Control; - select_control.set(2); - index_control = MROWS; - Draw_Control_Menu(); - break; - case 1: // max speed - checkkey = MaxSpeed; - select_speed.reset(); - Draw_Max_Speed_Menu(); - break; - case 2: // max acceleration - checkkey = MaxAcceleration; - select_acc.reset(); - Draw_Max_Accel_Menu(); - break; - case 3: // max corner speed - checkkey = MaxCorner; - select_corner.reset(); - Draw_Max_Jerk_Menu(); - break; - case 4: // transmission ratio - checkkey = Step; - select_step.reset(); - Draw_Steps_Menu(); - break; - default: - break; - } - } - DWIN_UpdateLCD(); -} - -/* Info */ -void HMI_Info(void) { - ENCODER_DiffState encoder_diffState = get_encoder_state(); - if (encoder_diffState == ENCODER_DIFF_NO) return; - if (encoder_diffState == ENCODER_DIFF_ENTER) { - #if HAS_LEVELING - checkkey = Control; - select_control.set(CONTROL_ITEMS); - Draw_Control_Menu(); - #else - select_page.set(3); - Goto_MainMenu(); - #endif - } - DWIN_UpdateLCD(); -} - -/* Tune */ -void HMI_Tune(void) { - ENCODER_DiffState encoder_diffState = get_encoder_state(); - if (encoder_diffState == ENCODER_DIFF_NO) return; - - // Avoid flicker by updating only the previous menu - if (encoder_diffState == ENCODER_DIFF_CW) { - if (select_tune.inc(6)) { - if (select_tune.now > MROWS && select_tune.now > index_tune) { - index_tune = select_tune.now; - Scroll_Menu(DWIN_SCROLL_UP); - Prepare_Item_Lang(5); - } - else { - Move_Highlight(1, select_tune.now + MROWS - index_tune); - } - } - } - else if (encoder_diffState == ENCODER_DIFF_CCW) { - if (select_tune.dec()) { - if (select_tune.now < index_tune - MROWS) { - index_tune--; - Scroll_Menu(DWIN_SCROLL_DOWN); - if (index_tune == MROWS) Draw_Back_First(); - } - else { - Move_Highlight(-1, select_tune.now + MROWS - index_tune); - } - } - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { - switch (select_tune.now) { - case 0: { // Back - select_print.set(0); - Goto_PrintProcess(); - } - break; - case 1: // Print speed - checkkey = PrintSpeed; - HMI_ValueStruct.print_speed = feedrate_percentage; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(1 + MROWS - index_tune), feedrate_percentage); - EncoderRate.encoderRateEnabled = 1; - break; - #if HAS_HOTEND - case 2: // Nozzle temp - checkkey = ETemp; - HMI_ValueStruct.E_Temp = thermalManager.temp_hotend[0].target; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(2 + MROWS - index_tune), thermalManager.temp_hotend[0].target); - EncoderRate.encoderRateEnabled = 1; - break; - #endif - #if HAS_HEATED_BED - case 3: // Bed temp - checkkey = BedTemp; - HMI_ValueStruct.Bed_Temp = thermalManager.temp_bed.target; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(3 + MROWS - index_tune), thermalManager.temp_bed.target); - EncoderRate.encoderRateEnabled = 1; - break; - #endif - #if HAS_FAN - case 4: // Fan speed - checkkey = FanSpeed; - HMI_ValueStruct.Fan_speed = thermalManager.fan_speed[0]; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(4 + MROWS - index_tune), thermalManager.fan_speed[0]); - EncoderRate.encoderRateEnabled = 1; - break; - #endif - case 5: // Z-offset - checkkey = Homeoffset; - HMI_ValueStruct.offset_value = BABY_Z_VAR * 100; - show_plus_or_minus(font8x16, Select_Color, 2, 2, 202, MBASE(5 + MROWS - index_tune), HMI_ValueStruct.offset_value); - EncoderRate.encoderRateEnabled = 1; - break; - case 6: // Language - // Select language - HMI_flag.language_chinese ^= true; - - Clear_Main_Window(); - - if (HMI_flag.language_chinese) { - HMI_SetAndSaveLanguageChinese(); - DWIN_JPG_CacheTo1(Language_Chinese); - } - else { - HMI_SetAndSaveLanguageWestern(); - DWIN_JPG_CacheTo1(Language_English); - } - - Draw_Tune_Menu(); - break; - - default: break; - } - } - DWIN_UpdateLCD(); -} - -/* PLA Preheat */ -void HMI_PLAPreheatSetting(void) { - ENCODER_DiffState encoder_diffState = get_encoder_state(); - if (encoder_diffState == ENCODER_DIFF_NO) return; - - // Avoid flicker by updating only the previous menu - if (encoder_diffState == ENCODER_DIFF_CW) { - if (select_PLA.inc(4)) Move_Highlight(1, select_PLA.now); - } - else if (encoder_diffState == ENCODER_DIFF_CCW) { - if (select_PLA.dec()) Move_Highlight(-1, select_PLA.now); - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { - switch (select_PLA.now) { - case 0: // back - checkkey = TemperatureID; - select_temp.now = 4; - HMI_ValueStruct.show_mode = -1; - Draw_Temperature_Menu(); - break; - #if HAS_HOTEND - case 1: // set nozzle temperature - checkkey = ETemp; - HMI_ValueStruct.E_Temp = ui.material_preset[0].hotend_temp; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(1), ui.material_preset[0].hotend_temp); - EncoderRate.encoderRateEnabled = 1; - break; - #endif - #if HAS_HEATED_BED - case 2: // set bed temperature - checkkey = BedTemp; - HMI_ValueStruct.Bed_Temp = ui.material_preset[0].bed_temp; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(2), ui.material_preset[0].bed_temp); - EncoderRate.encoderRateEnabled = 1; - break; - #endif - #if HAS_FAN - case 3: // set fan speed - checkkey = FanSpeed; - HMI_ValueStruct.Fan_speed = ui.material_preset[0].fan_speed; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(3), ui.material_preset[0].fan_speed); - EncoderRate.encoderRateEnabled = 1; - break; - #endif - case 4: { // save PLA configuration - const bool success = settings.save(); - HMI_AudioFeedback(success); - } break; - default: break; - } - } - DWIN_UpdateLCD(); -} - -/* ABS Preheat */ -void HMI_ABSPreheatSetting(void) { - ENCODER_DiffState encoder_diffState = get_encoder_state(); - if (encoder_diffState == ENCODER_DIFF_NO) return; - - // Avoid flicker by updating only the previous menu - if (encoder_diffState == ENCODER_DIFF_CW) { - if (select_ABS.inc(4)) Move_Highlight(1, select_ABS.now); - } - else if (encoder_diffState == ENCODER_DIFF_CCW) { - if (select_ABS.dec()) Move_Highlight(-1, select_ABS.now); - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { - switch (select_ABS.now) { - case 0: // back - checkkey = TemperatureID; - select_temp.now = 5; - HMI_ValueStruct.show_mode = -1; - Draw_Temperature_Menu(); - break; - #if HAS_HOTEND - case 1: // set nozzle temperature - checkkey = ETemp; - HMI_ValueStruct.E_Temp = ui.material_preset[1].hotend_temp; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(1), ui.material_preset[1].hotend_temp); - EncoderRate.encoderRateEnabled = 1; - break; - #endif - #if HAS_HEATED_BED - case 2: // set bed temperature - checkkey = BedTemp; - HMI_ValueStruct.Bed_Temp = ui.material_preset[1].bed_temp; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(2), ui.material_preset[1].bed_temp); - EncoderRate.encoderRateEnabled = 1; - break; - #endif - #if HAS_FAN - case 3: // set fan speed - checkkey = FanSpeed; - HMI_ValueStruct.Fan_speed = ui.material_preset[1].fan_speed; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 3, 216, MBASE(3), ui.material_preset[1].fan_speed); - EncoderRate.encoderRateEnabled = 1; - break; - #endif - case 4: { // save ABS configuration - const bool success = settings.save(); - HMI_AudioFeedback(success); - } break; - default: - break; - } - } - DWIN_UpdateLCD(); -} - -/* Max Speed */ -void HMI_MaxSpeed(void) { - ENCODER_DiffState encoder_diffState = get_encoder_state(); - if (encoder_diffState == ENCODER_DIFF_NO) return; - - // Avoid flicker by updating only the previous menu - if (encoder_diffState == ENCODER_DIFF_CW) { - if (select_speed.inc(4)) Move_Highlight(1, select_speed.now); - } - else if (encoder_diffState == ENCODER_DIFF_CCW) { - if (select_speed.dec()) Move_Highlight(-1, select_speed.now); - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { - switch (select_speed.now) { - case 0: // back - checkkey = Motion; - select_motion.now = 1; - Draw_Motion_Menu(); - break; - case 1: // max Speed X - checkkey = MaxSpeed_value; - HMI_flag.feedspeed_flag = X_AXIS; - HMI_ValueStruct.Max_Feedspeed = planner.settings.max_feedrate_mm_s[X_AXIS]; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 4, 210, MBASE(select_speed.now), HMI_ValueStruct.Max_Feedspeed); - EncoderRate.encoderRateEnabled = 1; - break; - case 2: // max Speed Y - checkkey = MaxSpeed_value; - HMI_flag.feedspeed_flag = Y_AXIS; - HMI_ValueStruct.Max_Feedspeed = planner.settings.max_feedrate_mm_s[Y_AXIS]; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 4, 210, MBASE(select_speed.now), HMI_ValueStruct.Max_Feedspeed); - EncoderRate.encoderRateEnabled = 1; - break; - case 3: // max Speed Z - checkkey = MaxSpeed_value; - HMI_flag.feedspeed_flag = Z_AXIS; - HMI_ValueStruct.Max_Feedspeed = planner.settings.max_feedrate_mm_s[Z_AXIS]; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 4, 210, MBASE(select_speed.now), HMI_ValueStruct.Max_Feedspeed); - EncoderRate.encoderRateEnabled = 1; - break; - case 4: // max Speed E - checkkey = MaxSpeed_value; - HMI_flag.feedspeed_flag = E_AXIS; - HMI_ValueStruct.Max_Feedspeed = planner.settings.max_feedrate_mm_s[E_AXIS]; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 4, 210, MBASE(select_speed.now), HMI_ValueStruct.Max_Feedspeed); - EncoderRate.encoderRateEnabled = 1; - break; - default: - break; - } - } - DWIN_UpdateLCD(); -} - -/* Max Acceleration */ -void HMI_MaxAcceleration(void) { - ENCODER_DiffState encoder_diffState = get_encoder_state(); - if (encoder_diffState == ENCODER_DIFF_NO) return; - - // Avoid flicker by updating only the previous menu - if (encoder_diffState == ENCODER_DIFF_CW) { - if (select_acc.inc(4)) Move_Highlight(1, select_acc.now); - } - else if (encoder_diffState == ENCODER_DIFF_CCW) { - if (select_acc.dec()) Move_Highlight(-1, select_acc.now); - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { - switch (select_acc.now) { - case 0: // back - checkkey = Motion; - select_motion.now = 2; - Draw_Motion_Menu(); - break; - case 1: // max acceleration X - checkkey = MaxAcceleration_value; - HMI_flag.acc_flag = X_AXIS; - HMI_ValueStruct.Max_Acceleration = planner.settings.max_acceleration_mm_per_s2[X_AXIS]; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 4, 210, MBASE(select_acc.now), HMI_ValueStruct.Max_Acceleration); - EncoderRate.encoderRateEnabled = 1; - break; - case 2: // max acceleration Y - checkkey = MaxAcceleration_value; - HMI_flag.acc_flag = Y_AXIS; - HMI_ValueStruct.Max_Acceleration = planner.settings.max_acceleration_mm_per_s2[Y_AXIS]; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 4, 210, MBASE(select_acc.now), HMI_ValueStruct.Max_Acceleration); - EncoderRate.encoderRateEnabled = 1; - break; - case 3: // max acceleration Z - checkkey = MaxAcceleration_value; - HMI_flag.acc_flag = Z_AXIS; - HMI_ValueStruct.Max_Acceleration = planner.settings.max_acceleration_mm_per_s2[Z_AXIS]; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 4, 210, MBASE(select_acc.now), HMI_ValueStruct.Max_Acceleration); - EncoderRate.encoderRateEnabled = 1; - break; - case 4: // max acceleration E - checkkey = MaxAcceleration_value; - HMI_flag.acc_flag = E_AXIS; - HMI_ValueStruct.Max_Acceleration = planner.settings.max_acceleration_mm_per_s2[E_AXIS]; - DWIN_Draw_IntValue(true, true, 0, font8x16, White, Select_Color, 4, 210, MBASE(select_acc.now), HMI_ValueStruct.Max_Acceleration); - EncoderRate.encoderRateEnabled = 1; - break; - default: - break; - } - } - DWIN_UpdateLCD(); -} - -/* Max Corner */ -void HMI_MaxCorner(void) { - ENCODER_DiffState encoder_diffState = get_encoder_state(); - if (encoder_diffState == ENCODER_DIFF_NO) return; - - // Avoid flicker by updating only the previous menu - if (encoder_diffState == ENCODER_DIFF_CW) { - if (select_corner.inc(4)) Move_Highlight(1, select_corner.now); - } - else if (encoder_diffState == ENCODER_DIFF_CCW) { - if (select_corner.dec()) Move_Highlight(-1, select_corner.now); - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { - switch (select_corner.now) { - case 0: // back - checkkey = Motion; - select_motion.now = 3; - Draw_Motion_Menu(); - break; - case 1: // max corner X - checkkey = MaxCorner_value; - HMI_flag.corner_flag = X_AXIS; - HMI_ValueStruct.Max_Corner = planner.max_jerk[X_AXIS] * MINUNITMULT; - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 210, MBASE(select_corner.now), HMI_ValueStruct.Max_Corner); - EncoderRate.encoderRateEnabled = 1; - break; - case 2: // max corner Y - checkkey = MaxCorner_value; - HMI_flag.corner_flag = Y_AXIS; - HMI_ValueStruct.Max_Corner = planner.max_jerk[Y_AXIS] * MINUNITMULT; - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 210, MBASE(select_corner.now), HMI_ValueStruct.Max_Corner); - EncoderRate.encoderRateEnabled = 1; - break; - case 3: // max corner Z - checkkey = MaxCorner_value; - HMI_flag.corner_flag = Z_AXIS; - HMI_ValueStruct.Max_Corner = planner.max_jerk[Z_AXIS] * MINUNITMULT; - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 210, MBASE(select_corner.now), HMI_ValueStruct.Max_Corner); - EncoderRate.encoderRateEnabled = 1; - break; - case 4: // max corner E - checkkey = MaxCorner_value; - HMI_flag.corner_flag = E_AXIS; - HMI_ValueStruct.Max_Corner = planner.max_jerk[E_AXIS] * MINUNITMULT; - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 210, MBASE(select_corner.now), HMI_ValueStruct.Max_Corner); - EncoderRate.encoderRateEnabled = 1; - break; - default: - break; - } - } - DWIN_UpdateLCD(); -} - -/* Step */ -void HMI_Step(void) { - ENCODER_DiffState encoder_diffState = get_encoder_state(); - if (encoder_diffState == ENCODER_DIFF_NO) return; - - // Avoid flicker by updating only the previous menu - if (encoder_diffState == ENCODER_DIFF_CW) { - if (select_step.inc(4)) Move_Highlight(1, select_step.now); - } - else if (encoder_diffState == ENCODER_DIFF_CCW) { - if (select_step.dec()) Move_Highlight(-1, select_step.now); - } - else if (encoder_diffState == ENCODER_DIFF_ENTER) { - switch (select_step.now) { - case 0: // back - checkkey = Motion; - select_motion.now = 4; - Draw_Motion_Menu(); - break; - case 1: // max step X - checkkey = Step_value; - HMI_flag.step_flag = X_AXIS; - HMI_ValueStruct.Max_Step = planner.settings.axis_steps_per_mm[X_AXIS] * MINUNITMULT; - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 210, MBASE(select_step.now), HMI_ValueStruct.Max_Step); - EncoderRate.encoderRateEnabled = 1; - break; - case 2: // max step Y - checkkey = Step_value; - HMI_flag.step_flag = Y_AXIS; - HMI_ValueStruct.Max_Step = planner.settings.axis_steps_per_mm[Y_AXIS] * MINUNITMULT; - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 210, MBASE(select_step.now), HMI_ValueStruct.Max_Step); - EncoderRate.encoderRateEnabled = 1; - break; - case 3: // max step Z - checkkey = Step_value; - HMI_flag.step_flag = Z_AXIS; - HMI_ValueStruct.Max_Step = planner.settings.axis_steps_per_mm[Z_AXIS] * MINUNITMULT; - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 210, MBASE(select_step.now), HMI_ValueStruct.Max_Step); - EncoderRate.encoderRateEnabled = 1; - break; - case 4: // max step E - checkkey = Step_value; - HMI_flag.step_flag = E_AXIS; - HMI_ValueStruct.Max_Step = planner.settings.axis_steps_per_mm[E_AXIS] * MINUNITMULT; - DWIN_Draw_FloatValue(true, true, 0, font8x16, White, Select_Color, 3, 1, 210, MBASE(select_step.now), HMI_ValueStruct.Max_Step); - EncoderRate.encoderRateEnabled = 1; - break; - default: - break; - } - } - DWIN_UpdateLCD(); -} - -void HMI_Init(void) { - HMI_SDCardInit(); - - for (uint16_t t = 0; t <= 100; t += 2) { - DWIN_ICON_Show(ICON, ICON_Bar, 15, 260); - DWIN_Draw_Rectangle(1, Background_black, 15 + t * 242 / 100, 260, 257, 280); - DWIN_UpdateLCD(); - delay(20); - } - - HMI_SetLanguage(); -} - -void DWIN_Update(void) { - EachMomentUpdate(); // Status update - HMI_SDCardUpdate(); // SD card update - DWIN_HandleScreen(); // Rotary encoder update -} - -void EachMomentUpdate(void) { - static millis_t next_rts_update_ms = 0; - const millis_t ms = millis(); - if (PENDING(ms, next_rts_update_ms)) return; - next_rts_update_ms = ms + DWIN_SCROLL_UPDATE_INTERVAL; - - // variable update - update_variable(); - - if (checkkey == PrintProcess) { - // if print done - if (HMI_flag.print_finish && !HMI_flag.confirm_flag) { - HMI_flag.print_finish = 0; - HMI_flag.confirm_flag = 1; - - TERN_(POWER_LOSS_RECOVERY, recovery.cancel()); - - planner.finish_and_disable(); - - // show percent bar and value - Percentrecord = 0; - Draw_Print_ProgressBar(); - - // show print done confirm - DWIN_Draw_Rectangle(1, Background_black, 0, 250, 271, 360); - DWIN_ICON_Show(ICON, HMI_flag.language_chinese ? ICON_Confirm_C : ICON_Confirm_E, 86, 302 - 19); - } - else if (HMI_flag.pause_flag != printingIsPaused()) { - // print status update - HMI_flag.pause_flag = printingIsPaused(); - if (HMI_flag.pause_flag) ICON_Continue(); else ICON_Pause(); - } - } - - // pause after homing - if (pause_action_flag && printingIsPaused() && !planner.has_blocks_queued()) { - pause_action_flag = 0; - #if ENABLED(PAUSE_HEAT) - tempbed = thermalManager.temp_bed.target; - temphot = thermalManager.temp_hotend[0].target; - thermalManager.disable_all_heaters(); - #endif - queue.inject_P(PSTR("G1 F1200 X0 Y0")); - } - - if (card.isPrinting() && checkkey == PrintProcess) { // print process - const uint8_t card_pct = card.percentDone(); - static uint8_t last_cardpercentValue = 101; - if (last_cardpercentValue != card_pct) { // print percent - last_cardpercentValue = card_pct; - if (card_pct) { - Percentrecord = card_pct; - Draw_Print_ProgressBar(); - } - } - - duration_t elapsed = print_job_timer.duration(); // print timer - /* already print time */ - const uint16_t min = (elapsed.value % 3600) / 60; - if (last_Printtime != min) { // 1 minute update - last_Printtime = min; - Draw_Print_ProgressElapsed(); - } - /* remain print time */ - static millis_t next_remain_time_update = 0; - if (elapsed.minute() > 5 && ELAPSED(ms, next_remain_time_update) && HMI_flag.heat_flag == 0) { // show after 5 min and 20s update - remain_time = ((elapsed.value - dwin_heat_time) * ((float)card.getFileSize() / (float)card.getIndex())) - (elapsed.value - dwin_heat_time); - next_remain_time_update += 20 * 1000UL; - Draw_Print_ProgressRemain(); - } - } - else if (abort_flag && !HMI_flag.home_flag) { // Print Stop - abort_flag = 0; - HMI_ValueStruct.print_speed = feedrate_percentage = 100; - zprobe_zoffset = TERN(HAS_BED_PROBE, probe.offset.z, 0); - - planner.finish_and_disable(); - - #if DISABLED(SD_ABORT_NO_COOLDOWN) - thermalManager.disable_all_heaters(); - #endif - - select_page.set(0); - Goto_MainMenu(); - } - else if (DWIN_lcd_sd_status && recovery.dwin_flag) { // resume print before power off - recovery.dwin_flag = false; - - recovery.load(); - if (!recovery.valid()) return recovery.purge(); - - auto draw_first_option = [](const bool sel) { - const uint16_t c1 = sel ? Background_window : Select_Color; - DWIN_Draw_Rectangle(0, c1, 25, 306, 126, 345); - DWIN_Draw_Rectangle(0, c1, 24, 305, 127, 346); - }; - - auto update_selection = [&](const bool sel) { - HMI_flag.select_flag = sel; - draw_first_option(sel); - const uint16_t c2 = sel ? Select_Color : Background_window; - DWIN_Draw_Rectangle(0, c2, 145, 306, 246, 345); - DWIN_Draw_Rectangle(0, c2, 144, 305, 247, 346); - }; - - const uint16_t fileCnt = card.get_num_Files(); - for (uint16_t i = 0; i < fileCnt; i++) { - // TODO: Resume print via M1000 then update the UI - // with the active filename which can come from CardReader. - card.getfilename_sorted(SD_ORDER(i, fileCnt)); - if (!strcmp(card.filename, &recovery.info.sd_filename[1])) { // Resume print before power failure while have the same file - recovery_flag = 1; - HMI_flag.select_flag = 1; - Popup_Window_Resume(); - draw_first_option(false); - char * const name = card.longest_filename(); - const int8_t npos = _MAX(0, DWIN_WIDTH - strlen(name) * (MENU_CHR_W)) / 2; - DWIN_Draw_String(false, true, font8x16, Font_window, Background_window, npos, 252, name); - DWIN_UpdateLCD(); - break; - } - } - - // if hasn't resumable G-code file - if (!recovery_flag) return; - - while (recovery_flag) { - ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - if (encoder_diffState == ENCODER_DIFF_ENTER) { - recovery_flag = 0; - if (HMI_flag.select_flag) break; - TERN_(POWER_LOSS_RECOVERY, recovery.cancel()); - HMI_StartFrame(true); - return; - } - else - update_selection(encoder_diffState == ENCODER_DIFF_CCW); - - DWIN_UpdateLCD(); - } - } - - select_print.set(0); - HMI_ValueStruct.show_mode = 0; - HMI_StartFrame(false); - recovery.resume(); - return; - } - DWIN_UpdateLCD(); -} - -void DWIN_HandleScreen(void) { - switch (checkkey) { - case MainMenu: HMI_MainMenu(); break; - case SelectFile: HMI_SelectFile(); break; - case Prepare: HMI_Prepare(); break; - case Control: HMI_Control(); break; - case Leveling: break; - case PrintProcess: HMI_Printing(); break; - case Print_window: HMI_PauseOrStop(); break; - case AxisMove: HMI_AxisMove(); break; - case TemperatureID: HMI_Temperature(); break; - case Motion: HMI_Motion(); break; - case Info: HMI_Info(); break; - case Tune: HMI_Tune(); break; - case PLAPreheat: HMI_PLAPreheatSetting(); break; - case ABSPreheat: HMI_ABSPreheatSetting(); break; - case MaxSpeed: HMI_MaxSpeed(); break; - case MaxAcceleration: HMI_MaxAcceleration(); break; - case MaxCorner: HMI_MaxCorner(); break; - case Step: HMI_Step(); break; - case Move_X: HMI_Move_X(); break; - case Move_Y: HMI_Move_Y(); break; - case Move_Z: HMI_Move_Z(); break; - #if HAS_HOTEND - case Extruder: HMI_Move_E(); break; - case ETemp: HMI_ETemp(); break; - #endif - case Homeoffset: HMI_Zoffset(); break; - #if HAS_HEATED_BED - case BedTemp: HMI_BedTemp(); break; - #endif - #if HAS_FAN - case FanSpeed: HMI_FanSpeed(); break; - #endif - case PrintSpeed: HMI_PrintSpeed(); break; - case MaxSpeed_value: HMI_MaxFeedspeedXYZE(); break; - case MaxAcceleration_value: HMI_MaxAccelerationXYZE(); break; - case MaxCorner_value: HMI_MaxCornerXYZE(); break; - case Step_value: HMI_StepXYZE(); break; - default: break; - } -} - -void DWIN_CompletedHoming(void) { - HMI_flag.home_flag = false; - if (checkkey == Last_Prepare) { - checkkey = Prepare; - select_prepare.now = 3; - index_prepare = MROWS; - Draw_Prepare_Menu(); - } - else if (checkkey == Back_Main) { - HMI_ValueStruct.print_speed = feedrate_percentage = 100; - zprobe_zoffset = TERN0(BLTOUCH, probe.offset.z); - planner.finish_and_disable(); - Goto_MainMenu(); - } -} - -void DWIN_CompletedLeveling(void) { - if (checkkey == Leveling) Goto_MainMenu(); -} - -#endif // DWIN_CREALITY_LCD diff --git a/Marlin/src/lcd/dwin/dwin_lcd.cpp b/Marlin/src/lcd/dwin/dwin_lcd.cpp index 0ca6b8a3ae..7d1528bed1 100644 --- a/Marlin/src/lcd/dwin/dwin_lcd.cpp +++ b/Marlin/src/lcd/dwin/dwin_lcd.cpp @@ -37,9 +37,12 @@ #include "dwin_lcd.h" #include // for memset -// Make sure DWIN_SendBuf is large enough to hold the largest -// printed string plus the draw command and tail. -uint8_t DWIN_SendBuf[11 + 24] = { 0xAA }; +//#define DEBUG_OUT 1 +#include "../../core/debug_out.h" + +// Make sure DWIN_SendBuf is large enough to hold the largest string plus draw command and tail. +// Assume the narrowest (6 pixel) font and 2-byte gb2312-encoded characters. +uint8_t DWIN_SendBuf[11 + DWIN_WIDTH / 6 * 2] = { 0xAA }; uint8_t DWIN_BufTail[4] = { 0xCC, 0x33, 0xC3, 0x3C }; uint8_t databuf[26] = { 0 }; uint8_t receivedType; @@ -63,7 +66,7 @@ inline void DWIN_Long(size_t &i, const uint32_t lval) { } inline void DWIN_String(size_t &i, char * const string) { - const size_t len = strlen(string); + const size_t len = _MIN(sizeof(DWIN_SendBuf) - i, strlen(string)); memcpy(&DWIN_SendBuf[i+1], string, len); i += len; } @@ -79,10 +82,8 @@ inline void DWIN_String(size_t &i, const __FlashStringHelper * string) { // Send the data in the buffer and the packet end inline void DWIN_Send(size_t &i) { ++i; - LOOP_L_N(n, i) { MYSERIAL1.write(DWIN_SendBuf[n]); - delayMicroseconds(1); } - LOOP_L_N(n, 4) { MYSERIAL1.write(DWIN_BufTail[n]); - delayMicroseconds(1); } + LOOP_L_N(n, i) { MYSERIAL1.write(DWIN_SendBuf[n]); delayMicroseconds(1); } + LOOP_L_N(n, 4) { MYSERIAL1.write(DWIN_BufTail[n]); delayMicroseconds(1); } } /*-------------------------------------- System variable function --------------------------------------*/ @@ -152,6 +153,20 @@ void DWIN_Frame_Clear(const uint16_t color) { DWIN_Send(i); } +// Draw a point +// width: point width 0x01-0x0F +// height: point height 0x01-0x0F +// x,y: upper left point +void DWIN_Draw_Point(uint8_t width, uint8_t height, uint16_t x, uint16_t y) { + size_t i = 0; + DWIN_Byte(i, 0x02); + DWIN_Byte(i, width); + DWIN_Byte(i, height); + DWIN_Word(i, x); + DWIN_Word(i, y); + DWIN_Send(i); +} + // Draw a line // color: Line segment color // xStart/yStart: Start point @@ -185,7 +200,6 @@ void DWIN_Draw_Rectangle(uint8_t mode, uint16_t color, DWIN_Send(i); } -// // Move a screen area // mode: 0, circle shift; 1, translation // dir: 0=left, 1=right, 2=up, 3=down @@ -221,19 +235,10 @@ void DWIN_Draw_String(bool widthAdjust, bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, char *string) { size_t i = 0; DWIN_Byte(i, 0x11); - DWIN_Byte(i, (widthAdjust * 0x80) | (bShow * 0x40) | size); - DWIN_Word(i, color); - DWIN_Word(i, bColor); - DWIN_Word(i, x); - DWIN_Word(i, y); - DWIN_String(i, string); - DWIN_Send(i); -} - -void DWIN_Draw_String(bool widthAdjust, bool bShow, uint8_t size, - uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, const __FlashStringHelper *string) { - size_t i = 0; - DWIN_Byte(i, 0x11); + // Bit 7: widthAdjust + // Bit 6: bShow + // Bit 5-4: Unused (0) + // Bit 3-0: size DWIN_Byte(i, (widthAdjust * 0x80) | (bShow * 0x40) | size); DWIN_Word(i, color); DWIN_Word(i, bColor); @@ -257,6 +262,11 @@ void DWIN_Draw_IntValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, uint16_t value) { size_t i = 0; DWIN_Byte(i, 0x14); + // Bit 7: bshow + // Bit 6: 1 = signed; 0 = unsigned number; + // Bit 5: zeroFill + // Bit 4: zeroMode + // Bit 3-0: size DWIN_Byte(i, (bShow * 0x80) | (zeroFill * 0x20) | (zeroMode * 0x10) | size); DWIN_Word(i, color); DWIN_Word(i, bColor); @@ -343,8 +353,9 @@ void DWIN_ICON_Show(uint8_t libID, uint8_t picID, uint16_t x, uint16_t y) { DWIN_Send(i); } -// Unzip the JPG picture to virtual display area #1 -// id: picture ID +// Unzip the JPG picture to a virtual display area +// n: Cache index +// id: Picture ID void DWIN_JPG_CacheToN(uint8_t n, uint8_t id) { size_t i = 0; DWIN_Byte(i, 0x25); @@ -372,4 +383,73 @@ void DWIN_Frame_AreaCopy(uint8_t cacheID, uint16_t xStart, uint16_t yStart, DWIN_Send(i); } +// Animate a series of icons +// animID: Animation ID; 0x00-0x0F +// animate: true on; false off; +// libID: Icon library ID +// picIDs: Icon starting ID +// picIDe: Icon ending ID +// x/y: Upper-left point +// interval: Display time interval, unit 10mS +void DWIN_ICON_Animation(uint8_t animID, bool animate, uint8_t libID, uint8_t picIDs, uint8_t picIDe, uint16_t x, uint16_t y, uint16_t interval) { + NOMORE(x, DWIN_WIDTH - 1); + NOMORE(y, DWIN_HEIGHT - 1); // -- ozy -- srl + size_t i = 0; + DWIN_Byte(i, 0x28); + DWIN_Word(i, x); + DWIN_Word(i, y); + // Bit 7: animation on or off + // Bit 6: start from begin or end + // Bit 5-4: unused (0) + // Bit 3-0: animID + DWIN_Byte(i, (animate * 0x80) | 0x40 | animID); + DWIN_Byte(i, libID); + DWIN_Byte(i, picIDs); + DWIN_Byte(i, picIDe); + DWIN_Byte(i, interval); + DWIN_Send(i); +} + +// Animation Control +// state: 16 bits, each bit is the state of an animation id +void DWIN_ICON_AnimationControl(uint16_t state) { + size_t i = 0; + DWIN_Byte(i, 0x28); + DWIN_Word(i, state); + DWIN_Send(i); +} + +/*---------------------------------------- Memory functions ----------------------------------------*/ +// The LCD has an additional 32KB SRAM and 16KB Flash + +// Data can be written to the sram and save to one of the jpeg page files + +// Write Data Memory +// command 0x31 +// Type: Write memory selection; 0x5A=SRAM; 0xA5=Flash +// Address: Write data memory address; 0x000-0x7FFF for SRAM; 0x000-0x3FFF for Flash +// Data: data +// +// Flash writing returns 0xA5 0x4F 0x4B + +// Read Data Memory +// command 0x32 +// Type: Read memory selection; 0x5A=SRAM; 0xA5=Flash +// Address: Read data memory address; 0x000-0x7FFF for SRAM; 0x000-0x3FFF for Flash +// Length: leangth of data to read; 0x01-0xF0 +// +// Response: +// Type, Address, Length, Data + +// Write Picture Memory +// Write the contents of the 32KB SRAM data memory into the designated image memory space +// Issued: 0x5A, 0xA5, PIC_ID +// Response: 0xA5 0x4F 0x4B +// +// command 0x33 +// 0x5A, 0xA5 +// PicId: Picture Memory location, 0x00-0x0F +// +// Flash writing returns 0xA5 0x4F 0x4B + #endif // DWIN_CREALITY_LCD diff --git a/Marlin/src/lcd/dwin/dwin_lcd.h b/Marlin/src/lcd/dwin/dwin_lcd.h index 3fae1ccfc9..9ae6d076d5 100644 --- a/Marlin/src/lcd/dwin/dwin_lcd.h +++ b/Marlin/src/lcd/dwin/dwin_lcd.h @@ -42,70 +42,172 @@ #define DWIN_WIDTH 272 #define DWIN_HEIGHT 480 -/*接收数据解析 返回值:true,接收到数据;false,未接收到数据*/ -bool DWIN_ReceiveAnalyze(void); +/*-------------------------------------- System variable function --------------------------------------*/ -/*发送当前BUF中的数据以及包尾数据 len:整包数据长度*/ -void DWIN_Send_BufTail(const uint8_t len); - -/*----------------------------------------------系统变量函数----------------------------------------------*/ -/*握手 1: 握手成功 2: 握手失败*/ +// Handshake (1: Success, 0: Fail) bool DWIN_Handshake(void); -/*设定背光亮度 luminance:亮度(0x00~0xFF)*/ +// Common DWIN startup +void DWIN_Startup(void); + +// Set the backlight luminance +// luminance: (0x00-0xFF) void DWIN_Backlight_SetLuminance(const uint8_t luminance); -/*设定画面显示方向 dir:0,0°; 1,90°; 2,180°; 3,270°*/ +// Set screen display direction +// dir: 0=0°, 1=90°, 2=180°, 3=270° void DWIN_Frame_SetDir(uint8_t dir); -/*更新显示*/ +// Update display void DWIN_UpdateLCD(void); -/*----------------------------------------------绘图相关函数----------------------------------------------*/ -/*画面清屏 color:清屏颜色*/ +/*---------------------------------------- Drawing functions ----------------------------------------*/ + +// Clear screen +// color: Clear screen color void DWIN_Frame_Clear(const uint16_t color); -/*画面画线 color:线段颜色 xStart:X起始坐标 yStart:Y起始坐标 xEnd:X终止坐标 yEnd:Y终止坐标*/ +// Draw a point +// width: point width 0x01-0x0F +// height: point height 0x01-0x0F +// x,y: upper left point +void DWIN_Draw_Point(uint8_t width, uint8_t height, uint16_t x, uint16_t y); + +// Draw a line +// color: Line segment color +// xStart/yStart: Start point +// xEnd/yEnd: End point void DWIN_Draw_Line(uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd); -/*画面画矩形 mode:0,外框;1,填充;2,异或填充 color:颜色 xStart/yStart:矩形左上坐标 xEnd/yEnd:矩形右下坐标*/ +// Draw a Horizontal line +// color: Line segment color +// xStart/yStart: Start point +// xLength: Line Length +inline void DWIN_Draw_HLine(uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xLength) { + DWIN_Draw_Line(color, xStart, yStart, xStart + xLength - 1, yStart); +} + +// Draw a Vertical line +// color: Line segment color +// xStart/yStart: Start point +// yLength: Line Length +inline void DWIN_Draw_VLine(uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t yLength) { + DWIN_Draw_Line(color, xStart, yStart, xStart, yStart + yLength - 1); +} + +// Draw a rectangle +// mode: 0=frame, 1=fill, 2=XOR fill +// color: Rectangle color +// xStart/yStart: upper left point +// xEnd/yEnd: lower right point void DWIN_Draw_Rectangle(uint8_t mode, uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd); -/*画面区域移动 mode:0,环移;1,平移 dir:0,向左移动;1,向右移动;2,向上移动;3,向下移动 dis:移动距离 - color:填充颜色 xStart/yStart:选定区域左上坐标 xEnd/yEnd:选定区域右下坐标*/ +// Draw a box +// mode: 0=frame, 1=fill, 2=XOR fill +// color: Rectangle color +// xStart/yStart: upper left point +// xSize/ySize: box size +inline void DWIN_Draw_Box(uint8_t mode, uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xSize, uint16_t ySize) { + DWIN_Draw_Rectangle(mode, color, xStart, yStart, xStart + xSize - 1, yStart + ySize - 1); +} + +// Move a screen area +// mode: 0, circle shift; 1, translation +// dir: 0=left, 1=right, 2=up, 3=down +// dis: Distance +// color: Fill color +// xStart/yStart: upper left point +// xEnd/yEnd: bottom right point void DWIN_Frame_AreaMove(uint8_t mode, uint8_t dir, uint16_t dis, uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd); -/*----------------------------------------------文本相关函数----------------------------------------------*/ -/*画面显示字符串 widthAdjust:true,自调整字符宽度;false,不调整字符宽度 bShow:true,显示背景色;false,不显示背景色 size:字号大小 - color:字符颜色 bColor:背景颜色 x/y:字符串左上坐标 *string:字符串*/ +/*---------------------------------------- Text related functions ----------------------------------------*/ + +// Draw a string +// widthAdjust: true=self-adjust character width; false=no adjustment +// bShow: true=display background color; false=don't display background color +// size: Font size +// color: Character color +// bColor: Background color +// x/y: Upper-left coordinate of the string +// *string: The string void DWIN_Draw_String(bool widthAdjust, bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, char *string); -/*画面显示正整数 bShow:true,显示背景色;false,不显示背景色 zeroFill:true,补零;false,不补零 zeroMode:1,无效0显示为0; 0,无效0显示为空格 size:字号大小 - color:字符颜色 bColor:背景颜色 iNum:位数 x/y:变量左上坐标 value:整型变量*/ +class __FlashStringHelper; + +inline void DWIN_Draw_String(bool widthAdjust, bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, const __FlashStringHelper *title) { + DWIN_Draw_String(widthAdjust, bShow, size, color, bColor, x, y, (char *)title); +} + +// Draw a positive integer +// bShow: true=display background color; false=don't display background color +// zeroFill: true=zero fill; false=no zero fill +// zeroMode: 1=leading 0 displayed as 0; 0=leading 0 displayed as a space +// size: Font size +// color: Character color +// bColor: Background color +// iNum: Number of digits +// x/y: Upper-left coordinate +// value: Integer value void DWIN_Draw_IntValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, uint16_t value); -/*画面显示浮点数 bShow:true,显示背景色;false,不显示背景色 zeroFill:true,补零;false,不补零 zeroMode:1,无效0显示为0; 0,无效0显示为空格 size:字号大小 - color:字符颜色 bColor:背景颜色 iNum:整数位数 fNum:小数位数 x/y:变量左上坐标 value:浮点数变量*/ +// Draw a floating point number +// bShow: true=display background color; false=don't display background color +// zeroFill: true=zero fill; false=no zero fill +// zeroMode: 1=leading 0 displayed as 0; 0=leading 0 displayed as a space +// size: Font size +// color: Character color +// bColor: Background color +// iNum: Number of whole digits +// fNum: Number of decimal digits +// x/y: Upper-left point +// value: Float value void DWIN_Draw_FloatValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value); -/*----------------------------------------------图片相关函数----------------------------------------------*/ -/*jpg图片显示并缓存在#0虚拟显示区 id:图片ID*/ +/*---------------------------------------- Picture related functions ----------------------------------------*/ + +// Draw JPG and cached in #0 virtual display area +// id: Picture ID void DWIN_JPG_ShowAndCache(const uint8_t id); -/*图标显示 libID:图标库ID picID:图标ID x/y:图标左上坐标*/ +// Draw an Icon +// libID: Icon library ID +// picID: Icon ID +// x/y: Upper-left point void DWIN_ICON_Show(uint8_t libID, uint8_t picID, uint16_t x, uint16_t y); -/*jpg图片解压到#1虚拟显示区 id:图片ID*/ +// Unzip the JPG picture to a virtual display area +// n: Cache index +// id: Picture ID void DWIN_JPG_CacheToN(uint8_t n, uint8_t id); -/*jpg图片解压到#1虚拟显示区 id:图片ID*/ +// Unzip the JPG picture to virtual display area #1 +// id: Picture ID inline void DWIN_JPG_CacheTo1(uint8_t id) { DWIN_JPG_CacheToN(1, id); } -/*从虚拟显示区复制区域至当前画面 cacheID:虚拟区号 xStart/yStart:虚拟区左上坐标 xEnd/yEnd:虚拟区右下坐标 x/y:当前画面粘贴坐标*/ +// Copy area from virtual display area to current screen +// cacheID: virtual area number +// xStart/yStart: Upper-left of virtual area +// xEnd/yEnd: Lower-right of virtual area +// x/y: Screen paste point void DWIN_Frame_AreaCopy(uint8_t cacheID, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd, uint16_t x, uint16_t y); + +// Animate a series of icons +// animID: Animation ID up to 16 +// animate: animation on or off +// libID: Icon library ID +// picIDs: Icon starting ID +// picIDe: Icon ending ID +// x/y: Upper-left point +// interval: Display time interval, unit 10mS +void DWIN_ICON_Animation(uint8_t animID, bool animate, uint8_t libID, uint8_t picIDs, + uint8_t picIDe, uint16_t x, uint16_t y, uint16_t interval); + +// Animation Control +// state: 16 bits, each bit is the state of an animation id +void DWIN_ICON_AnimationControl(uint16_t state); diff --git a/Marlin/src/lcd/dwin/README.md b/Marlin/src/lcd/dwin/e3v2/README.md similarity index 100% rename from Marlin/src/lcd/dwin/README.md rename to Marlin/src/lcd/dwin/e3v2/README.md diff --git a/Marlin/src/lcd/dwin/e3v2/dwin.cpp b/Marlin/src/lcd/dwin/e3v2/dwin.cpp new file mode 100644 index 0000000000..85263a89ab --- /dev/null +++ b/Marlin/src/lcd/dwin/e3v2/dwin.cpp @@ -0,0 +1,3719 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * DWIN by Creality3D + */ + +#include "../../../inc/MarlinConfigPre.h" + +#if ENABLED(DWIN_CREALITY_LCD) + +#include "dwin.h" + +#if ANY(AUTO_BED_LEVELING_BILINEAR, AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_3POINT) && DISABLED(PROBE_MANUALLY) + #define HAS_ONESTEP_LEVELING 1 +#endif + +#if ANY(BABYSTEPPING, HAS_BED_PROBE, HAS_WORKSPACE_OFFSET) + #define HAS_ZOFFSET_ITEM 1 +#endif + +#if !HAS_BED_PROBE && ENABLED(BABYSTEPPING) + #define JUST_BABYSTEP 1 +#endif + +#include +#include +#include + +#include "../../fontutils.h" +#include "../../ultralcd.h" + +#include "../../../sd/cardreader.h" + +#include "../../../MarlinCore.h" +#include "../../../core/serial.h" +#include "../../../core/macros.h" +#include "../../../gcode/queue.h" + +#include "../../../module/temperature.h" +#include "../../../module/printcounter.h" +#include "../../../module/motion.h" +#include "../../../module/planner.h" + +#if ENABLED(EEPROM_SETTINGS) + #include "../../../module/settings.h" +#endif + +#if ENABLED(HOST_ACTION_COMMANDS) + #include "../../../feature/host_actions.h" +#endif + +#if HAS_ONESTEP_LEVELING + #include "../../../feature/bedlevel/bedlevel.h" +#endif + +#if HAS_BED_PROBE + #include "../../../module/probe.h" +#endif + +#if EITHER(BABYSTEP_ZPROBE_OFFSET, JUST_BABYSTEP) + #include "../../../feature/babystep.h" +#endif + +#if ENABLED(POWER_LOSS_RECOVERY) + #include "../../../feature/powerloss.h" +#endif + +#ifndef MACHINE_SIZE + #define MACHINE_SIZE "220x220x250" +#endif +#ifndef CORP_WEBSITE_C + #define CORP_WEBSITE_C "www.cxsw3d.com" +#endif +#ifndef CORP_WEBSITE_E + #define CORP_WEBSITE_E "www.creality.com" +#endif + +#define PAUSE_HEAT + +#define USE_STRING_HEADINGS + +#define DWIN_FONT_MENU font8x16 +#define DWIN_FONT_STAT font10x20 +#define DWIN_FONT_HEAD font10x20 + +#define MENU_CHAR_LIMIT 24 +#define STATUS_Y 360 + +// Fan speed limit +#define FANON 255 +#define FANOFF 0 + +// Print speed limit +#define MAX_PRINT_SPEED 999 +#define MIN_PRINT_SPEED 10 + +// Temp limits +#if HAS_HOTEND + #define MAX_E_TEMP (HEATER_0_MAXTEMP - (HOTEND_OVERSHOOT)) + #define MIN_E_TEMP HEATER_0_MINTEMP +#endif + +#if HAS_HEATED_BED + #define MIN_BED_TEMP BED_MINTEMP +#endif + +// Feedspeed limit (max feedspeed = DEFAULT_MAX_FEEDRATE * 2) +#define MIN_MAXFEEDSPEED 1 +#define MIN_MAXACCELERATION 1 +#define MIN_MAXJERK 0.1 +#define MIN_STEP 1 + +#define FEEDRATE_E (60) + +// Mininum unit (0.1) : multiple (10) +#define MINUNITMULT 10 + +#define ENCODER_WAIT 20 +#define DWIN_SCROLL_UPDATE_INTERVAL 2000 +#define DWIN_REMAIN_TIME_UPDATE_INTERVAL 20000 + +constexpr uint16_t TROWS = 6, MROWS = TROWS - 1, // Total rows, and other-than-Back + TITLE_HEIGHT = 30, // Title bar height + MLINE = 53, // Menu line height + LBLX = 60, // Menu item label X + MENU_CHR_W = 8, STAT_CHR_W = 10; + +#define MBASE(L) (49 + MLINE * (L)) + +#define BABY_Z_VAR TERN(HAS_BED_PROBE, probe.offset.z, dwin_zoffset) + +/* Value Init */ +HMI_value_t HMI_ValueStruct; +HMI_Flag_t HMI_flag{0}; + +millis_t dwin_heat_time = 0; + +uint8_t checkkey = 0; + +typedef struct { + uint8_t now, last; + void set(uint8_t v) { now = last = v; } + void reset() { set(0); } + bool changed() { bool c = (now != last); if (c) last = now; return c; } + bool dec() { if (now) now--; return changed(); } + bool inc(uint8_t v) { if (now < (v - 1)) now++; else now = (v - 1); return changed(); } +} select_t; + +select_t select_page{0}, select_file{0}, select_print{0}, select_prepare{0} + , select_control{0}, select_axis{0}, select_temp{0}, select_motion{0}, select_tune{0} + , select_PLA{0}, select_ABS{0} + , select_speed{0} + , select_acc{0} + , select_jerk{0} + , select_step{0} + ; + +uint8_t index_file = MROWS, + index_prepare = MROWS, + index_control = MROWS, + index_leveling = MROWS, + index_tune = MROWS; + +bool dwin_abort_flag = false; + +constexpr float default_max_feedrate[] = DEFAULT_MAX_FEEDRATE; +constexpr float default_max_acceleration[] = DEFAULT_MAX_ACCELERATION; +constexpr float default_max_jerk[] = { DEFAULT_XJERK, DEFAULT_YJERK, DEFAULT_ZJERK, DEFAULT_EJERK }; +constexpr float default_axis_steps_per_unit[] = DEFAULT_AXIS_STEPS_PER_UNIT; + +uint8_t Percentrecord = 0; +uint16_t remain_time = 0; + +#if ENABLED(PAUSE_HEAT) + #if HAS_HOTEND + uint16_t temphot = 0; + #endif + #if HAS_HEATED_BED + uint16_t tempbed = 0; + #endif +#endif + +#if HAS_ZOFFSET_ITEM + float dwin_zoffset = 0, last_zoffset = 0; +#endif + +#define DWIN_LANGUAGE_EEPROM_ADDRESS 0x01 // Between 0x01 and 0x63 (EEPROM_OFFSET-1) + // BL24CXX::check() uses 0x00 + +inline bool HMI_IsChinese() { return HMI_flag.language == DWIN_CHINESE; } + +void HMI_SetLanguageCache() { + DWIN_JPG_CacheTo1(HMI_IsChinese() ? Language_Chinese : Language_English); +} + +void HMI_SetLanguage() { + #if ENABLED(EEPROM_SETTINGS) + BL24CXX::read(DWIN_LANGUAGE_EEPROM_ADDRESS, (uint8_t*)&HMI_flag.language, sizeof(HMI_flag.language)); + #endif + HMI_SetLanguageCache(); +} + +void HMI_ToggleLanguage() { + HMI_flag.language = HMI_IsChinese() ? DWIN_ENGLISH : DWIN_CHINESE; + HMI_SetLanguageCache(); + #if ENABLED(EEPROM_SETTINGS) + BL24CXX::write(DWIN_LANGUAGE_EEPROM_ADDRESS, (uint8_t*)&HMI_flag.language, sizeof(HMI_flag.language)); + #endif +} + +void DWIN_Draw_Signed_Float(uint8_t size, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value) { + if (value < 0) { + DWIN_Draw_String(false, true, size, Color_White, bColor, x - 6, y, F("-")); + DWIN_Draw_FloatValue(true, true, 0, size, Color_White, bColor, iNum, fNum, x, y, -value); + } + else { + DWIN_Draw_String(false, true, size, Color_White, bColor, x - 6, y, F(" ")); + DWIN_Draw_FloatValue(true, true, 0, size, Color_White, bColor, iNum, fNum, x, y, value); + } +} + +void ICON_Print() { + if (select_page.now == 0) { + DWIN_ICON_Show(ICON, ICON_Print_1, 17, 130); + DWIN_Draw_Rectangle(0, Color_White, 17, 130, 126, 229); + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 1, 447, 28, 460, 58, 201); + else + DWIN_Frame_AreaCopy(1, 1, 451, 31, 463, 57, 201); + } + else { + DWIN_ICON_Show(ICON, ICON_Print_0, 17, 130); + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 1, 405, 28, 420, 58, 201); + else + DWIN_Frame_AreaCopy(1, 1, 423, 31, 435, 57, 201); + } +} + +void ICON_Prepare() { + if (select_page.now == 1) { + DWIN_ICON_Show(ICON, ICON_Prepare_1, 145, 130); + DWIN_Draw_Rectangle(0, Color_White, 145, 130, 254, 229); + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 31, 447, 58, 460, 186, 201); + else + DWIN_Frame_AreaCopy(1, 33, 451, 82, 466, 175, 201); + } + else { + DWIN_ICON_Show(ICON, ICON_Prepare_0, 145, 130); + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 31, 405, 58, 420, 186, 201); + else + DWIN_Frame_AreaCopy(1, 33, 423, 82, 438, 175, 201); + } +} + +void ICON_Control() { + if (select_page.now == 2) { + DWIN_ICON_Show(ICON, ICON_Control_1, 17, 246); + DWIN_Draw_Rectangle(0, Color_White, 17, 246, 126, 345); + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 61, 447, 88, 460, 58, 318); + else + DWIN_Frame_AreaCopy(1, 85, 451, 132, 463, 48, 318); + } + else { + DWIN_ICON_Show(ICON, ICON_Control_0, 17, 246); + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 61, 405, 88, 420, 58, 318); + else + DWIN_Frame_AreaCopy(1, 85, 423, 132, 434, 48, 318); + } +} + +void ICON_StartInfo(bool show) { + if (show) { + DWIN_ICON_Show(ICON, ICON_Info_1, 145, 246); + DWIN_Draw_Rectangle(0, Color_White, 145, 246, 254, 345); + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 91, 447, 118, 460, 186, 318); + else + DWIN_Frame_AreaCopy(1, 132, 451, 159, 466, 186, 318); + } + else { + DWIN_ICON_Show(ICON, ICON_Info_0, 145, 246); + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 91, 405, 118, 420, 186, 318); + else + DWIN_Frame_AreaCopy(1, 132, 423, 159, 435, 186, 318); + } +} + +void ICON_Leveling(bool show) { + if (show) { + DWIN_ICON_Show(ICON, ICON_Leveling_1, 145, 246); + DWIN_Draw_Rectangle(0, Color_White, 145, 246, 254, 345); + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 211, 447, 238, 460, 186, 318); + else + DWIN_Frame_AreaCopy(1, 84, 437, 120, 449, 182, 318); + } + else { + DWIN_ICON_Show(ICON, ICON_Leveling_0, 145, 246); + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 211, 405, 238, 420, 186, 318); + else + DWIN_Frame_AreaCopy(1, 84, 465, 120, 478, 182, 318); + } +} + +void ICON_Tune() { + if (select_print.now == 0) { + DWIN_ICON_Show(ICON, ICON_Setup_1, 8, 252); + DWIN_Draw_Rectangle(0, Color_White, 8, 252, 87, 351); + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 121, 447, 148, 458, 34, 325); + else + DWIN_Frame_AreaCopy(1, 0, 466, 34, 476, 31, 325); + } + else { + DWIN_ICON_Show(ICON, ICON_Setup_0, 8, 252); + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 121, 405, 148, 420, 34, 325); + else + DWIN_Frame_AreaCopy(1, 0, 438, 32, 448, 31, 325); + } +} + +void ICON_Pause() { + if (select_print.now == 1) { + DWIN_ICON_Show(ICON, ICON_Pause_1, 96, 252); + DWIN_Draw_Rectangle(0, Color_White, 96, 252, 175, 351); + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 181, 447, 208, 459, 124, 325); + else + DWIN_Frame_AreaCopy(1, 177, 451, 216, 462, 116, 325); + } + else { + DWIN_ICON_Show(ICON, ICON_Pause_0, 96, 252); + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 181, 405, 208, 420, 124, 325); + else + DWIN_Frame_AreaCopy(1, 177, 423, 215, 433, 116, 325); + } +} + +void ICON_Continue() { + if (select_print.now == 1) { + DWIN_ICON_Show(ICON, ICON_Continue_1, 96, 252); + DWIN_Draw_Rectangle(0, Color_White, 96, 252, 175, 351); + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 1, 447, 28, 460, 124, 325); + else + DWIN_Frame_AreaCopy(1, 1, 452, 32, 464, 121, 325); + } + else { + DWIN_ICON_Show(ICON, ICON_Continue_0, 96, 252); + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 1, 405, 28, 420, 124, 325); + else + DWIN_Frame_AreaCopy(1, 1, 424, 31, 434, 121, 325); + } +} + +void ICON_Stop() { + if (select_print.now == 2) { + DWIN_ICON_Show(ICON, ICON_Stop_1, 184, 252); + DWIN_Draw_Rectangle(0, Color_White, 184, 252, 263, 351); + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 151, 447, 178, 459, 210, 325); + else + DWIN_Frame_AreaCopy(1, 218, 452, 249, 466, 209, 325); + } + else { + DWIN_ICON_Show(ICON, ICON_Stop_0, 184, 252); + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 151, 405, 178, 420, 210, 325); + else + DWIN_Frame_AreaCopy(1, 218, 423, 247, 436, 209, 325); + } +} + +inline void Clear_Title_Bar() { + DWIN_Draw_Rectangle(1, Color_Bg_Blue, 0, 0, DWIN_WIDTH, 30); +} + +inline void Draw_Title(const char * const title) { + DWIN_Draw_String(false, false, DWIN_FONT_HEAD, Color_White, Color_Bg_Blue, 14, 4, (char*)title); +} + +inline void Draw_Title(const __FlashStringHelper * title) { + DWIN_Draw_String(false, false, DWIN_FONT_HEAD, Color_White, Color_Bg_Blue, 14, 4, (char*)title); +} + +inline void Clear_Menu_Area() { + DWIN_Draw_Rectangle(1, Color_Bg_Black, 0, 31, DWIN_WIDTH, STATUS_Y); +} + +inline void Clear_Main_Window() { + Clear_Title_Bar(); + Clear_Menu_Area(); +} + +inline void Clear_Popup_Area() { + Clear_Title_Bar(); + DWIN_Draw_Rectangle(1, Color_Bg_Black, 0, 31, DWIN_WIDTH, DWIN_HEIGHT); +} + +void Draw_Popup_Bkgd_105() { + DWIN_Draw_Rectangle(1, Color_Bg_Window, 14, 105, 258, 374); +} + +inline void Draw_More_Icon(const uint8_t line) { + DWIN_ICON_Show(ICON, ICON_More, 226, MBASE(line) - 3); +} + +inline void Draw_Menu_Cursor(const uint8_t line) { + // DWIN_ICON_Show(ICON,ICON_Rectangle, 0, MBASE(line) - 18); + DWIN_Draw_Rectangle(1, Rectangle_Color, 0, MBASE(line) - 18, 14, MBASE(line + 1) - 20); +} + +inline void Erase_Menu_Cursor(const uint8_t line) { + DWIN_Draw_Rectangle(1, Color_Bg_Black, 0, MBASE(line) - 18, 14, MBASE(line + 1) - 20); +} + +inline void Move_Highlight(const int16_t from, const uint16_t newline) { + Erase_Menu_Cursor(newline - from); + Draw_Menu_Cursor(newline); +} + +inline void Add_Menu_Line() { + Move_Highlight(1, MROWS); + DWIN_Draw_Line(Line_Color, 16, MBASE(MROWS + 1) - 20, 256, MBASE(MROWS + 1) - 19); +} + +inline void Scroll_Menu(const uint8_t dir) { + DWIN_Frame_AreaMove(1, dir, MLINE, Color_Bg_Black, 0, 31, DWIN_WIDTH, 349); + switch (dir) { + case DWIN_SCROLL_DOWN: Move_Highlight(-1, 0); break; + case DWIN_SCROLL_UP: Add_Menu_Line(); break; + } +} + +inline uint16_t nr_sd_menu_items() { + return card.get_num_Files() + !card.flag.workDirIsRoot; +} + +inline void Draw_Menu_Icon(const uint8_t line, const uint8_t icon) { + DWIN_ICON_Show(ICON, icon, 26, MBASE(line) - 3); +} + +inline void Erase_Menu_Text(const uint8_t line) { + DWIN_Draw_Rectangle(1, Color_Bg_Black, LBLX, MBASE(line) - 14, 271, MBASE(line) + 28); +} + +inline void Draw_Menu_Line(const uint8_t line, const uint8_t icon=0, const char * const label=nullptr) { + if (label) DWIN_Draw_String(false, false, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(line) - 1, (char*)label); + if (icon) Draw_Menu_Icon(line, icon); + DWIN_Draw_Line(Line_Color, 16, MBASE(line) + 33, 256, MBASE(line) + 34); +} + +// The "Back" label is always on the first line +inline void Draw_Back_Label() { + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 129, 72, 156, 84, LBLX, MBASE(0)); + else + DWIN_Frame_AreaCopy(1, 226, 179, 256, 189, LBLX, MBASE(0)); +} + +// Draw "Back" line at the top +inline void Draw_Back_First(const bool is_sel=true) { + Draw_Menu_Line(0, ICON_Back); + Draw_Back_Label(); + if (is_sel) Draw_Menu_Cursor(0); +} + +inline bool Apply_Encoder(const ENCODER_DiffState &encoder_diffState, auto &valref) { + if (encoder_diffState == ENCODER_DIFF_CW) + valref += EncoderRate.encoderMoveValue; + else if (encoder_diffState == ENCODER_DIFF_CCW) + valref -= EncoderRate.encoderMoveValue; + else if (encoder_diffState == ENCODER_DIFF_ENTER) + return true; + return false; +} + +// +// Draw Menus +// + +#define MOTION_CASE_RATE 1 +#define MOTION_CASE_ACCEL 2 +#define MOTION_CASE_JERK (MOTION_CASE_ACCEL + ENABLED(HAS_CLASSIC_JERK)) +#define MOTION_CASE_STEPS (MOTION_CASE_JERK + 1) +#define MOTION_CASE_TOTAL MOTION_CASE_STEPS + +#define PREPARE_CASE_MOVE 1 +#define PREPARE_CASE_DISA 2 +#define PREPARE_CASE_HOME 3 +#define PREPARE_CASE_ZOFF (PREPARE_CASE_HOME + ENABLED(HAS_ZOFFSET_ITEM)) +#define PREPARE_CASE_PLA (PREPARE_CASE_ZOFF + ENABLED(HAS_HOTEND)) +#define PREPARE_CASE_ABS (PREPARE_CASE_PLA + ENABLED(HAS_HOTEND)) +#define PREPARE_CASE_COOL (PREPARE_CASE_ABS + EITHER(HAS_HOTEND, HAS_HEATED_BED)) +#define PREPARE_CASE_LANG (PREPARE_CASE_COOL + 1) +#define PREPARE_CASE_TOTAL PREPARE_CASE_LANG + +#define CONTROL_CASE_TEMP 1 +#define CONTROL_CASE_MOVE (CONTROL_CASE_TEMP + 1) +#define CONTROL_CASE_SAVE (CONTROL_CASE_MOVE + ENABLED(EEPROM_SETTINGS)) +#define CONTROL_CASE_LOAD (CONTROL_CASE_SAVE + ENABLED(EEPROM_SETTINGS)) +#define CONTROL_CASE_RESET (CONTROL_CASE_LOAD + ENABLED(EEPROM_SETTINGS)) +#define CONTROL_CASE_INFO (CONTROL_CASE_RESET + 1) +#define CONTROL_CASE_TOTAL CONTROL_CASE_INFO + +#define TUNE_CASE_SPEED 1 +#define TUNE_CASE_TEMP (TUNE_CASE_SPEED + ENABLED(HAS_HOTEND)) +#define TUNE_CASE_BED (TUNE_CASE_TEMP + ENABLED(HAS_HEATED_BED)) +#define TUNE_CASE_FAN (TUNE_CASE_BED + ENABLED(HAS_FAN)) +#define TUNE_CASE_ZOFF (TUNE_CASE_FAN + ENABLED(HAS_ZOFFSET_ITEM)) +#define TUNE_CASE_TOTAL TUNE_CASE_ZOFF + +#define TEMP_CASE_TEMP (0 + ENABLED(HAS_HOTEND)) +#define TEMP_CASE_BED (TEMP_CASE_TEMP + ENABLED(HAS_HEATED_BED)) +#define TEMP_CASE_FAN (TEMP_CASE_BED + ENABLED(HAS_FAN)) +#define TEMP_CASE_PLA (TEMP_CASE_FAN + ENABLED(HAS_HOTEND)) +#define TEMP_CASE_ABS (TEMP_CASE_PLA + ENABLED(HAS_HOTEND)) +#define TEMP_CASE_TOTAL TEMP_CASE_ABS + +#define PREHEAT_CASE_TEMP (0 + ENABLED(HAS_HOTEND)) +#define PREHEAT_CASE_BED (PREHEAT_CASE_TEMP + ENABLED(HAS_HEATED_BED)) +#define PREHEAT_CASE_FAN (PREHEAT_CASE_BED + ENABLED(HAS_FAN)) +#define PREHEAT_CASE_SAVE (PREHEAT_CASE_FAN + ENABLED(EEPROM_SETTINGS)) +#define PREHEAT_CASE_TOTAL PREHEAT_CASE_SAVE + +// +// Draw Menus +// + +inline void draw_move_en(const uint16_t line) { + DWIN_Frame_AreaCopy(1, 69, 61, 102, 71, LBLX, line); // "Move" +} + +inline void DWIN_Frame_TitleCopy(uint8_t id, uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2) { DWIN_Frame_AreaCopy(id, x1, y1, x2, y2, 14, 8); } + +inline void Item_Prepare_Move(const uint8_t row) { + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 159, 70, 200, 84, LBLX, MBASE(row)); + else + draw_move_en(MBASE(row)); // "Move >" + Draw_Menu_Line(row, ICON_Axis); + Draw_More_Icon(row); +} + +inline void Item_Prepare_Disable(const uint8_t row) { + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 204, 70, 259, 82, LBLX, MBASE(row)); + else + DWIN_Frame_AreaCopy(1, 103, 59, 200, 74, LBLX, MBASE(row)); // "Disable Stepper" + Draw_Menu_Line(row, ICON_CloseMotor); +} + +inline void Item_Prepare_Home(const uint8_t row) { + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 0, 89, 41, 101, LBLX, MBASE(row)); + else + DWIN_Frame_AreaCopy(1, 202, 61, 271, 71, LBLX, MBASE(row)); // "Auto Home" + Draw_Menu_Line(row, ICON_Homing); +} + +#if HAS_ZOFFSET_ITEM + + inline void Item_Prepare_Offset(const uint8_t row) { + if (HMI_IsChinese()) { + #if HAS_BED_PROBE + DWIN_Frame_AreaCopy(1, 174, 164, 223, 177, LBLX, MBASE(row)); + DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 2, 2, 202, MBASE(row), BABY_Z_VAR * 100); + #else + DWIN_Frame_AreaCopy(1, 43, 89, 98, 101, LBLX, MBASE(row)); + #endif + } + else { + #if HAS_BED_PROBE + DWIN_Frame_AreaCopy(1, 93, 179, 141, 189, LBLX, MBASE(row)); // "Z-Offset" + DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 2, 2, 202, MBASE(row), BABY_Z_VAR * 100); + #else + DWIN_Frame_AreaCopy(1, 1, 76, 106, 86, LBLX, MBASE(row)); // "..." + #endif + } + Draw_Menu_Line(row, ICON_SetHome); + } + +#endif + +#if HAS_HOTEND + inline void Item_Prepare_PLA(const uint8_t row) { + if (HMI_IsChinese()) { + DWIN_Frame_AreaCopy(1, 100, 89, 151, 101, LBLX, MBASE(row)); + } + else { + DWIN_Frame_AreaCopy(1, 107, 76, 156, 86, LBLX, MBASE(row)); // "Preheat" + DWIN_Frame_AreaCopy(1, 157, 76, 181, 86, LBLX + 52, MBASE(row)); // "PLA" + } + Draw_Menu_Line(row, ICON_PLAPreheat); + } + + inline void Item_Prepare_ABS(const uint8_t row) { + if (HMI_IsChinese()) { + DWIN_Frame_AreaCopy(1, 180, 89, 233, 100, LBLX, MBASE(row)); + } + else { + DWIN_Frame_AreaCopy(1, 107, 76, 156, 86, LBLX, MBASE(row)); // "Preheat" + DWIN_Frame_AreaCopy(1, 172, 76, 198, 86, LBLX + 52, MBASE(row)); // "ABS" + } + Draw_Menu_Line(row, ICON_ABSPreheat); + } +#endif + +#if HAS_PREHEAT + inline void Item_Prepare_Cool(const uint8_t row) { + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 1, 104, 56, 117, LBLX, MBASE(row)); + else + DWIN_Frame_AreaCopy(1, 200, 76, 264, 86, LBLX, MBASE(row)); // "Cooldown" + Draw_Menu_Line(row, ICON_Cool); + } +#endif + +inline void Item_Prepare_Lang(const uint8_t row) { + if (HMI_IsChinese()) { + DWIN_Frame_AreaCopy(1, 239, 134, 266, 146, LBLX, MBASE(row)); + DWIN_Draw_String(false, false, font8x16, Color_White, Color_Bg_Black, 226, MBASE(row), F("CN")); + } + else { + DWIN_Frame_AreaCopy(1, 0, 194, 121, 207, LBLX, MBASE(row)); // "Language selection" + DWIN_Draw_String(false, false, font8x16, Color_White, Color_Bg_Black, 226, MBASE(row), F("EN")); + } + Draw_Menu_Icon(row, ICON_Language); +} + +inline void Draw_Prepare_Menu() { + Clear_Main_Window(); + + const int16_t scroll = MROWS - index_prepare; // Scrolled-up lines + #define PSCROL(L) (scroll + (L)) + #define PVISI(L) WITHIN(PSCROL(L), 0, MROWS) + + if (HMI_IsChinese()) { + DWIN_Frame_TitleCopy(1, 133, 1, 160, 13); // "Prepare" + } + else { + #ifdef USE_STRING_HEADINGS + Draw_Title(GET_TEXT_F(MSG_PREPARE)); + #else + DWIN_Frame_TitleCopy(1, 178, 2, 229, 14); // "Prepare" + #endif + } + + if (PVISI(0)) Draw_Back_First(select_prepare.now == 0); // < Back + if (PVISI(PREPARE_CASE_MOVE)) Item_Prepare_Move(PSCROL(PREPARE_CASE_MOVE)); // Move > + if (PVISI(PREPARE_CASE_DISA)) Item_Prepare_Disable(PSCROL(PREPARE_CASE_DISA)); // Disable Stepper + if (PVISI(PREPARE_CASE_HOME)) Item_Prepare_Home(PSCROL(PREPARE_CASE_HOME)); // Auto Home + #if HAS_ZOFFSET_ITEM + if (PVISI(PREPARE_CASE_ZOFF)) Item_Prepare_Offset(PSCROL(PREPARE_CASE_ZOFF)); // Edit Z-Offset / Babystep / Set Home Offset + #endif + #if HAS_HOTEND + if (PVISI(PREPARE_CASE_PLA)) Item_Prepare_PLA(PSCROL(PREPARE_CASE_PLA)); // Preheat PLA + if (PVISI(PREPARE_CASE_ABS)) Item_Prepare_ABS(PSCROL(PREPARE_CASE_ABS)); // Preheat ABS + #endif + #if HAS_PREHEAT + if (PVISI(PREPARE_CASE_COOL)) Item_Prepare_Cool(PSCROL(PREPARE_CASE_COOL)); // Cooldown + #endif + if (PVISI(PREPARE_CASE_LANG)) Item_Prepare_Lang(PSCROL(PREPARE_CASE_LANG)); // Language CN/EN + + if (select_prepare.now) Draw_Menu_Cursor(PSCROL(select_prepare.now)); +} + +inline void Draw_Control_Menu() { + Clear_Main_Window(); + + #if CONTROL_CASE_TOTAL >= 6 + const int16_t scroll = MROWS - index_control; // Scrolled-up lines + #define CSCROL(L) (scroll + (L)) + #else + #define CSCROL(L) (L) + #endif + #define CLINE(L) MBASE(CSCROL(L)) + #define CVISI(L) WITHIN(CSCROL(L), 0, MROWS) + + if (CVISI(0)) Draw_Back_First(select_control.now == 0); // < Back + + if (HMI_IsChinese()) { + DWIN_Frame_TitleCopy(1, 103, 1, 130, 14); // "Control" + + DWIN_Frame_AreaCopy(1, 57, 104, 84, 116, LBLX, CLINE(CONTROL_CASE_TEMP)); // Temperature > + DWIN_Frame_AreaCopy(1, 87, 104, 114, 116, LBLX, CLINE(CONTROL_CASE_MOVE)); // Motion > + + #if ENABLED(EEPROM_SETTINGS) + DWIN_Frame_AreaCopy(1, 117, 104, 172, 116, LBLX, CLINE(CONTROL_CASE_SAVE)); // Store Configuration + DWIN_Frame_AreaCopy(1, 174, 103, 229, 116, LBLX, CLINE(CONTROL_CASE_LOAD)); // Read Configuration + DWIN_Frame_AreaCopy(1, 1, 118, 56, 131, LBLX, CLINE(CONTROL_CASE_RESET)); // Reset Configuration + #endif + + if (CVISI(CONTROL_CASE_INFO)) + DWIN_Frame_AreaCopy(1, 231, 104, 258, 116, LBLX, CLINE(CONTROL_CASE_TEMP)); // Info > + } + else { + #ifdef USE_STRING_HEADINGS + Draw_Title(GET_TEXT_F(MSG_CONTROL)); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(CONTROL_CASE_TEMP), GET_TEXT_F(MSG_TEMPERATURE)); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(CONTROL_CASE_MOVE), GET_TEXT_F(MSG_MOTION)); + #if ENABLED(EEPROM_SETTINGS) + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(CONTROL_CASE_SAVE), GET_TEXT_F(MSG_STORE_EEPROM)); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(CONTROL_CASE_LOAD), GET_TEXT_F(MSG_LOAD_EEPROM)); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(CONTROL_CASE_RESET), GET_TEXT_F(MSG_RESTORE_DEFAULTS)); + #endif + if (CVISI(CONTROL_CASE_INFO)) DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(CONTROL_CASE_INFO), F("Info")); + #else + DWIN_Frame_TitleCopy(1, 128, 2, 176, 12); // "Control" + DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX, CLINE(CONTROL_CASE_TEMP)); // Temperature > + DWIN_Frame_AreaCopy(1, 84, 89, 128, 99, LBLX, CLINE(CONTROL_CASE_MOVE)); // Motion > + #if ENABLED(EEPROM_SETTINGS) + DWIN_Frame_AreaCopy(1, 148, 89, 268, 101, LBLX , CLINE(CONTROL_CASE_SAVE // "Store Configuration" + DWIN_Frame_AreaCopy(1, 26, 104, 57, 114, LBLX , CLINE(CONTROL_CASE_LOAD)); // "Read" + DWIN_Frame_AreaCopy(1, 182, 89, 268, 101, LBLX + 34, CLINE(CONTROL_CASE_LOAD)); // "Configuration" + DWIN_Frame_AreaCopy(1, 59, 104, 93, 114, LBLX , CLINE(CONTROL_CASE_RESET)); // "Reset" + DWIN_Frame_AreaCopy(1, 182, 89, 268, 101, LBLX + 37, CLINE(CONTROL_CASE_RESET)); // "Configuration" + #endif + if (CVISI(CONTROL_CASE_INFO)) DWIN_Frame_AreaCopy(1, 0, 104, 25, 115, LBLX, CLINE(CONTROL_CASE_INFO)); // Info > + #endif + } + + if (select_control.now && CVISI(select_control.now)) + Draw_Menu_Cursor(CSCROL(select_control.now)); + + // Draw icons and lines + uint8_t i = 0; + #define _TEMP_ICON(N) do{ ++i; if (CVISI(i)) Draw_Menu_Line(CSCROL(i), ICON_Temperature + (N) - 1); }while(0) + + _TEMP_ICON(CONTROL_CASE_TEMP); + if (CVISI(i)) Draw_More_Icon(CSCROL(i)); + + _TEMP_ICON(CONTROL_CASE_MOVE); + Draw_More_Icon(CSCROL(i)); + + #if ENABLED(EEPROM_SETTINGS) + _TEMP_ICON(CONTROL_CASE_SAVE); + _TEMP_ICON(CONTROL_CASE_LOAD); + _TEMP_ICON(CONTROL_CASE_RESET); + #endif + + _TEMP_ICON(CONTROL_CASE_INFO); + if (CVISI(CONTROL_CASE_INFO)) Draw_More_Icon(CSCROL(i)); +} + +inline void Draw_Tune_Menu() { + Clear_Main_Window(); + + if (HMI_IsChinese()) { + DWIN_Frame_AreaCopy(1, 73, 2, 100, 13, 14, 9); + DWIN_Frame_AreaCopy(1, 116, 164, 171, 176, LBLX, MBASE(TUNE_CASE_SPEED)); + #if HAS_HOTEND + DWIN_Frame_AreaCopy(1, 1, 134, 56, 146, LBLX, MBASE(TUNE_CASE_TEMP)); + #endif + #if HAS_HEATED_BED + DWIN_Frame_AreaCopy(1, 58, 134, 113, 146, LBLX, MBASE(TUNE_CASE_BED)); + #endif + #if HAS_FAN + DWIN_Frame_AreaCopy(1, 115, 134, 170, 146, LBLX, MBASE(TUNE_CASE_FAN)); + #endif + #if HAS_ZOFFSET_ITEM + DWIN_Frame_AreaCopy(1, 174, 164, 223, 177, LBLX, MBASE(TUNE_CASE_ZOFF)); + #endif + } + else { + #ifdef USE_STRING_HEADINGS + Draw_Title(GET_TEXT_F(MSG_TUNE)); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(TUNE_CASE_SPEED), GET_TEXT_F(MSG_SPEED)); + #if HAS_HOTEND + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(TUNE_CASE_TEMP), GET_TEXT_F(MSG_UBL_SET_TEMP_HOTEND)); + #endif + #if HAS_HEATED_BED + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(TUNE_CASE_BED), GET_TEXT_F(MSG_UBL_SET_TEMP_BED)); + #endif + #if HAS_FAN + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(TUNE_CASE_FAN), GET_TEXT_F(MSG_FAN_SPEED)); + #endif + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(TUNE_CASE_ZOFF), GET_TEXT_F(MSG_ZPROBE_ZOFFSET)); + #else + DWIN_Frame_AreaCopy(1, 94, 2, 126, 12, 14, 9); + DWIN_Frame_AreaCopy(1, 1, 179, 92, 190, LBLX, MBASE(TUNE_CASE_SPEED)); // Print speed + #if HAS_HOTEND + DWIN_Frame_AreaCopy(1, 197, 104, 238, 114, LBLX, MBASE(TUNE_CASE_TEMP)); // Hotend... + DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX + 44, MBASE(TUNE_CASE_TEMP)); // ...Temperature + #endif + #if HAS_HEATED_BED + DWIN_Frame_AreaCopy(1, 240, 104, 264, 114, LBLX, MBASE(TUNE_CASE_BED)); // Bed... + DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX + 27, MBASE(TUNE_CASE_BED)); // ...Temperature + #endif + #if HAS_FAN + DWIN_Frame_AreaCopy(1, 0, 119, 64, 132, LBLX, MBASE(TUNE_CASE_FAN)); // Fan speed + #endif + #if HAS_ZOFFSET_ITEM + DWIN_Frame_AreaCopy(1, 93, 179, 141, 189, LBLX, MBASE(TUNE_CASE_ZOFF)); // Z-offset + #endif + #endif + } + + Draw_Back_First(select_tune.now == 0); + if (select_tune.now) Draw_Menu_Cursor(select_tune.now); + + Draw_Menu_Line(TUNE_CASE_SPEED, ICON_Speed); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(TUNE_CASE_SPEED), feedrate_percentage); + + #if HAS_HOTEND + Draw_Menu_Line(TUNE_CASE_TEMP, ICON_HotendTemp); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(TUNE_CASE_TEMP), thermalManager.temp_hotend[0].target); + #endif + #if HAS_HEATED_BED + Draw_Menu_Line(TUNE_CASE_BED, ICON_BedTemp); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(TUNE_CASE_BED), thermalManager.temp_bed.target); + #endif + #if HAS_FAN + Draw_Menu_Line(TUNE_CASE_FAN, ICON_FanSpeed); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(TUNE_CASE_FAN), thermalManager.fan_speed[0]); + #endif + #if HAS_ZOFFSET_ITEM + Draw_Menu_Line(TUNE_CASE_ZOFF, ICON_Zoffset); + DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 2, 2, 202, MBASE(TUNE_CASE_ZOFF), BABY_Z_VAR * 100); + #endif +} + +inline void draw_max_en(const uint16_t line) { + DWIN_Frame_AreaCopy(1, 245, 119, 269, 129, LBLX, line); // "Max" +} +inline void draw_max_accel_en(const uint16_t line) { + draw_max_en(line); + DWIN_Frame_AreaCopy(1, 1, 135, 79, 145, LBLX + 27, line); // "Acceleration" +} +inline void draw_speed_en(const uint16_t inset, const uint16_t line) { + DWIN_Frame_AreaCopy(1, 184, 119, 224, 132, LBLX + inset, line); // "Speed" +} +inline void draw_jerk_en(const uint16_t line) { + DWIN_Frame_AreaCopy(1, 64, 119, 106, 129, LBLX + 27, line); // "Jerk" +} +inline void draw_steps_per_mm(const uint16_t line) { + DWIN_Frame_AreaCopy(1, 1, 151, 101, 161, LBLX, line); // "Steps-per-mm" +} +inline void say_x(const uint16_t inset, const uint16_t line) { + DWIN_Frame_AreaCopy(1, 95, 104, 102, 114, LBLX + inset, line); // "X" +} +inline void say_y(const uint16_t inset, const uint16_t line) { + DWIN_Frame_AreaCopy(1, 104, 104, 110, 114, LBLX + inset, line); // "Y" +} +inline void say_z(const uint16_t inset, const uint16_t line) { + DWIN_Frame_AreaCopy(1, 112, 104, 120, 114, LBLX + inset, line); // "Z" +} +inline void say_e(const uint16_t inset, const uint16_t line) { + DWIN_Frame_AreaCopy(1, 237, 119, 244, 129, LBLX + inset, line); // "E" +} + +inline void Draw_Motion_Menu() { + Clear_Main_Window(); + + if (HMI_IsChinese()) { + DWIN_Frame_TitleCopy(1, 1, 16, 28, 28); // "Motion" + DWIN_Frame_AreaCopy(1, 173, 133, 228, 147, LBLX, MBASE(MOTION_CASE_RATE)); // Max speed + DWIN_Frame_AreaCopy(1, 173, 133, 200, 147, LBLX, MBASE(MOTION_CASE_ACCEL)); // Max... + DWIN_Frame_AreaCopy(1, 28, 149, 69, 161, LBLX + 27, MBASE(MOTION_CASE_ACCEL) + 1); // ...Acceleration + #if HAS_CLASSIC_JERK + DWIN_Frame_AreaCopy(1, 173, 133, 200, 147, LBLX, MBASE(MOTION_CASE_JERK)); // Max... + DWIN_Frame_AreaCopy(1, 1, 180, 28, 192, LBLX + 27, MBASE(MOTION_CASE_JERK) + 1); // ... + DWIN_Frame_AreaCopy(1, 202, 133, 228, 147, LBLX + 54, MBASE(MOTION_CASE_JERK)); // ...Jerk + #endif + DWIN_Frame_AreaCopy(1, 153, 148, 194, 161, LBLX, MBASE(MOTION_CASE_STEPS)); // Flow ratio + } + else { + #ifdef USE_STRING_HEADINGS + Draw_Title(GET_TEXT_F(MSG_MOTION)); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(MOTION_CASE_RATE), F("Feedrate")); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(MOTION_CASE_ACCEL), GET_TEXT_F(MSG_ACCELERATION)); + #if HAS_CLASSIC_JERK + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(MOTION_CASE_JERK), GET_TEXT_F(MSG_JERK)); + #endif + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(MOTION_CASE_STEPS), GET_TEXT_F(MSG_STEPS_PER_MM)); + #else + DWIN_Frame_TitleCopy(1, 144, 16, 189, 26); // "Motion" + draw_max_en(MBASE(MOTION_CASE_RATE)); draw_speed_en(27, MBASE(MOTION_CASE_RATE)); // "Max Speed" + draw_max_accel_en(MBASE(MOTION_CASE_ACCEL)); // "Max Acceleration" + #if HAS_CLASSIC_JERK + draw_max_en(MBASE(MOTION_CASE_JERK)); draw_jerk_en(MBASE(MOTION_CASE_JERK)); // "Max Jerk" + #endif + draw_steps_per_mm(MBASE(MOTION_CASE_STEPS)); // "Steps-per-mm" + #endif + } + + Draw_Back_First(select_motion.now == 0); + if (select_motion.now) Draw_Menu_Cursor(select_motion.now); + + uint8_t i = 0; + #define _MOTION_ICON(N) Draw_Menu_Line(++i, ICON_MaxSpeed + (N) - 1) + _MOTION_ICON(MOTION_CASE_RATE); Draw_More_Icon(i); + _MOTION_ICON(MOTION_CASE_ACCEL); Draw_More_Icon(i); + #if HAS_CLASSIC_JERK + _MOTION_ICON(MOTION_CASE_JERK); Draw_More_Icon(i); + #endif + _MOTION_ICON(MOTION_CASE_STEPS); Draw_More_Icon(i); +} + +// +// Draw Popup Windows +// +#if HAS_HOTEND || HAS_HEATED_BED + + void DWIN_Popup_Temperature(const bool toohigh) { + Clear_Popup_Area(); + Draw_Popup_Bkgd_105(); + if (toohigh) { + DWIN_ICON_Show(ICON, ICON_TempTooHigh, 102, 165); + if (HMI_IsChinese()) { + DWIN_Frame_AreaCopy(1, 103, 371, 237, 386, 52, 285); + DWIN_Frame_AreaCopy(1, 151, 389, 185, 402, 187, 285); + DWIN_Frame_AreaCopy(1, 189, 389, 271, 402, 95, 310); + } + else { + DWIN_Draw_String(false, true, font8x16, Popup_Text_Color, Color_Bg_Window, 36, 300, F("Nozzle or Bed temperature")); + DWIN_Draw_String(false, true, font8x16, Popup_Text_Color, Color_Bg_Window, 92, 300, F("is too high")); + } + } + else { + DWIN_ICON_Show(ICON, ICON_TempTooLow, 102, 165); + if (HMI_IsChinese()) { + DWIN_Frame_AreaCopy(1, 103, 371, 270, 386, 52, 285); + DWIN_Frame_AreaCopy(1, 189, 389, 271, 402, 95, 310); + } + else { + DWIN_Draw_String(false, true, font8x16, Popup_Text_Color, Color_Bg_Window, 36, 300, F("Nozzle or Bed temperature")); + DWIN_Draw_String(false, true, font8x16, Popup_Text_Color, Color_Bg_Window, 92, 300, F("is too low")); + } + } + } + +#endif + +inline void Draw_Popup_Bkgd_60() { + DWIN_Draw_Rectangle(1, Color_Bg_Window, 14, 60, 258, 330); +} + +#if HAS_HOTEND + + void Popup_Window_ETempTooLow() { + Clear_Main_Window(); + Draw_Popup_Bkgd_60(); + DWIN_ICON_Show(ICON, ICON_TempTooLow, 102, 105); + if (HMI_IsChinese()) { + DWIN_Frame_AreaCopy(1, 103, 371, 136, 386, 69, 240); + DWIN_Frame_AreaCopy(1, 170, 371, 270, 386, 102, 240); + DWIN_ICON_Show(ICON, ICON_Confirm_C, 86, 280); + } + else { + DWIN_Draw_String(false, true, font8x16, Popup_Text_Color, Color_Bg_Window, 20, 235, F("Nozzle is too cold")); + DWIN_ICON_Show(ICON, ICON_Confirm_E, 86, 280); + } + } + +#endif + +void Popup_Window_Resume() { + Clear_Popup_Area(); + Draw_Popup_Bkgd_105(); + if (HMI_IsChinese()) { + DWIN_Frame_AreaCopy(1, 160, 338, 235, 354, 98, 135); + DWIN_Frame_AreaCopy(1, 103, 321, 271, 335, 52, 192); + DWIN_ICON_Show(ICON, ICON_Cancel_C, 26, 307); + DWIN_ICON_Show(ICON, ICON_Continue_C, 146, 307); + } + else { + DWIN_Draw_String(false, true, font8x16, Popup_Text_Color, Color_Bg_Window, (272 - 8 * 14) / 2, 115, F("Continue Print")); + DWIN_Draw_String(false, true, font8x16, Popup_Text_Color, Color_Bg_Window, (272 - 8 * 22) / 2, 192, F("It looks like the last")); + DWIN_Draw_String(false, true, font8x16, Popup_Text_Color, Color_Bg_Window, (272 - 8 * 22) / 2, 212, F("file was interrupted.")); + DWIN_ICON_Show(ICON, ICON_Cancel_E, 26, 307); + DWIN_ICON_Show(ICON, ICON_Continue_E, 146, 307); + } +} + +void Popup_Window_Home(const bool parking/*=false*/) { + Clear_Main_Window(); + Draw_Popup_Bkgd_60(); + DWIN_ICON_Show(ICON, ICON_BLTouch, 101, 105); + if (HMI_IsChinese()) { + DWIN_Frame_AreaCopy(1, 0, 371, 33, 386, 85, 240); + DWIN_Frame_AreaCopy(1, 203, 286, 271, 302, 118, 240); + DWIN_Frame_AreaCopy(1, 0, 389, 150, 402, 61, 280); + } + else { + DWIN_Draw_String(false, true, font8x16, Popup_Text_Color, Color_Bg_Window, (272 - 8 * (parking ? 7 : 10)) / 2, 230, parking ? F("Parking") : F("Homing XYZ")); + DWIN_Draw_String(false, true, font8x16, Popup_Text_Color, Color_Bg_Window, (272 - 8 * 23) / 2, 260, F("Please wait until done.")); + } +} + +#if HAS_ONESTEP_LEVELING + + void Popup_Window_Leveling() { + Clear_Main_Window(); + Draw_Popup_Bkgd_60(); + DWIN_ICON_Show(ICON, ICON_AutoLeveling, 101, 105); + if (HMI_IsChinese()) { + DWIN_Frame_AreaCopy(1, 0, 371, 100, 386, 84, 240); + DWIN_Frame_AreaCopy(1, 0, 389, 150, 402, 61, 280); + } + else { + DWIN_Draw_String(false, true, font8x16, Popup_Text_Color, Color_Bg_Window, (272 - 8 * 13) / 2, 230, GET_TEXT_F(MSG_BED_LEVELING)); + DWIN_Draw_String(false, true, font8x16, Popup_Text_Color, Color_Bg_Window, (272 - 8 * 23) / 2, 260, F("Please wait until done.")); + } + } + +#endif + +void Draw_Select_Highlight(const bool sel) { + HMI_flag.select_flag = sel; + const uint16_t c1 = sel ? Select_Color : Color_Bg_Window, + c2 = sel ? Color_Bg_Window : Select_Color; + DWIN_Draw_Rectangle(0, c1, 25, 279, 126, 318); + DWIN_Draw_Rectangle(0, c1, 24, 278, 127, 319); + DWIN_Draw_Rectangle(0, c2, 145, 279, 246, 318); + DWIN_Draw_Rectangle(0, c2, 144, 278, 247, 319); +} + +void Popup_window_PauseOrStop() { + Clear_Main_Window(); + Draw_Popup_Bkgd_60(); + if (HMI_IsChinese()) { + if (select_print.now == 1) DWIN_Frame_AreaCopy(1, 237, 338, 269, 356, 98, 150); + else if (select_print.now == 2) DWIN_Frame_AreaCopy(1, 221, 320, 253, 336, 98, 150); + DWIN_Frame_AreaCopy(1, 220, 304, 264, 319, 130, 150); + DWIN_ICON_Show(ICON, ICON_Confirm_C, 26, 280); + DWIN_ICON_Show(ICON, ICON_Cancel_C, 146, 280); + } + else { + if (select_print.now == 1) DWIN_Draw_String(false, true, font8x16, Popup_Text_Color, Color_Bg_Window, (272 - 8 * 11) / 2, 150, GET_TEXT_F(MSG_PAUSE_PRINT)); + else if (select_print.now == 2) DWIN_Draw_String(false, true, font8x16, Popup_Text_Color, Color_Bg_Window, (272 - 8 * 10) / 2, 150, GET_TEXT_F(MSG_STOP_PRINT)); + DWIN_ICON_Show(ICON, ICON_Confirm_E, 26, 280); + DWIN_ICON_Show(ICON, ICON_Cancel_E, 146, 280); + } + Draw_Select_Highlight(true); +} + +void Draw_Printing_Screen() { + if (HMI_IsChinese()) { + DWIN_Frame_AreaCopy(1, 30, 1, 71, 14, 14, 9); // Tune + DWIN_Frame_AreaCopy(1, 0, 72, 63, 86, 41, 188); // Pause + DWIN_Frame_AreaCopy(1, 65, 72, 128, 86, 176, 188); // Stop + } + else { + DWIN_Frame_AreaCopy(1, 40, 2, 92, 14, 14, 9); // Tune + DWIN_Frame_AreaCopy(1, 0, 44, 96, 58, 41, 188); // Pause + DWIN_Frame_AreaCopy(1, 98, 44, 152, 58, 176, 188); // Stop + } +} + +void Draw_Print_ProgressBar() { + DWIN_ICON_Show(ICON, ICON_Bar, 15, 93); + DWIN_Draw_Rectangle(1, BarFill_Color, 16 + Percentrecord * 240 / 100, 93, 256, 113); + DWIN_Draw_IntValue(true, true, 0, font8x16, Percent_Color, Color_Bg_Black, 2, 117, 133, Percentrecord); + DWIN_Draw_String(false, false, font8x16, Percent_Color, Color_Bg_Black, 133, 133, F("%")); +} + +void Draw_Print_ProgressElapsed() { + duration_t elapsed = print_job_timer.duration(); // print timer + DWIN_Draw_IntValue(true, true, 1, font8x16, Color_White, Color_Bg_Black, 2, 42, 212, elapsed.value / 3600); + DWIN_Draw_String(false, false, font8x16, Color_White, Color_Bg_Black, 58, 212, F(":")); + DWIN_Draw_IntValue(true, true, 1, font8x16, Color_White, Color_Bg_Black, 2, 66, 212, (elapsed.value % 3600) / 60); +} + +void Draw_Print_ProgressRemain() { + DWIN_Draw_IntValue(true, true, 1, font8x16, Color_White, Color_Bg_Black, 2, 176, 212, remain_time / 3600); + DWIN_Draw_String(false, false, font8x16, Color_White, Color_Bg_Black, 192, 212, F(":")); + DWIN_Draw_IntValue(true, true, 1, font8x16, Color_White, Color_Bg_Black, 2, 200, 212, (remain_time % 3600) / 60); +} + +void Goto_PrintProcess() { + checkkey = PrintProcess; + + Clear_Main_Window(); + Draw_Printing_Screen(); + + ICON_Tune(); + if (printingIsPaused()) ICON_Continue(); else ICON_Pause(); + ICON_Stop(); + + // Copy into filebuf string before entry + char * const name = card.longest_filename(); + const int8_t npos = _MAX(0U, DWIN_WIDTH - strlen(name) * MENU_CHR_W) / 2; + DWIN_Draw_String(false, false, font8x16, Color_White, Color_Bg_Black, npos, 60, name); + + DWIN_ICON_Show(ICON, ICON_PrintTime, 17, 193); + DWIN_ICON_Show(ICON, ICON_RemainTime, 150, 191); + + Draw_Print_ProgressBar(); + Draw_Print_ProgressElapsed(); + Draw_Print_ProgressRemain(); +} + +void Goto_MainMenu() { + checkkey = MainMenu; + + Clear_Main_Window(); + + if (HMI_IsChinese()) { + DWIN_Frame_AreaCopy(1, 2, 2, 27, 14, 14, 9); // "Home" + } + else { + #ifdef USE_STRING_HEADINGS + Draw_Title(GET_TEXT_F(MSG_MAIN)); + #else + DWIN_Frame_AreaCopy(1, 0, 2, 39, 12, 14, 9); + #endif + } + + DWIN_ICON_Show(ICON, ICON_LOGO, 71, 52); + + ICON_Print(); + ICON_Prepare(); + ICON_Control(); + TERN(HAS_ONESTEP_LEVELING, ICON_Leveling, ICON_StartInfo)(select_page.now == 3); +} + +inline ENCODER_DiffState get_encoder_state() { + static millis_t Encoder_ms = 0; + const millis_t ms = millis(); + if (PENDING(ms, Encoder_ms)) return ENCODER_DIFF_NO; + const ENCODER_DiffState state = Encoder_ReceiveAnalyze(); + if (state != ENCODER_DIFF_NO) Encoder_ms = ms + ENCODER_WAIT; + return state; +} + +void HMI_Move_X() { + ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState != ENCODER_DIFF_NO) { + if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Move_X_scale)) { + checkkey = AxisMove; + EncoderRate.enabled = false; + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 216, MBASE(1), HMI_ValueStruct.Move_X_scale); + if (!planner.is_full()) { + // Wait for planner moves to finish! + planner.synchronize(); + planner.buffer_line(current_position, MMM_TO_MMS(HOMING_FEEDRATE_XY), active_extruder); + } + DWIN_UpdateLCD(); + return; + } + NOLESS(HMI_ValueStruct.Move_X_scale, (X_MIN_POS) * MINUNITMULT); + NOMORE(HMI_ValueStruct.Move_X_scale, (X_MAX_POS) * MINUNITMULT); + current_position.x = HMI_ValueStruct.Move_X_scale / 10; + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 1, 216, MBASE(1), HMI_ValueStruct.Move_X_scale); + DWIN_UpdateLCD(); + } +} + +void HMI_Move_Y() { + ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState != ENCODER_DIFF_NO) { + if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Move_Y_scale)) { + checkkey = AxisMove; + EncoderRate.enabled = false; + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 216, MBASE(2), HMI_ValueStruct.Move_Y_scale); + if (!planner.is_full()) { + // Wait for planner moves to finish! + planner.synchronize(); + planner.buffer_line(current_position, MMM_TO_MMS(HOMING_FEEDRATE_XY), active_extruder); + } + DWIN_UpdateLCD(); + return; + } + NOLESS(HMI_ValueStruct.Move_Y_scale, (Y_MIN_POS) * MINUNITMULT); + NOMORE(HMI_ValueStruct.Move_Y_scale, (Y_MAX_POS) * MINUNITMULT); + current_position.y = HMI_ValueStruct.Move_Y_scale / 10; + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 1, 216, MBASE(2), HMI_ValueStruct.Move_Y_scale); + DWIN_UpdateLCD(); + } +} + +void HMI_Move_Z() { + ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState != ENCODER_DIFF_NO) { + if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Move_Z_scale)) { + checkkey = AxisMove; + EncoderRate.enabled = false; + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 216, MBASE(3), HMI_ValueStruct.Move_Z_scale); + if (!planner.is_full()) { + // Wait for planner moves to finish! + planner.synchronize(); + planner.buffer_line(current_position, MMM_TO_MMS(HOMING_FEEDRATE_Z), active_extruder); + } + DWIN_UpdateLCD(); + return; + } + NOLESS(HMI_ValueStruct.Move_Z_scale, Z_MIN_POS * MINUNITMULT); + NOMORE(HMI_ValueStruct.Move_Z_scale, Z_MAX_POS * MINUNITMULT); + current_position.z = HMI_ValueStruct.Move_Z_scale / 10; + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 1, 216, MBASE(3), HMI_ValueStruct.Move_Z_scale); + DWIN_UpdateLCD(); + } +} + +#if HAS_HOTEND + + void HMI_Move_E() { + static float last_E_scale = 0; + ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState != ENCODER_DIFF_NO) { + if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Move_E_scale)) { + checkkey = AxisMove; + EncoderRate.enabled = false; + last_E_scale = HMI_ValueStruct.Move_E_scale; + DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 3, 1, 216, MBASE(4), HMI_ValueStruct.Move_E_scale); + if (!planner.is_full()) { + planner.synchronize(); // Wait for planner moves to finish! + planner.buffer_line(current_position, MMM_TO_MMS(FEEDRATE_E), active_extruder); + } + DWIN_UpdateLCD(); + return; + } + if ((HMI_ValueStruct.Move_E_scale - last_E_scale) > (EXTRUDE_MAXLENGTH) * MINUNITMULT) + HMI_ValueStruct.Move_E_scale = last_E_scale + (EXTRUDE_MAXLENGTH) * MINUNITMULT; + else if ((last_E_scale - HMI_ValueStruct.Move_E_scale) > (EXTRUDE_MAXLENGTH) * MINUNITMULT) + HMI_ValueStruct.Move_E_scale = last_E_scale - (EXTRUDE_MAXLENGTH) * MINUNITMULT; + current_position.e = HMI_ValueStruct.Move_E_scale / 10; + DWIN_Draw_Signed_Float(font8x16, Select_Color, 3, 1, 216, MBASE(4), HMI_ValueStruct.Move_E_scale); + DWIN_UpdateLCD(); + } + } + +#endif + +#if HAS_ZOFFSET_ITEM + + bool printer_busy() { return planner.movesplanned() || printingIsActive(); } + + void HMI_Zoffset() { + ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState != ENCODER_DIFF_NO) { + uint8_t zoff_line; + switch (HMI_ValueStruct.show_mode) { + case -4: zoff_line = PREPARE_CASE_ZOFF + MROWS - index_prepare; break; + default: zoff_line = TUNE_CASE_ZOFF + MROWS - index_tune; + } + if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.offset_value)) { + EncoderRate.enabled = false; + #if HAS_BED_PROBE + probe.offset.z = dwin_zoffset; + TERN_(EEPROM_SETTINGS, settings.save()); + #endif + if (HMI_ValueStruct.show_mode == -4) { + checkkey = Prepare; + DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 2, 2, 202, MBASE(zoff_line), TERN(HAS_BED_PROBE, BABY_Z_VAR * 100, HMI_ValueStruct.offset_value)); + } + else { + checkkey = Tune; + DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 2, 2, 202, MBASE(zoff_line), TERN(HAS_BED_PROBE, BABY_Z_VAR * 100, HMI_ValueStruct.offset_value)); + } + DWIN_UpdateLCD(); + return; + } + NOLESS(HMI_ValueStruct.offset_value, (Z_PROBE_OFFSET_RANGE_MIN) * 100); + NOMORE(HMI_ValueStruct.offset_value, (Z_PROBE_OFFSET_RANGE_MAX) * 100); + last_zoffset = dwin_zoffset; + dwin_zoffset = HMI_ValueStruct.offset_value / 100.0f; + #if EITHER(BABYSTEP_ZPROBE_OFFSET, JUST_BABYSTEP) + if ( (ENABLED(BABYSTEP_WITHOUT_HOMING) || all_axes_known()) && (ENABLED(BABYSTEP_ALWAYS_AVAILABLE) || printer_busy()) ) + babystep.add_mm(Z_AXIS, dwin_zoffset - last_zoffset); + #endif + DWIN_Draw_Signed_Float(font8x16, Select_Color, 2, 2, 202, MBASE(zoff_line), HMI_ValueStruct.offset_value); + DWIN_UpdateLCD(); + } + } + +#endif // HAS_ZOFFSET_ITEM + +#if HAS_HOTEND + + void HMI_ETemp() { + ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState != ENCODER_DIFF_NO) { + uint8_t temp_line; + switch (HMI_ValueStruct.show_mode) { + case -1: temp_line = TEMP_CASE_TEMP; break; + case -2: temp_line = PREHEAT_CASE_TEMP; break; + case -3: temp_line = PREHEAT_CASE_TEMP; break; + default: temp_line = TUNE_CASE_TEMP + MROWS - index_tune; + } + if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.E_Temp)) { + EncoderRate.enabled = false; + if (HMI_ValueStruct.show_mode == -1) { // temperature + checkkey = TemperatureID; + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(temp_line), HMI_ValueStruct.E_Temp); + } + else if (HMI_ValueStruct.show_mode == -2) { + checkkey = PLAPreheat; + ui.material_preset[0].hotend_temp = HMI_ValueStruct.E_Temp; + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(temp_line), ui.material_preset[0].hotend_temp); + return; + } + else if (HMI_ValueStruct.show_mode == -3) { + checkkey = ABSPreheat; + ui.material_preset[1].hotend_temp = HMI_ValueStruct.E_Temp; + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(temp_line), ui.material_preset[1].hotend_temp); + return; + } + else { // tune + checkkey = Tune; + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(temp_line), HMI_ValueStruct.E_Temp); + } + thermalManager.setTargetHotend(HMI_ValueStruct.E_Temp, 0); + return; + } + // E_Temp limit + NOMORE(HMI_ValueStruct.E_Temp, MAX_E_TEMP); + NOLESS(HMI_ValueStruct.E_Temp, MIN_E_TEMP); + // E_Temp value + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(temp_line), HMI_ValueStruct.E_Temp); + } + } + +#endif // HAS_HOTEND + +#if HAS_HEATED_BED + + void HMI_BedTemp() { + ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState != ENCODER_DIFF_NO) { + uint8_t bed_line; + switch (HMI_ValueStruct.show_mode) { + case -1: bed_line = TEMP_CASE_BED; break; + case -2: bed_line = PREHEAT_CASE_BED; break; + case -3: bed_line = PREHEAT_CASE_BED; break; + default: bed_line = TUNE_CASE_BED + MROWS - index_tune; + } + if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Bed_Temp)) { + EncoderRate.enabled = false; + if (HMI_ValueStruct.show_mode == -1) { + checkkey = TemperatureID; + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(bed_line), HMI_ValueStruct.Bed_Temp); + } + else if (HMI_ValueStruct.show_mode == -2) { + checkkey = PLAPreheat; + ui.material_preset[0].bed_temp = HMI_ValueStruct.Bed_Temp; + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(bed_line), ui.material_preset[0].bed_temp); + return; + } + else if (HMI_ValueStruct.show_mode == -3) { + checkkey = ABSPreheat; + ui.material_preset[1].bed_temp = HMI_ValueStruct.Bed_Temp; + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(bed_line), ui.material_preset[1].bed_temp); + return; + } + else { + checkkey = Tune; + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(bed_line), HMI_ValueStruct.Bed_Temp); + } + thermalManager.setTargetBed(HMI_ValueStruct.Bed_Temp); + return; + } + // Bed_Temp limit + NOMORE(HMI_ValueStruct.Bed_Temp, BED_MAX_TARGET); + NOLESS(HMI_ValueStruct.Bed_Temp, MIN_BED_TEMP); + // Bed_Temp value + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(bed_line), HMI_ValueStruct.Bed_Temp); + } + } + +#endif // HAS_HEATED_BED + +#if HAS_PREHEAT + + void HMI_FanSpeed() { + ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState != ENCODER_DIFF_NO) { + uint8_t fan_line; + switch (HMI_ValueStruct.show_mode) { + case -1: fan_line = TEMP_CASE_FAN; break; + case -2: fan_line = PREHEAT_CASE_FAN; break; + case -3: fan_line = PREHEAT_CASE_FAN; break; + default: fan_line = TUNE_CASE_FAN + MROWS - index_tune; + } + + if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Fan_speed)) { + EncoderRate.enabled = false; + if (HMI_ValueStruct.show_mode == -1) { + checkkey = TemperatureID; + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(fan_line), HMI_ValueStruct.Fan_speed); + } + else if (HMI_ValueStruct.show_mode == -2) { + checkkey = PLAPreheat; + ui.material_preset[0].fan_speed = HMI_ValueStruct.Fan_speed; + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(fan_line), ui.material_preset[0].fan_speed); + return; + } + else if (HMI_ValueStruct.show_mode == -3) { + checkkey = ABSPreheat; + ui.material_preset[1].fan_speed = HMI_ValueStruct.Fan_speed; + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(fan_line), ui.material_preset[1].fan_speed); + return; + } + else { + checkkey = Tune; + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(fan_line), HMI_ValueStruct.Fan_speed); + } + thermalManager.set_fan_speed(0, HMI_ValueStruct.Fan_speed); + return; + } + // Fan_speed limit + NOMORE(HMI_ValueStruct.Fan_speed, FANON); + NOLESS(HMI_ValueStruct.Fan_speed, FANOFF); + // Fan_speed value + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(fan_line), HMI_ValueStruct.Fan_speed); + } + } + +#endif // HAS_PREHEAT + +void HMI_PrintSpeed() { + ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState != ENCODER_DIFF_NO) { + if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.print_speed)) { + checkkey = Tune; + EncoderRate.enabled = false; + feedrate_percentage = HMI_ValueStruct.print_speed; + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(select_tune.now + MROWS - index_tune), HMI_ValueStruct.print_speed); + return; + } + // print_speed limit + NOMORE(HMI_ValueStruct.print_speed, MAX_PRINT_SPEED); + NOLESS(HMI_ValueStruct.print_speed, MIN_PRINT_SPEED); + // print_speed value + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(select_tune.now + MROWS - index_tune), HMI_ValueStruct.print_speed); + } +} + +void HMI_MaxFeedspeedXYZE() { + ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState != ENCODER_DIFF_NO) { + if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Max_Feedspeed)) { + checkkey = MaxSpeed; + EncoderRate.enabled = false; + if (WITHIN(HMI_flag.feedspeed_axis, X_AXIS, E_AXIS)) + planner.set_max_feedrate(HMI_flag.feedspeed_axis, HMI_ValueStruct.Max_Feedspeed); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 4, 210, MBASE(select_speed.now), HMI_ValueStruct.Max_Feedspeed); + return; + } + // MaxFeedspeed limit + if (WITHIN(HMI_flag.feedspeed_axis, X_AXIS, E_AXIS)) + NOMORE(HMI_ValueStruct.Max_Feedspeed, default_max_feedrate[HMI_flag.feedspeed_axis] * 2); + if (HMI_ValueStruct.Max_Feedspeed < MIN_MAXFEEDSPEED) HMI_ValueStruct.Max_Feedspeed = MIN_MAXFEEDSPEED; + // MaxFeedspeed value + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 4, 210, MBASE(select_speed.now), HMI_ValueStruct.Max_Feedspeed); + } +} + +void HMI_MaxAccelerationXYZE() { + ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState != ENCODER_DIFF_NO) { + if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Max_Acceleration)) { + checkkey = MaxAcceleration; + EncoderRate.enabled = false; + if (HMI_flag.acc_axis == X_AXIS) planner.set_max_acceleration(X_AXIS, HMI_ValueStruct.Max_Acceleration); + else if (HMI_flag.acc_axis == Y_AXIS) planner.set_max_acceleration(Y_AXIS, HMI_ValueStruct.Max_Acceleration); + else if (HMI_flag.acc_axis == Z_AXIS) planner.set_max_acceleration(Z_AXIS, HMI_ValueStruct.Max_Acceleration); + #if HAS_HOTEND + else if (HMI_flag.acc_axis == E_AXIS) planner.set_max_acceleration(E_AXIS, HMI_ValueStruct.Max_Acceleration); + #endif + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 4, 210, MBASE(select_acc.now), HMI_ValueStruct.Max_Acceleration); + return; + } + // MaxAcceleration limit + if (WITHIN(HMI_flag.acc_axis, X_AXIS, E_AXIS)) + NOMORE(HMI_ValueStruct.Max_Acceleration, default_max_acceleration[HMI_flag.acc_axis] * 2); + if (HMI_ValueStruct.Max_Acceleration < MIN_MAXACCELERATION) HMI_ValueStruct.Max_Acceleration = MIN_MAXACCELERATION; + // MaxAcceleration value + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 4, 210, MBASE(select_acc.now), HMI_ValueStruct.Max_Acceleration); + } +} + +#if HAS_CLASSIC_JERK + + void HMI_MaxJerkXYZE() { + ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState != ENCODER_DIFF_NO) { + if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Max_Jerk)) { + checkkey = MaxJerk; + EncoderRate.enabled = false; + if (WITHIN(HMI_flag.step_axis, X_AXIS, E_AXIS)) + planner.set_max_jerk(HMI_flag.step_axis, HMI_ValueStruct.Max_Jerk / 10); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 210, MBASE(select_jerk.now), HMI_ValueStruct.Max_Jerk); + return; + } + // MaxJerk limit + if (WITHIN(HMI_flag.jerk_axis, X_AXIS, E_AXIS)) + NOMORE(HMI_ValueStruct.Max_Jerk, default_max_jerk[HMI_flag.jerk_axis] * 2 * MINUNITMULT); + NOLESS(HMI_ValueStruct.Max_Jerk, (MIN_MAXJERK) * MINUNITMULT); + // MaxJerk value + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 1, 210, MBASE(select_jerk.now), HMI_ValueStruct.Max_Jerk); + } + } + +#endif // HAS_CLASSIC_JERK + +void HMI_StepXYZE() { + ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState != ENCODER_DIFF_NO) { + if (Apply_Encoder(encoder_diffState, HMI_ValueStruct.Max_Step)) { + checkkey = Step; + EncoderRate.enabled = false; + if (WITHIN(HMI_flag.step_axis, X_AXIS, E_AXIS)) + planner.settings.axis_steps_per_mm[HMI_flag.step_axis] = HMI_ValueStruct.Max_Step / 10; + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 210, MBASE(select_step.now), HMI_ValueStruct.Max_Step); + return; + } + // Step limit + if (WITHIN(HMI_flag.step_axis, X_AXIS, E_AXIS)) + NOMORE(HMI_ValueStruct.Max_Step, default_axis_steps_per_unit[HMI_flag.step_axis] * 2 * MINUNITMULT); + NOLESS(HMI_ValueStruct.Max_Step, MIN_STEP); + // Step value + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 1, 210, MBASE(select_step.now), HMI_ValueStruct.Max_Step); + } +} + +void update_variable() { + #if HAS_HOTEND + static float last_temp_hotend_target = 0, last_temp_hotend_current = 0; + #endif + #if HAS_HEATED_BED + static float last_temp_bed_target = 0, last_temp_bed_current = 0; + #endif + #if HAS_FAN + static uint8_t last_fan_speed = 0; + #endif + + /* Tune page temperature update */ + if (checkkey == Tune) { + #if HAS_HOTEND + if (last_temp_hotend_target != thermalManager.temp_hotend[0].target) + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(TUNE_CASE_TEMP + MROWS - index_tune), thermalManager.temp_hotend[0].target); + #endif + #if HAS_HEATED_BED + if (last_temp_bed_target != thermalManager.temp_bed.target) + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(TUNE_CASE_BED + MROWS - index_tune), thermalManager.temp_bed.target); + #endif + #if HAS_FAN + if (last_fan_speed != thermalManager.fan_speed[0]) { + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(TUNE_CASE_FAN + MROWS - index_tune), thermalManager.fan_speed[0]); + last_fan_speed = thermalManager.fan_speed[0]; + } + #endif + } + + /* Temperature page temperature update */ + if (checkkey == TemperatureID) { + #if HAS_HOTEND + if (last_temp_hotend_target != thermalManager.temp_hotend[0].target) + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(TEMP_CASE_TEMP), thermalManager.temp_hotend[0].target); + #endif + #if HAS_HEATED_BED + if (last_temp_bed_target != thermalManager.temp_bed.target) + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(TEMP_CASE_BED), thermalManager.temp_bed.target); + #endif + #if HAS_FAN + if (last_fan_speed != thermalManager.fan_speed[0]) { + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(TEMP_CASE_FAN), thermalManager.fan_speed[0]); + last_fan_speed = thermalManager.fan_speed[0]; + } + #endif + } + + /* Bottom temperature update */ + #if HAS_HOTEND + if (last_temp_hotend_current != thermalManager.temp_hotend[0].celsius) { + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 33, 382, thermalManager.temp_hotend[0].celsius); + last_temp_hotend_current = thermalManager.temp_hotend[0].celsius; + } + if (last_temp_hotend_target != thermalManager.temp_hotend[0].target) { + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 33 + 4 * STAT_CHR_W + 6, 382, thermalManager.temp_hotend[0].target); + last_temp_hotend_target = thermalManager.temp_hotend[0].target; + } + #endif + #if HAS_HEATED_BED + if (last_temp_bed_current != thermalManager.temp_bed.celsius) { + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 178, 382, thermalManager.temp_bed.celsius); + last_temp_bed_current = thermalManager.temp_bed.celsius; + } + if (last_temp_bed_target != thermalManager.temp_bed.target) { + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 178 + 4 * STAT_CHR_W + 6, 382, thermalManager.temp_bed.target); + last_temp_bed_target = thermalManager.temp_bed.target; + } + #endif + static uint16_t last_speed = 0; + if (last_speed != feedrate_percentage) { + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 33 + 2 * STAT_CHR_W, 429, feedrate_percentage); + last_speed = feedrate_percentage; + } + #if HAS_ZOFFSET_ITEM + if (last_zoffset != BABY_Z_VAR) { + DWIN_Draw_Signed_Float(DWIN_FONT_STAT, Color_Bg_Black, 2, 2, 178 + STAT_CHR_W, 429, BABY_Z_VAR * 100); + last_zoffset = BABY_Z_VAR; + } + #endif +} + +/** + * Read and cache the working directory. + * + * TODO: New code can follow the pattern of menu_media.cpp + * and rely on Marlin caching for performance. No need to + * cache files here. + */ + +#ifndef strcasecmp_P + #define strcasecmp_P(a, b) strcasecmp((a), (b)) +#endif + +inline void make_name_without_ext(char *dst, char *src, size_t maxlen=MENU_CHAR_LIMIT) { + char * const name = card.longest_filename(); + size_t pos = strlen(name); // index of ending nul + + // For files, remove the extension + // which may be .gcode, .gco, or .g + if (!card.flag.filenameIsDir) + while (pos && src[pos] != '.') pos--; // find last '.' (stop at 0) + + size_t len = pos; // nul or '.' + if (len > maxlen) { // Keep the name short + pos = len = maxlen; // move nul down + dst[--pos] = '.'; // insert dots + dst[--pos] = '.'; + dst[--pos] = '.'; + } + + dst[len] = '\0'; // end it + + // Copy down to 0 + while (pos--) dst[pos] = src[pos]; +} + +inline void HMI_SDCardInit() { card.cdroot(); } + +void MarlinUI::refresh() { /* Nothing to see here */ } + +#define ICON_Folder ICON_More + +#if ENABLED(SCROLL_LONG_FILENAMES) + + char shift_name[LONG_FILENAME_LENGTH + 1]; + int8_t shift_amt; // = 0 + millis_t shift_ms; // = 0 + + // Init the shift name based on the highlighted item + inline void Init_Shift_Name() { + const bool is_subdir = !card.flag.workDirIsRoot; + const int8_t filenum = select_file.now - 1 - is_subdir; // Skip "Back" and ".." + const uint16_t fileCnt = card.get_num_Files(); + if (WITHIN(filenum, 0, fileCnt - 1)) { + card.getfilename_sorted(SD_ORDER(filenum, fileCnt)); + char * const name = card.longest_filename(); + make_name_without_ext(shift_name, name, 100); + } + } + + inline void Init_SDItem_Shift() { + shift_amt = 0; + shift_ms = select_file.now > 0 && strlen(shift_name) > MENU_CHAR_LIMIT + ? millis() + 750UL : 0; + } + +#endif + +/** + * Display an SD item, adding a CDUP for subfolders. + */ +inline void Draw_SDItem(const uint16_t item, int16_t row=-1) { + if (row < 0) row = item + 1 + MROWS - index_file; + const bool is_subdir = !card.flag.workDirIsRoot; + if (is_subdir && item == 0) { + Draw_Menu_Line(row, ICON_Folder, ".."); + return; + } + + card.getfilename_sorted(item - is_subdir); + char * const name = card.longest_filename(); + + #if ENABLED(SCROLL_LONG_FILENAMES) + // Init the current selected name + // This is used during scroll drawing + if (item == select_file.now - 1) { + make_name_without_ext(shift_name, name, 100); + Init_SDItem_Shift(); + } + #endif + + // Draw the file/folder with name aligned left + char str[strlen(name) + 1]; + make_name_without_ext(str, name); + Draw_Menu_Line(row, card.flag.filenameIsDir ? ICON_Folder : ICON_File, str); +} + +#if ENABLED(SCROLL_LONG_FILENAMES) + + inline void Draw_SDItem_Shifted(int8_t &shift) { + // Limit to the number of chars past the cutoff + const size_t len = strlen(shift_name); + NOMORE(shift, _MAX(len - MENU_CHAR_LIMIT, 0U)); + + // Shorten to the available space + const size_t lastchar = _MIN((signed)len, shift + MENU_CHAR_LIMIT); + + const char c = shift_name[lastchar]; + shift_name[lastchar] = '\0'; + + const uint8_t row = select_file.now + MROWS - index_file; // skip "Back" and scroll + Erase_Menu_Text(row); + Draw_Menu_Line(row, 0, &shift_name[shift]); + + shift_name[lastchar] = c; + } + +#endif + +// Redraw the first set of SD Files +inline void Redraw_SD_List() { + select_file.reset(); + index_file = MROWS; + + Clear_Menu_Area(); // Leave title bar unchanged + + Draw_Back_First(); + + if (card.isMounted()) { + // As many files as will fit + LOOP_L_N(i, _MIN(nr_sd_menu_items(), MROWS)) + Draw_SDItem(i, i + 1); + + TERN_(SCROLL_LONG_FILENAMES, Init_SDItem_Shift()); + } + else { + DWIN_Draw_Rectangle(1, Color_Bg_Red, 10, MBASE(3) - 10, DWIN_WIDTH - 10, MBASE(4)); + DWIN_Draw_String(false, false, font16x32, Color_Yellow, Color_Bg_Red, ((DWIN_WIDTH) - 8 * 16) / 2, MBASE(3), F("No Media")); + } +} + +bool DWIN_lcd_sd_status = false; + +inline void SDCard_Up() { + card.cdup(); + Redraw_SD_List(); + DWIN_lcd_sd_status = false; // On next DWIN_Update +} + +inline void SDCard_Folder(char * const dirname) { + card.cd(dirname); + Redraw_SD_List(); + DWIN_lcd_sd_status = false; // On next DWIN_Update +} + +// +// Watch for media mount / unmount +// +void HMI_SDCardUpdate() { + if (HMI_flag.home_flag) return; + if (DWIN_lcd_sd_status != card.isMounted()) { + DWIN_lcd_sd_status = card.isMounted(); + // SERIAL_ECHOLNPAIR("HMI_SDCardUpdate: ", int(DWIN_lcd_sd_status)); + if (DWIN_lcd_sd_status) { + if (checkkey == SelectFile) + Redraw_SD_List(); + } + else { + // clean file icon + if (checkkey == SelectFile) { + Redraw_SD_List(); + } + else if (checkkey == PrintProcess || checkkey == Tune || printingIsActive()) { + // TODO: Move card removed abort handling + // to CardReader::manage_media. + card.flag.abort_sd_printing = true; + wait_for_heatup = false; + dwin_abort_flag = true; + } + } + DWIN_UpdateLCD(); + } +} + +// +// The status area is always on-screen, except during +// full-screen modal dialogs. (TODO: Keep alive during dialogs) +// +void Draw_Status_Area(const bool with_update) { + + // Clear the bottom area of the screen + DWIN_Draw_Rectangle(1, Color_Bg_Black, 0, STATUS_Y, DWIN_WIDTH, DWIN_HEIGHT - 1); + + // + // Status Area + // + #if HAS_HOTEND + DWIN_ICON_Show(ICON, ICON_HotendTemp, 13, 381); + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 33, 382, thermalManager.temp_hotend[0].celsius); + DWIN_Draw_String(false, false, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 33 + 3 * STAT_CHR_W + 5, 383, F("/")); + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 33 + 4 * STAT_CHR_W + 6, 382, thermalManager.temp_hotend[0].target); + #endif + #if HOTENDS > 1 + // DWIN_ICON_Show(ICON,ICON_HotendTemp, 13, 381); + #endif + + #if HAS_HEATED_BED + DWIN_ICON_Show(ICON, ICON_BedTemp, 158, 381); + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 178, 382, thermalManager.temp_bed.celsius); + DWIN_Draw_String(false, false, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 178 + 3 * STAT_CHR_W + 5, 383, F("/")); + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 178 + 4 * STAT_CHR_W + 6, 382, thermalManager.temp_bed.target); + #endif + + DWIN_ICON_Show(ICON, ICON_Speed, 13, 429); + DWIN_Draw_IntValue(true, true, 0, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 3, 33 + 2 * STAT_CHR_W, 429, feedrate_percentage); + DWIN_Draw_String(false, false, DWIN_FONT_STAT, Color_White, Color_Bg_Black, 33 + 5 * STAT_CHR_W + 2, 429, F("%")); + + #if HAS_ZOFFSET_ITEM + DWIN_ICON_Show(ICON, ICON_Zoffset, 158, 428); + DWIN_Draw_Signed_Float(DWIN_FONT_STAT, Color_Bg_Black, 2, 2, 178, 429, BABY_Z_VAR * 100); + #endif + + if (with_update) { + DWIN_UpdateLCD(); + delay(5); + } +} + +void HMI_StartFrame(const bool with_update) { + Goto_MainMenu(); + Draw_Status_Area(with_update); +} + +inline void Draw_Info_Menu() { + Clear_Main_Window(); + + DWIN_Draw_String(false, false, font8x16, Color_White, Color_Bg_Black, (DWIN_WIDTH - strlen(MACHINE_SIZE) * MENU_CHR_W) / 2, 122, (char*)MACHINE_SIZE); + DWIN_Draw_String(false, false, font8x16, Color_White, Color_Bg_Black, (DWIN_WIDTH - strlen(SHORT_BUILD_VERSION) * MENU_CHR_W) / 2, 195, (char*)SHORT_BUILD_VERSION); + + if (HMI_IsChinese()) { + DWIN_Frame_TitleCopy(1, 30, 17, 57, 29); // "Info" + + DWIN_Frame_AreaCopy(1, 197, 149, 252, 161, 108, 102); + DWIN_Frame_AreaCopy(1, 1, 164, 56, 176, 108, 175); + DWIN_Frame_AreaCopy(1, 58, 164, 113, 176, 105, 248); + DWIN_Draw_String(false, false, font8x16, Color_White, Color_Bg_Black, (DWIN_WIDTH - strlen(CORP_WEBSITE_C) * MENU_CHR_W) / 2, 268, (char*)CORP_WEBSITE_C); + } + else { + #ifdef USE_STRING_HEADINGS + Draw_Title(GET_TEXT_F(MSG_INFO_SCREEN)); + #else + DWIN_Frame_TitleCopy(1, 190, 16, 215, 26); // "Info" + #endif + + DWIN_Frame_AreaCopy(1, 120, 150, 146, 161, 124, 102); + DWIN_Frame_AreaCopy(1, 146, 151, 254, 161, 82, 175); + DWIN_Frame_AreaCopy(1, 0, 165, 94, 175, 89, 248); + DWIN_Draw_String(false, false, font8x16, Color_White, Color_Bg_Black, (DWIN_WIDTH - strlen(CORP_WEBSITE_E) * MENU_CHR_W) / 2, 268, (char*)CORP_WEBSITE_E); + } + + Draw_Back_First(); + LOOP_L_N(i, 3) { + DWIN_ICON_Show(ICON, ICON_PrintSize + i, 26, 99 + i * 73); + DWIN_Draw_Line(Line_Color, 16, MBASE(2) + i * 73, 256, 156 + i * 73); + } +} + +inline void Draw_Print_File_Menu() { + Clear_Title_Bar(); + + if (HMI_IsChinese()) { + DWIN_Frame_TitleCopy(1, 0, 31, 55, 44); // "Print file" + } + else { + #ifdef USE_STRING_HEADINGS + Draw_Title("Print file"); // TODO: GET_TEXT_F + #else + DWIN_Frame_TitleCopy(1, 52, 31, 137, 41); // "Print file" + #endif + } + + Redraw_SD_List(); +} + +/* Main Process */ +void HMI_MainMenu() { + ENCODER_DiffState encoder_diffState = get_encoder_state(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + + if (encoder_diffState == ENCODER_DIFF_CW) { + if (select_page.inc(4)) { + switch (select_page.now) { + case 0: ICON_Print(); break; + case 1: ICON_Print(); ICON_Prepare(); break; + case 2: ICON_Prepare(); ICON_Control(); break; + case 3: ICON_Control(); TERN(HAS_ONESTEP_LEVELING, ICON_Leveling, ICON_StartInfo)(1); break; + } + } + } + else if (encoder_diffState == ENCODER_DIFF_CCW) { + if (select_page.dec()) { + switch (select_page.now) { + case 0: ICON_Print(); ICON_Prepare(); break; + case 1: ICON_Prepare(); ICON_Control(); break; + case 2: ICON_Control(); TERN(HAS_ONESTEP_LEVELING, ICON_Leveling, ICON_StartInfo)(0); break; + case 3: TERN(HAS_ONESTEP_LEVELING, ICON_Leveling, ICON_StartInfo)(1); break; + } + } + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + switch (select_page.now) { + case 0: // Print File + checkkey = SelectFile; + Draw_Print_File_Menu(); + break; + + case 1: // Prepare + checkkey = Prepare; + select_prepare.reset(); + index_prepare = MROWS; + Draw_Prepare_Menu(); + break; + + case 2: // Control + checkkey = Control; + select_control.reset(); + index_control = MROWS; + Draw_Control_Menu(); + break; + + case 3: // Leveling or Info + #if HAS_ONESTEP_LEVELING + checkkey = Leveling; + HMI_Leveling(); + #else + checkkey = Info; + Draw_Info_Menu(); + #endif + break; + } + } + DWIN_UpdateLCD(); +} + +// Select (and Print) File +void HMI_SelectFile() { + ENCODER_DiffState encoder_diffState = get_encoder_state(); + + const uint16_t hasUpDir = !card.flag.workDirIsRoot; + + if (encoder_diffState == ENCODER_DIFF_NO) { + #if ENABLED(SCROLL_LONG_FILENAMES) + if (shift_ms && select_file.now >= 1 + hasUpDir) { + // Scroll selected filename every second + const millis_t ms = millis(); + if (ELAPSED(ms, shift_ms)) { + const bool was_reset = shift_amt < 0; + shift_ms = ms + 375UL + was_reset * 250UL; // ms per character + int8_t shift_new = shift_amt + 1; // Try to shift by... + Draw_SDItem_Shifted(shift_new); // Draw the item + if (!was_reset && shift_new == 0) // Was it limited to 0? + shift_ms = 0; // No scrolling needed + else if (shift_new == shift_amt) // Scroll reached the end + shift_new = -1; // Reset + shift_amt = shift_new; // Set new scroll + } + } + #endif + return; + } + + // First pause is long. Easy. + // On reset, long pause must be after 0. + + const uint16_t fullCnt = nr_sd_menu_items(); + + if (encoder_diffState == ENCODER_DIFF_CW && fullCnt) { + if (select_file.inc(1 + fullCnt)) { + const uint8_t itemnum = select_file.now - 1; // -1 for "Back" + if (TERN0(SCROLL_LONG_FILENAMES, shift_ms)) { // If line was shifted + Erase_Menu_Text(itemnum + MROWS - index_file); // Erase and + Draw_SDItem(itemnum - 1); // redraw + } + if (select_file.now > MROWS && select_file.now > index_file) { // Cursor past the bottom + index_file = select_file.now; // New bottom line + Scroll_Menu(DWIN_SCROLL_UP); + Draw_SDItem(itemnum, MROWS); // Draw and init the shift name + } + else { + Move_Highlight(1, select_file.now + MROWS - index_file); // Just move highlight + TERN_(SCROLL_LONG_FILENAMES, Init_Shift_Name()); // ...and init the shift name + } + TERN_(SCROLL_LONG_FILENAMES, Init_SDItem_Shift()); + } + } + else if (encoder_diffState == ENCODER_DIFF_CCW && fullCnt) { + if (select_file.dec()) { + const uint8_t itemnum = select_file.now - 1; // -1 for "Back" + if (TERN0(SCROLL_LONG_FILENAMES, shift_ms)) { // If line was shifted + Erase_Menu_Text(select_file.now + 1 + MROWS - index_file); // Erase and + Draw_SDItem(itemnum + 1); // redraw + } + if (select_file.now < index_file - MROWS) { // Cursor past the top + index_file--; // New bottom line + Scroll_Menu(DWIN_SCROLL_DOWN); + if (index_file == MROWS) { + Draw_Back_First(); + TERN_(SCROLL_LONG_FILENAMES, shift_ms = 0); + } + else { + Draw_SDItem(itemnum, 0); // Draw the item (and init shift name) + } + } + else { + Move_Highlight(-1, select_file.now + MROWS - index_file); // Just move highlight + TERN_(SCROLL_LONG_FILENAMES, Init_Shift_Name()); // ...and init the shift name + } + TERN_(SCROLL_LONG_FILENAMES, Init_SDItem_Shift()); // Reset left. Init timer. + } + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + if (select_file.now == 0) { // Back + select_page.set(0); + Goto_MainMenu(); + } + else if (hasUpDir && select_file.now == 1) { // CD-Up + SDCard_Up(); + goto HMI_SelectFileExit; + } + else { + const uint16_t filenum = select_file.now - 1 - hasUpDir; + card.getfilename_sorted(SD_ORDER(filenum, card.get_num_Files())); + + // Enter that folder! + if (card.flag.filenameIsDir) { + SDCard_Folder(card.filename); + goto HMI_SelectFileExit; + } + + // Reset highlight for next entry + select_print.reset(); + select_file.reset(); + + // Start choice and print SD file + HMI_flag.heat_flag = true; + HMI_flag.print_finish = false; + HMI_ValueStruct.show_mode = 0; + + card.openAndPrintFile(card.filename); + + #if FAN_COUNT > 0 + // All fans on for Ender 3 v2 ? + // The slicer should manage this for us. + // for (uint8_t i = 0; i < FAN_COUNT; i++) + // thermalManager.fan_speed[i] = FANON; + #endif + + Goto_PrintProcess(); + } + } +HMI_SelectFileExit: + DWIN_UpdateLCD(); +} + +/* Printing */ +void HMI_Printing() { + ENCODER_DiffState encoder_diffState = get_encoder_state(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + + if (HMI_flag.done_confirm_flag) { + if (encoder_diffState == ENCODER_DIFF_ENTER) { + HMI_flag.done_confirm_flag = false; + dwin_abort_flag = true; + } + return; + } + + // Avoid flicker by updating only the previous menu + if (encoder_diffState == ENCODER_DIFF_CW) { + if (select_print.inc(3)) { + switch (select_print.now) { + case 0: ICON_Tune(); break; + case 1: + ICON_Tune(); + if (printingIsPaused()) ICON_Continue(); else ICON_Pause(); + break; + case 2: + if (printingIsPaused()) ICON_Continue(); else ICON_Pause(); + ICON_Stop(); + break; + } + } + } + else if (encoder_diffState == ENCODER_DIFF_CCW) { + if (select_print.dec()) { + switch (select_print.now) { + case 0: + ICON_Tune(); + if (printingIsPaused()) ICON_Continue(); else ICON_Pause(); + break; + case 1: + if (printingIsPaused()) ICON_Continue(); else ICON_Pause(); + ICON_Stop(); + break; + case 2: ICON_Stop(); break; + } + } + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + switch (select_print.now) { + case 0: // Tune + checkkey = Tune; + HMI_ValueStruct.show_mode = 0; + select_tune.reset(); + index_tune = MROWS; + Draw_Tune_Menu(); + break; + case 1: // Pause + if (HMI_flag.pause_flag) { + ICON_Pause(); + + char cmd[40]; + cmd[0] = '\0'; + + #if ENABLED(PAUSE_HEAT) + #if HAS_HEATED_BED + if (tempbed) sprintf_P(cmd, PSTR("M190 S%i\n"), tempbed); + #endif + #if HAS_HOTEND + if (temphot) sprintf_P(&cmd[strlen(cmd)], PSTR("M109 S%i\n"), temphot); + #endif + #endif + + strcat_P(cmd, PSTR("M24")); + queue.inject(cmd); + } + else { + HMI_flag.select_flag = true; + checkkey = Print_window; + Popup_window_PauseOrStop(); + } + break; + + case 2: // Stop + HMI_flag.select_flag = true; + checkkey = Print_window; + Popup_window_PauseOrStop(); + break; + + default: break; + } + } + DWIN_UpdateLCD(); +} + +/* Pause and Stop window */ +void HMI_PauseOrStop() { + ENCODER_DiffState encoder_diffState = get_encoder_state(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + + if (encoder_diffState == ENCODER_DIFF_CW) + Draw_Select_Highlight(false); + else if (encoder_diffState == ENCODER_DIFF_CCW) + Draw_Select_Highlight(true); + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + if (select_print.now == 1) { // pause window + if (HMI_flag.select_flag) { + HMI_flag.pause_action = true; + ICON_Continue(); + #if ENABLED(POWER_LOSS_RECOVERY) + if (recovery.enabled) recovery.save(true); + #endif + queue.inject_P(PSTR("M25")); + } + else { + // cancel pause + } + Goto_PrintProcess(); + } + else if (select_print.now == 2) { // stop window + if (HMI_flag.select_flag) { + wait_for_heatup = false; // Stop waiting for heater + + #if 0 + // TODO: In ExtUI or MarlinUI add a common stop event + // card.flag.abort_sd_printing = true; + #else + checkkey = Back_Main; + // Wait for planner moves to finish! + if (HMI_flag.home_flag) planner.synchronize(); + card.endFilePrint(); + #ifdef ACTION_ON_CANCEL + host_action_cancel(); + #endif + #ifdef EVENT_GCODE_SD_ABORT + Popup_Window_Home(true); + queue.inject_P(PSTR(EVENT_GCODE_SD_ABORT)); + #endif + dwin_abort_flag = true; + #endif + } + else + Goto_PrintProcess(); // cancel stop + } + } + DWIN_UpdateLCD(); +} + +inline void Draw_Move_Menu() { + Clear_Main_Window(); + + if (HMI_IsChinese()) { + DWIN_Frame_TitleCopy(1, 192, 1, 233, 14); // "Move" + DWIN_Frame_AreaCopy(1, 58, 118, 106, 132, LBLX, MBASE(1)); + DWIN_Frame_AreaCopy(1, 109, 118, 157, 132, LBLX, MBASE(2)); + DWIN_Frame_AreaCopy(1, 160, 118, 209, 132, LBLX, MBASE(3)); + #if HAS_HOTEND + DWIN_Frame_AreaCopy(1, 212, 118, 253, 131, LBLX, MBASE(4)); + #endif + } + else { + #ifdef USE_STRING_HEADINGS + Draw_Title(GET_TEXT_F(MSG_MOVE_AXIS)); + #else + DWIN_Frame_TitleCopy(1, 231, 2, 265, 12); // "Move" + #endif + draw_move_en(MBASE(1)); say_x(36, MBASE(1)); // "Move X" + draw_move_en(MBASE(2)); say_y(36, MBASE(2)); // "Move Y" + draw_move_en(MBASE(3)); say_z(36, MBASE(3)); // "Move Z" + #if HAS_HOTEND + DWIN_Frame_AreaCopy(1, 123, 192, 176, 202, LBLX, MBASE(4)); // "Extruder" + #endif + } + + Draw_Back_First(select_axis.now == 0); + if (select_axis.now) Draw_Menu_Cursor(select_axis.now); + + // Draw separators and icons + LOOP_L_N(i, 3 + ENABLED(HAS_HOTEND)) Draw_Menu_Line(i + 1, ICON_MoveX + i); +} + +#include "../../../libs/buzzer.h" + +void HMI_AudioFeedback(const bool success=true) { + if (success) { + buzzer.tone(100, 659); + buzzer.tone(10, 0); + buzzer.tone(100, 698); + } + else + buzzer.tone(40, 440); +} + +/* Prepare */ +void HMI_Prepare() { + ENCODER_DiffState encoder_diffState = get_encoder_state(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + + // Avoid flicker by updating only the previous menu + if (encoder_diffState == ENCODER_DIFF_CW) { + if (select_prepare.inc(1 + PREPARE_CASE_TOTAL)) { + if (select_prepare.now > MROWS && select_prepare.now > index_prepare) { + index_prepare = select_prepare.now; + + // Scroll up and draw a blank bottom line + Scroll_Menu(DWIN_SCROLL_UP); + Draw_Menu_Icon(MROWS, ICON_Axis + select_prepare.now - 1); + + // Draw "More" icon for sub-menus + if (index_prepare < 7) Draw_More_Icon(MROWS - index_prepare + 1); + + #if HAS_HOTEND + if (index_prepare == PREPARE_CASE_ABS) Item_Prepare_ABS(MROWS); + #endif + #if HAS_PREHEAT + if (index_prepare == PREPARE_CASE_COOL) Item_Prepare_Cool(MROWS); + #endif + if (index_prepare == PREPARE_CASE_LANG) Item_Prepare_Lang(MROWS); + } + else { + Move_Highlight(1, select_prepare.now + MROWS - index_prepare); + } + } + } + else if (encoder_diffState == ENCODER_DIFF_CCW) { + if (select_prepare.dec()) { + if (select_prepare.now < index_prepare - MROWS) { + index_prepare--; + Scroll_Menu(DWIN_SCROLL_DOWN); + + if (index_prepare == MROWS) + Draw_Back_First(); + else + Draw_Menu_Line(0, ICON_Axis + select_prepare.now - 1); + + if (index_prepare < 7) Draw_More_Icon(MROWS - index_prepare + 1); + + if (index_prepare == 6) Item_Prepare_Move(0); + else if (index_prepare == 7) Item_Prepare_Disable(0); + else if (index_prepare == 8) Item_Prepare_Home(0); + } + else { + Move_Highlight(-1, select_prepare.now + MROWS - index_prepare); + } + } + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + switch (select_prepare.now) { + case 0: // Back + select_page.set(1); + Goto_MainMenu(); + break; + case PREPARE_CASE_MOVE: // Axis move + checkkey = AxisMove; + select_axis.reset(); + Draw_Move_Menu(); + + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 216, MBASE(1), current_position.x * MINUNITMULT); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 216, MBASE(2), current_position.y * MINUNITMULT); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 216, MBASE(3), current_position.z * MINUNITMULT); + #if HAS_HOTEND + queue.inject_P(PSTR("G92 E0")); + current_position.e = HMI_ValueStruct.Move_E_scale = 0; + DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 3, 1, 216, MBASE(4), 0); + #endif + break; + case PREPARE_CASE_DISA: // Disable steppers + queue.inject_P(PSTR("M84")); + break; + case PREPARE_CASE_HOME: // Homing + checkkey = Last_Prepare; + index_prepare = MROWS; + queue.inject_P(PSTR("G28")); // G28 will set home_flag + Popup_Window_Home(); + break; + #if HAS_ZOFFSET_ITEM + case PREPARE_CASE_ZOFF: // Z-offset + #if EITHER(HAS_BED_PROBE, BABYSTEPPING) + checkkey = Homeoffset; + HMI_ValueStruct.show_mode = -4; + HMI_ValueStruct.offset_value = BABY_Z_VAR * 100; + DWIN_Draw_Signed_Float(font8x16, Select_Color, 2, 2, 202, MBASE(PREPARE_CASE_ZOFF + MROWS - index_prepare), HMI_ValueStruct.offset_value); + EncoderRate.enabled = true; + #else + // Apply workspace offset, making the current position 0,0,0 + queue.inject_P(PSTR("G92 X0 Y0 Z0")); + HMI_AudioFeedback(); + #endif + break; + #endif + #if HAS_HOTEND + case PREPARE_CASE_PLA: // PLA preheat + thermalManager.setTargetHotend(ui.material_preset[0].hotend_temp, 0); + thermalManager.setTargetBed(ui.material_preset[0].bed_temp); + thermalManager.set_fan_speed(0, ui.material_preset[0].fan_speed); + break; + case PREPARE_CASE_ABS: // ABS preheat + thermalManager.setTargetHotend(ui.material_preset[1].hotend_temp, 0); + thermalManager.setTargetBed(ui.material_preset[1].bed_temp); + thermalManager.set_fan_speed(0, ui.material_preset[1].fan_speed); + break; + #endif + #if HAS_PREHEAT + case PREPARE_CASE_COOL: // Cool + TERN_(HAS_FAN, thermalManager.zero_fan_speeds()); + #if HAS_HOTEND || HAS_HEATED_BED + thermalManager.disable_all_heaters(); + #endif + break; + #endif + case PREPARE_CASE_LANG: // Toggle Language + HMI_ToggleLanguage(); + Draw_Prepare_Menu(); + break; + default: break; + } + } + DWIN_UpdateLCD(); +} + +void Draw_Temperature_Menu() { + Clear_Main_Window(); + + if (HMI_IsChinese()) { + DWIN_Frame_TitleCopy(1, 236, 2, 263, 13); // "Temperature" + #if HAS_HOTEND + DWIN_Frame_AreaCopy(1, 1, 134, 56, 146, LBLX, MBASE(TEMP_CASE_TEMP)); + #endif + #if HAS_HEATED_BED + DWIN_Frame_AreaCopy(1, 58, 134, 113, 146, LBLX, MBASE(TEMP_CASE_BED)); + #endif + #if HAS_FAN + DWIN_Frame_AreaCopy(1, 115, 134, 170, 146, LBLX, MBASE(TEMP_CASE_FAN)); + #endif + #if HAS_HOTEND + DWIN_Frame_AreaCopy(1, 100, 89, 178, 101, LBLX, MBASE(TEMP_CASE_PLA)); + DWIN_Frame_AreaCopy(1, 180, 89, 260, 100, LBLX, MBASE(TEMP_CASE_ABS)); + #endif + } + else { + #ifdef USE_STRING_HEADINGS + Draw_Title(GET_TEXT_F(MSG_TEMPERATURE)); + #if HAS_HOTEND + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(TEMP_CASE_TEMP), GET_TEXT_F(MSG_UBL_SET_TEMP_HOTEND)); + #endif + #if HAS_HEATED_BED + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(TEMP_CASE_BED), GET_TEXT_F(MSG_UBL_SET_TEMP_BED)); + #endif + #if HAS_FAN + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(TEMP_CASE_FAN), GET_TEXT_F(MSG_FAN_SPEED)); + #endif + #if HAS_HOTEND + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(TEMP_CASE_PLA), F("PLA Preheat Settings")); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(TEMP_CASE_ABS), F("ABS Preheat Settings")); + #endif + #else + DWIN_Frame_TitleCopy(1, 56, 16, 141, 28); // "Temperature" + #if HAS_HOTEND + DWIN_Frame_AreaCopy(1, 197, 104, 238, 114, LBLX, MBASE(TEMP_CASE_TEMP)); // Nozzle... + DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX + 44, MBASE(TEMP_CASE_TEMP)); // ...Temperature + #endif + #if HAS_HEATED_BED + DWIN_Frame_AreaCopy(1, 240, 104, 264, 114, LBLX, MBASE(TEMP_CASE_BED)); // Bed... + DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX + 27, MBASE(TEMP_CASE_BED)); // ...Temperature + #endif + #if HAS_FAN + DWIN_Frame_AreaCopy(1, 0, 119, 64, 132, LBLX, MBASE(TEMP_CASE_FAN)); // Fan speed + #endif + #if HAS_HOTEND + DWIN_Frame_AreaCopy(1, 107, 76, 156, 86, LBLX, MBASE(TEMP_CASE_PLA)); // Preheat... + DWIN_Frame_AreaCopy(1, 157, 76, 181, 86, LBLX + 52, MBASE(TEMP_CASE_PLA)); // ...PLA + DWIN_Frame_AreaCopy(1, 131, 119, 182, 132, LBLX + 79, MBASE(TEMP_CASE_PLA)); // PLA setting + DWIN_Frame_AreaCopy(1, 107, 76, 156, 86, LBLX, MBASE(TEMP_CASE_ABS)); // Preheat... + DWIN_Frame_AreaCopy(1, 172, 76, 198, 86, LBLX + 52, MBASE(TEMP_CASE_ABS)); // ...ABS + DWIN_Frame_AreaCopy(1, 131, 119, 182, 132, LBLX + 81, MBASE(TEMP_CASE_ABS)); // ABS setting + #endif + #endif + } + + Draw_Back_First(select_temp.now == 0); + if (select_temp.now) Draw_Menu_Cursor(select_temp.now); + + // Draw icons and lines + uint8_t i = 0; + #define _TMENU_ICON(N) Draw_Menu_Line(++i, ICON_SetEndTemp + (N) - 1) + #if HAS_HOTEND + _TMENU_ICON(TEMP_CASE_TEMP); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(i), thermalManager.temp_hotend[0].target); + #endif + #if HAS_HEATED_BED + _TMENU_ICON(TEMP_CASE_BED); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(i), thermalManager.temp_bed.target); + #endif + #if HAS_FAN + _TMENU_ICON(TEMP_CASE_FAN); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(i), thermalManager.fan_speed[0]); + #endif + #if HAS_HOTEND + // PLA/ABS items have submenus + _TMENU_ICON(TEMP_CASE_PLA); + Draw_More_Icon(i); + _TMENU_ICON(TEMP_CASE_ABS); + Draw_More_Icon(i); + #endif +} + +/* Control */ +void HMI_Control() { + ENCODER_DiffState encoder_diffState = get_encoder_state(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + + // Avoid flicker by updating only the previous menu + if (encoder_diffState == ENCODER_DIFF_CW) { + if (select_control.inc(1 + CONTROL_CASE_TOTAL)) { + if (select_control.now > MROWS && select_control.now > index_control) { + index_control = select_control.now; + Scroll_Menu(DWIN_SCROLL_UP); + Draw_Menu_Icon(MROWS, ICON_Temperature + index_control - 1); + Draw_More_Icon(CONTROL_CASE_TEMP + MROWS - index_control); // Temperature > + Draw_More_Icon(CONTROL_CASE_MOVE + MROWS - index_control); // Motion > + if (index_control > MROWS) { + Draw_More_Icon(CONTROL_CASE_INFO + MROWS - index_control); // Info > + if (HMI_IsChinese()) + DWIN_Frame_AreaCopy(1, 231, 104, 258, 116, LBLX, MBASE(CONTROL_CASE_INFO - 1)); + else + DWIN_Frame_AreaCopy(1, 0, 104, 24, 114, LBLX, MBASE(CONTROL_CASE_INFO - 1)); + } + } + else { + Move_Highlight(1, select_control.now + MROWS - index_control); + } + } + } + else if (encoder_diffState == ENCODER_DIFF_CCW) { + if (select_control.dec()) { + if (select_control.now < index_control - MROWS) { + index_control--; + Scroll_Menu(DWIN_SCROLL_DOWN); + if (index_control == MROWS) + Draw_Back_First(); + else + Draw_Menu_Line(0, ICON_Temperature + select_control.now - 1); + Draw_More_Icon(0 + MROWS - index_control + 1); // Temperature > + Draw_More_Icon(1 + MROWS - index_control + 1); // Motion > + } + else { + Move_Highlight(-1, select_control.now + MROWS - index_control); + } + } + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + switch (select_control.now) { + case 0: // Back + select_page.set(2); + Goto_MainMenu(); + break; + case CONTROL_CASE_TEMP: // Temperature + checkkey = TemperatureID; + HMI_ValueStruct.show_mode = -1; + select_temp.reset(); + Draw_Temperature_Menu(); + break; + case CONTROL_CASE_MOVE: // Motion + checkkey = Motion; + select_motion.reset(); + Draw_Motion_Menu(); + break; + #if ENABLED(EEPROM_SETTINGS) + case CONTROL_CASE_SAVE: { // Write EEPROM + const bool success = settings.save(); + HMI_AudioFeedback(success); + } break; + case CONTROL_CASE_LOAD: { // Read EEPROM + const bool success = settings.load(); + HMI_AudioFeedback(success); + } break; + case CONTROL_CASE_RESET: // Reset EEPROM + settings.reset(); + HMI_AudioFeedback(); + break; + #endif + case CONTROL_CASE_INFO: // Info + checkkey = Info; + Draw_Info_Menu(); + break; + default: break; + } + } + DWIN_UpdateLCD(); +} + + +#if HAS_ONESTEP_LEVELING + + /* Leveling */ + void HMI_Leveling() { + Popup_Window_Leveling(); + DWIN_UpdateLCD(); + queue.inject_P(PSTR("G28O\nG29")); + } + +#endif + +/* Axis Move */ +void HMI_AxisMove() { + ENCODER_DiffState encoder_diffState = get_encoder_state(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + + #if ENABLED(PREVENT_COLD_EXTRUSION) + // popup window resume + if (HMI_flag.ETempTooLow_flag) { + if (encoder_diffState == ENCODER_DIFF_ENTER) { + HMI_flag.ETempTooLow_flag = false; + current_position.e = HMI_ValueStruct.Move_E_scale = 0; + Draw_Move_Menu(); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 216, MBASE(1), HMI_ValueStruct.Move_X_scale); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 216, MBASE(2), HMI_ValueStruct.Move_Y_scale); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 216, MBASE(3), HMI_ValueStruct.Move_Z_scale); + DWIN_Draw_Signed_Float(font8x16, Color_Bg_Black, 3, 1, 216, MBASE(4), 0); + DWIN_UpdateLCD(); + } + return; + } + #endif + + // Avoid flicker by updating only the previous menu + if (encoder_diffState == ENCODER_DIFF_CW) { + if (select_axis.inc(1 + 3 + ENABLED(HAS_HOTEND))) Move_Highlight(1, select_axis.now); + } + else if (encoder_diffState == ENCODER_DIFF_CCW) { + if (select_axis.dec()) Move_Highlight(-1, select_axis.now); + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + switch (select_axis.now) { + case 0: // Back + checkkey = Prepare; + select_prepare.set(1); + index_prepare = MROWS; + Draw_Prepare_Menu(); + break; + case 1: // X axis move + checkkey = Move_X; + HMI_ValueStruct.Move_X_scale = current_position.x * MINUNITMULT; + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 1, 216, MBASE(1), HMI_ValueStruct.Move_X_scale); + EncoderRate.enabled = true; + break; + case 2: // Y axis move + checkkey = Move_Y; + HMI_ValueStruct.Move_Y_scale = current_position.y * MINUNITMULT; + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 1, 216, MBASE(2), HMI_ValueStruct.Move_Y_scale); + EncoderRate.enabled = true; + break; + case 3: // Z axis move + checkkey = Move_Z; + HMI_ValueStruct.Move_Z_scale = current_position.z * MINUNITMULT; + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 1, 216, MBASE(3), HMI_ValueStruct.Move_Z_scale); + EncoderRate.enabled = true; + break; + #if HAS_HOTEND + case 4: // Extruder + // window tips + #ifdef PREVENT_COLD_EXTRUSION + if (thermalManager.temp_hotend[0].celsius < EXTRUDE_MINTEMP) { + HMI_flag.ETempTooLow_flag = true; + Popup_Window_ETempTooLow(); + DWIN_UpdateLCD(); + return; + } + #endif + checkkey = Extruder; + HMI_ValueStruct.Move_E_scale = current_position.e * MINUNITMULT; + DWIN_Draw_Signed_Float(font8x16, Select_Color, 3, 1, 216, MBASE(4), HMI_ValueStruct.Move_E_scale); + EncoderRate.enabled = true; + break; + #endif + } + } + DWIN_UpdateLCD(); +} + +/* TemperatureID */ +void HMI_Temperature() { + ENCODER_DiffState encoder_diffState = get_encoder_state(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + + // Avoid flicker by updating only the previous menu + if (encoder_diffState == ENCODER_DIFF_CW) { + if (select_temp.inc(1 + TEMP_CASE_TOTAL)) Move_Highlight(1, select_temp.now); + } + else if (encoder_diffState == ENCODER_DIFF_CCW) { + if (select_temp.dec()) Move_Highlight(-1, select_temp.now); + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + switch (select_temp.now) { + case 0: // Back + checkkey = Control; + select_control.set(1); + index_control = MROWS; + Draw_Control_Menu(); + break; + #if HAS_HOTEND + case TEMP_CASE_TEMP: // Nozzle temperature + checkkey = ETemp; + HMI_ValueStruct.E_Temp = thermalManager.temp_hotend[0].target; + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(1), thermalManager.temp_hotend[0].target); + EncoderRate.enabled = true; + break; + #endif + #if HAS_HEATED_BED + case TEMP_CASE_BED: // Bed temperature + checkkey = BedTemp; + HMI_ValueStruct.Bed_Temp = thermalManager.temp_bed.target; + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(2), thermalManager.temp_bed.target); + EncoderRate.enabled = true; + break; + #endif + #if HAS_FAN + case TEMP_CASE_FAN: // Fan speed + checkkey = FanSpeed; + HMI_ValueStruct.Fan_speed = thermalManager.fan_speed[0]; + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(3), thermalManager.fan_speed[0]); + EncoderRate.enabled = true; + break; + #endif + #if HAS_HOTEND + case TEMP_CASE_PLA: { // PLA preheat setting + checkkey = PLAPreheat; + select_PLA.reset(); + HMI_ValueStruct.show_mode = -2; + + Clear_Main_Window(); + + if (HMI_IsChinese()) { + DWIN_Frame_TitleCopy(1, 59, 16, 139, 29); // "PLA Settings" + DWIN_Frame_AreaCopy(1, 100, 89, 124, 101, LBLX, MBASE(PREHEAT_CASE_TEMP)); + DWIN_Frame_AreaCopy(1, 1, 134, 56, 146, LBLX + 24, MBASE(PREHEAT_CASE_TEMP)); // PLA nozzle temp + #if HAS_HEATED_BED + DWIN_Frame_AreaCopy(1, 100, 89, 124, 101, LBLX, MBASE(PREHEAT_CASE_BED)); + DWIN_Frame_AreaCopy(1, 58, 134, 113, 146, LBLX + 24, MBASE(PREHEAT_CASE_BED)); // PLA bed temp + #endif + #if HAS_FAN + DWIN_Frame_AreaCopy(1, 100, 89, 124, 101, LBLX, MBASE(PREHEAT_CASE_FAN)); + DWIN_Frame_AreaCopy(1, 115, 134, 170, 146, LBLX + 24, MBASE(PREHEAT_CASE_FAN)); // PLA fan speed + #endif + #if ENABLED(EEPROM_SETTINGS) + DWIN_Frame_AreaCopy(1, 72, 148, 151, 162, LBLX, MBASE(PREHEAT_CASE_SAVE)); // Save PLA configuration + #endif + } + else { + #ifdef USE_STRING_HEADINGS + Draw_Title("PLA Settings"); // TODO: GET_TEXT_F + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(PREHEAT_CASE_TEMP), F("Nozzle Temp")); + #if HAS_HEATED_BED + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(PREHEAT_CASE_BED), F("Bed Temp")); + #endif + #if HAS_FAN + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(PREHEAT_CASE_FAN), GET_TEXT_F(MSG_FAN_SPEED)); + #endif + #if ENABLED(EEPROM_SETTINGS) + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(PREHEAT_CASE_SAVE), GET_TEXT_F(MSG_STORE_EEPROM)); + #endif + #else + DWIN_Frame_TitleCopy(1, 56, 16, 141, 28); // "PLA Settings" + DWIN_Frame_AreaCopy(1, 157, 76, 181, 86, LBLX, MBASE(PREHEAT_CASE_TEMP)); + DWIN_Frame_AreaCopy(1, 197, 104, 238, 114, LBLX + 27, MBASE(PREHEAT_CASE_TEMP)); + DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX + 71, MBASE(PREHEAT_CASE_TEMP)); // PLA nozzle temp + #if HAS_HEATED_BED + DWIN_Frame_AreaCopy(1, 157, 76, 181, 86, LBLX, MBASE(PREHEAT_CASE_BED) + 3); + DWIN_Frame_AreaCopy(1, 240, 104, 264, 114, LBLX + 27, MBASE(PREHEAT_CASE_BED) + 3); + DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX + 54, MBASE(PREHEAT_CASE_BED) + 3); // PLA bed temp + #endif + #if HAS_FAN + DWIN_Frame_AreaCopy(1, 157, 76, 181, 86, LBLX, MBASE(PREHEAT_CASE_FAN)); + DWIN_Frame_AreaCopy(1, 0, 119, 64, 132, LBLX + 27, MBASE(PREHEAT_CASE_FAN)); // PLA fan speed + #endif + #if ENABLED(EEPROM_SETTINGS) + DWIN_Frame_AreaCopy(1, 97, 165, 229, 177, LBLX, MBASE(PREHEAT_CASE_SAVE)); // Save PLA configuration + #endif + #endif + } + + Draw_Back_First(); + + uint8_t i = 0; + Draw_Menu_Line(++i, ICON_SetEndTemp); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(i), ui.material_preset[0].hotend_temp); + #if HAS_HEATED_BED + Draw_Menu_Line(++i, ICON_SetBedTemp); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(i), ui.material_preset[0].bed_temp); + #endif + #if HAS_FAN + Draw_Menu_Line(++i, ICON_FanSpeed); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(i), ui.material_preset[0].fan_speed); + #endif + #if ENABLED(EEPROM_SETTINGS) + Draw_Menu_Line(++i, ICON_WriteEEPROM); + #endif + } break; + + case TEMP_CASE_ABS: { // ABS preheat setting + checkkey = ABSPreheat; + select_ABS.reset(); + HMI_ValueStruct.show_mode = -3; + + Clear_Main_Window(); + + if (HMI_IsChinese()) { + DWIN_Frame_TitleCopy(1, 142, 16, 223, 29); // "ABS Settings" + + DWIN_Frame_AreaCopy(1, 180, 89, 204, 100, LBLX, MBASE(PREHEAT_CASE_TEMP)); + DWIN_Frame_AreaCopy(1, 1, 134, 56, 146, LBLX + 24, MBASE(PREHEAT_CASE_TEMP)); // ABS nozzle temp + #if HAS_HEATED_BED + DWIN_Frame_AreaCopy(1, 180, 89, 204, 100, LBLX, MBASE(PREHEAT_CASE_BED)); + DWIN_Frame_AreaCopy(1, 58, 134, 113, 146, LBLX + 24, MBASE(PREHEAT_CASE_BED)); // ABS bed temp + #endif + #if HAS_FAN + DWIN_Frame_AreaCopy(1, 180, 89, 204, 100, LBLX, MBASE(PREHEAT_CASE_FAN)); + DWIN_Frame_AreaCopy(1, 115, 134, 170, 146, LBLX + 24, MBASE(PREHEAT_CASE_FAN)); // ABS fan speed + #endif + #if ENABLED(EEPROM_SETTINGS) + DWIN_Frame_AreaCopy(1, 72, 148, 151, 162, LBLX, MBASE(PREHEAT_CASE_SAVE)); + DWIN_Frame_AreaCopy(1, 180, 89, 204, 100, LBLX + 28, MBASE(PREHEAT_CASE_SAVE) + 2); // Save ABS configuration + #endif + } + else { + #ifdef USE_STRING_HEADINGS + Draw_Title("ABS Settings"); // TODO: GET_TEXT_F + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(PREHEAT_CASE_TEMP), F("Nozzle Temp")); + #if HAS_HEATED_BED + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(PREHEAT_CASE_BED), F("Bed Temp")); + #endif + #if HAS_FAN + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(PREHEAT_CASE_FAN), GET_TEXT_F(MSG_FAN_SPEED)); + #endif + #if ENABLED(EEPROM_SETTINGS) + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(PREHEAT_CASE_SAVE), GET_TEXT_F(MSG_STORE_EEPROM)); + #endif + #else + DWIN_Frame_TitleCopy(1, 56, 16, 141, 28); // "ABS Settings" + DWIN_Frame_AreaCopy(1, 172, 76, 198, 86, LBLX, MBASE(PREHEAT_CASE_TEMP)); + DWIN_Frame_AreaCopy(1, 197, 104, 238, 114, LBLX + 27, MBASE(PREHEAT_CASE_TEMP)); + DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX + 71, MBASE(PREHEAT_CASE_TEMP)); // ABS nozzle temp + #if HAS_HEATED_BED + DWIN_Frame_AreaCopy(1, 172, 76, 198, 86, LBLX, MBASE(PREHEAT_CASE_BED) + 3); + DWIN_Frame_AreaCopy(1, 240, 104, 264, 114, LBLX + 27, MBASE(PREHEAT_CASE_BED) + 3); + DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX + 54, MBASE(PREHEAT_CASE_BED) + 3); // ABS bed temp + #endif + #if HAS_FAN + DWIN_Frame_AreaCopy(1, 172, 76, 198, 86, LBLX, MBASE(PREHEAT_CASE_FAN)); + DWIN_Frame_AreaCopy(1, 0, 119, 64, 132, LBLX + 27, MBASE(PREHEAT_CASE_FAN)); // ABS fan speed + #endif + #if ENABLED(EEPROM_SETTINGS) + DWIN_Frame_AreaCopy(1, 97, 165, 229, 177, LBLX, MBASE(PREHEAT_CASE_SAVE)); + DWIN_Frame_AreaCopy(1, 172, 76, 198, 86, LBLX + 33, MBASE(PREHEAT_CASE_SAVE)); // Save ABS configuration + #endif + #endif + } + + Draw_Back_First(); + + uint8_t i = 0; + Draw_Menu_Line(++i, ICON_SetEndTemp); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(i), ui.material_preset[1].hotend_temp); + #if HAS_HEATED_BED + Draw_Menu_Line(++i, ICON_SetBedTemp); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(i), ui.material_preset[1].bed_temp); + #endif + #if HAS_FAN + Draw_Menu_Line(++i, ICON_FanSpeed); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 216, MBASE(i), ui.material_preset[1].fan_speed); + #endif + #if ENABLED(EEPROM_SETTINGS) + Draw_Menu_Line(++i, ICON_WriteEEPROM); + #endif + + } break; + + #endif // HAS_HOTEND + } + } + DWIN_UpdateLCD(); +} + +inline void Draw_Max_Speed_Menu() { + Clear_Main_Window(); + + if (HMI_IsChinese()) { + DWIN_Frame_TitleCopy(1, 1, 16, 28, 28); // "Max Speed (mm/s)" + + auto say_max_speed = [](const uint16_t row) { + DWIN_Frame_AreaCopy(1, 173, 133, 228, 147, LBLX, row); // "Max speed" + }; + + say_max_speed(MBASE(1)); // "Max speed" + DWIN_Frame_AreaCopy(1, 229, 133, 236, 147, LBLX + 58, MBASE(1)); // X + say_max_speed(MBASE(2)); // "Max speed" + DWIN_Frame_AreaCopy(1, 1, 150, 7, 160, LBLX + 58, MBASE(2) + 3); // Y + say_max_speed(MBASE(3)); // "Max speed" + DWIN_Frame_AreaCopy(1, 9, 150, 16, 160, LBLX + 58, MBASE(3) + 3); // Z + #if HAS_HOTEND + say_max_speed(MBASE(4)); // "Max speed" + DWIN_Frame_AreaCopy(1, 18, 150, 25, 160, LBLX + 58, MBASE(4) + 3); // E + #endif + } + else { + #ifdef USE_STRING_HEADINGS + Draw_Title("Max Speed (mm/s)"); // TODO: GET_TEXT_F + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(1), F("Max Feedrate X")); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(2), F("Max Feedrate Y")); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(3), F("Max Feedrate Z")); + #if HAS_HOTEND + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(4), F("Max Feedrate E")); + #endif + #else + DWIN_Frame_TitleCopy(1, 144, 16, 189, 26); // "Max Speed (mm/s)" + + draw_max_en(MBASE(1)); // "Max" + DWIN_Frame_AreaCopy(1, 184, 119, 234, 132, LBLX + 27, MBASE(1)); // "Speed X" + + draw_max_en(MBASE(2)); // "Max" + draw_speed_en(27, MBASE(2)); // "Speed" + say_y(70, MBASE(2)); // "Y" + + draw_max_en(MBASE(3)); // "Max" + draw_speed_en(27, MBASE(3)); // "Speed" + say_z(70, MBASE(3)); // "Z" + + #if HAS_HOTEND + draw_max_en(MBASE(4)); // "Max" + draw_speed_en(27, MBASE(4)); // "Speed" + say_e(70, MBASE(4)); // "E" + #endif + #endif + } + + Draw_Back_First(); + LOOP_L_N(i, 3 + ENABLED(HAS_HOTEND)) Draw_Menu_Line(i + 1, ICON_MaxSpeedX + i); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 4, 210, MBASE(1), planner.settings.max_feedrate_mm_s[X_AXIS]); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 4, 210, MBASE(2), planner.settings.max_feedrate_mm_s[Y_AXIS]); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 4, 210, MBASE(3), planner.settings.max_feedrate_mm_s[Z_AXIS]); + #if HAS_HOTEND + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 4, 210, MBASE(4), planner.settings.max_feedrate_mm_s[E_AXIS]); + #endif +} + +inline void Draw_Max_Accel_Menu() { + Clear_Main_Window(); + + if (HMI_IsChinese()) { + DWIN_Frame_TitleCopy(1, 1, 16, 28, 28); // "Acceleration" + + DWIN_Frame_AreaCopy(1, 173, 133, 200, 147, LBLX, MBASE(1)); + DWIN_Frame_AreaCopy(1, 28, 149, 69, 161, LBLX + 27, MBASE(1) + 1); + DWIN_Frame_AreaCopy(1, 229, 133, 236, 147, LBLX + 71, MBASE(1)); // Max acceleration X + DWIN_Frame_AreaCopy(1, 173, 133, 200, 147, LBLX, MBASE(2)); + DWIN_Frame_AreaCopy(1, 28, 149, 69, 161, LBLX + 27, MBASE(2) + 1); + DWIN_Frame_AreaCopy(1, 1, 150, 7, 160, LBLX + 71, MBASE(2) + 2); // Max acceleration Y + DWIN_Frame_AreaCopy(1, 173, 133, 200, 147, LBLX, MBASE(3)); + DWIN_Frame_AreaCopy(1, 28, 149, 69, 161, LBLX + 27, MBASE(3) + 1); + DWIN_Frame_AreaCopy(1, 9, 150, 16, 160, LBLX + 71, MBASE(3) + 2); // Max acceleration Z + #if HAS_HOTEND + DWIN_Frame_AreaCopy(1, 173, 133, 200, 147, LBLX, MBASE(4)); + DWIN_Frame_AreaCopy(1, 28, 149, 69, 161, LBLX + 27, MBASE(4) + 1); + DWIN_Frame_AreaCopy(1, 18, 150, 25, 160, LBLX + 71, MBASE(4) + 2); // Max acceleration E + #endif + } + else { + #ifdef USE_STRING_HEADINGS + Draw_Title(GET_TEXT_F(MSG_ACCELERATION)); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(1), F("Max Accel X")); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(2), F("Max Accel Y")); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(3), F("Max Accel Z")); + #if HAS_HOTEND + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(4), F("Max Accel E")); + #endif + #else + DWIN_Frame_TitleCopy(1, 144, 16, 189, 26); // "Acceleration" + draw_max_accel_en(MBASE(1)); say_x(108, MBASE(1)); // "Max Acceleration X" + draw_max_accel_en(MBASE(2)); say_y(108, MBASE(2)); // "Max Acceleration Y" + draw_max_accel_en(MBASE(3)); say_z(108, MBASE(3)); // "Max Acceleration Z" + #if HAS_HOTEND + draw_max_accel_en(MBASE(4)); say_e(108, MBASE(4)); // "Max Acceleration E" + #endif + #endif + } + + Draw_Back_First(); + LOOP_L_N(i, 3 + ENABLED(HAS_HOTEND)) Draw_Menu_Line(i + 1, ICON_MaxAccX + i); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 4, 210, MBASE(1), planner.settings.max_acceleration_mm_per_s2[X_AXIS]); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 4, 210, MBASE(2), planner.settings.max_acceleration_mm_per_s2[Y_AXIS]); + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 4, 210, MBASE(3), planner.settings.max_acceleration_mm_per_s2[Z_AXIS]); + #if HAS_HOTEND + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 4, 210, MBASE(4), planner.settings.max_acceleration_mm_per_s2[E_AXIS]); + #endif +} + +inline void Draw_Max_Jerk_Menu() { + Clear_Main_Window(); + + if (HMI_IsChinese()) { + DWIN_Frame_TitleCopy(1, 1, 16, 28, 28); // "Jerk" + + DWIN_Frame_AreaCopy(1, 173, 133, 200, 147, LBLX , MBASE(1)); + DWIN_Frame_AreaCopy(1, 1, 180, 28, 192, LBLX + 27, MBASE(1) + 1); + DWIN_Frame_AreaCopy(1, 202, 133, 228, 147, LBLX + 53, MBASE(1)); + DWIN_Frame_AreaCopy(1, 229, 133, 236, 147, LBLX + 83, MBASE(1)); // Max Jerk speed X + DWIN_Frame_AreaCopy(1, 173, 133, 200, 147, LBLX , MBASE(2)); + DWIN_Frame_AreaCopy(1, 1, 180, 28, 192, LBLX + 27, MBASE(2) + 1); + DWIN_Frame_AreaCopy(1, 202, 133, 228, 147, LBLX + 53, MBASE(2)); + DWIN_Frame_AreaCopy(1, 1, 150, 7, 160, LBLX + 83, MBASE(2) + 3); // Max Jerk speed Y + DWIN_Frame_AreaCopy(1, 173, 133, 200, 147, LBLX , MBASE(3)); + DWIN_Frame_AreaCopy(1, 1, 180, 28, 192, LBLX + 27, MBASE(3) + 1); + DWIN_Frame_AreaCopy(1, 202, 133, 228, 147, LBLX + 53, MBASE(3)); + DWIN_Frame_AreaCopy(1, 9, 150, 16, 160, LBLX + 83, MBASE(3) + 3); // Max Jerk speed Z + #if HAS_HOTEND + DWIN_Frame_AreaCopy(1, 173, 133, 200, 147, LBLX , MBASE(4)); + DWIN_Frame_AreaCopy(1, 1, 180, 28, 192, LBLX + 27, MBASE(4) + 1); + DWIN_Frame_AreaCopy(1, 202, 133, 228, 147, LBLX + 53, MBASE(4)); + DWIN_Frame_AreaCopy(1, 18, 150, 25, 160, LBLX + 83, MBASE(4) + 3); // Max Jerk speed E + #endif + } + else { + #ifdef USE_STRING_HEADINGS + Draw_Title(GET_TEXT_F(MSG_JERK)); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(1), F("Max Jerk X")); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(2), F("Max Jerk Y")); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(3), F("Max Jerk Z")); + #if HAS_HOTEND + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(4), F("Max Jerk E")); + #endif + #else + DWIN_Frame_TitleCopy(1, 144, 16, 189, 26); // "Jerk" + draw_max_en(MBASE(1)); // "Max" + draw_jerk_en(MBASE(1)); // "Jerk" + draw_speed_en(72, MBASE(1)); // "Speed" + say_x(115, MBASE(1)); // "X" + + draw_max_en(MBASE(2)); // "Max" + draw_jerk_en(MBASE(2)); // "Jerk" + draw_speed_en(72, MBASE(2)); // "Speed" + say_y(115, MBASE(2)); // "Y" + + draw_max_en(MBASE(3)); // "Max" + draw_jerk_en(MBASE(3)); // "Jerk" + draw_speed_en(72, MBASE(3)); // "Speed" + say_z(115, MBASE(3)); // "Z" + + #if HAS_HOTEND + draw_max_en(MBASE(4)); // "Max" + draw_jerk_en(MBASE(4)); // "Jerk" + draw_speed_en(72, MBASE(4)); // "Speed" + say_e(115, MBASE(4)); // "E" + #endif + #endif + } + + Draw_Back_First(); + LOOP_L_N(i, 3 + ENABLED(HAS_HOTEND)) Draw_Menu_Line(i + 1, ICON_MaxSpeedJerkX + i); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 210, MBASE(1), planner.max_jerk[X_AXIS] * MINUNITMULT); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 210, MBASE(2), planner.max_jerk[Y_AXIS] * MINUNITMULT); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 210, MBASE(3), planner.max_jerk[Z_AXIS] * MINUNITMULT); + #if HAS_HOTEND + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 210, MBASE(4), planner.max_jerk[E_AXIS] * MINUNITMULT); + #endif +} + +inline void Draw_Steps_Menu() { + Clear_Main_Window(); + + if (HMI_IsChinese()) { + DWIN_Frame_TitleCopy(1, 1, 16, 28, 28); // "Steps per mm" + + DWIN_Frame_AreaCopy(1, 153, 148, 194, 161, LBLX, MBASE(1)); + DWIN_Frame_AreaCopy(1, 229, 133, 236, 147, LBLX + 44, MBASE(1)); // Transmission Ratio X + DWIN_Frame_AreaCopy(1, 153, 148, 194, 161, LBLX, MBASE(2)); + DWIN_Frame_AreaCopy(1, 1, 150, 7, 160, LBLX + 44, MBASE(2) + 3); // Transmission Ratio Y + DWIN_Frame_AreaCopy(1, 153, 148, 194, 161, LBLX, MBASE(3)); + DWIN_Frame_AreaCopy(1, 9, 150, 16, 160, LBLX + 44, MBASE(3) + 3); // Transmission Ratio Z + #if HAS_HOTEND + DWIN_Frame_AreaCopy(1, 153, 148, 194, 161, LBLX, MBASE(4)); + DWIN_Frame_AreaCopy(1, 18, 150, 25, 160, LBLX + 44, MBASE(4) + 3); // Transmission Ratio E + #endif + } + else { + #ifdef USE_STRING_HEADINGS + Draw_Title(GET_TEXT_F(MSG_STEPS_PER_MM)); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(1), F("Steps/mm X")); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(2), F("Steps/mm Y")); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(3), F("Steps/mm Z")); + #if HAS_HOTEND + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(4), F("Steps/mm E")); + #endif + #else + DWIN_Frame_TitleCopy(1, 144, 16, 189, 26); // "Steps per mm" + draw_steps_per_mm(MBASE(1)); say_x(103, MBASE(1)); // "Steps-per-mm X" + draw_steps_per_mm(MBASE(2)); say_y(103, MBASE(2)); // "Y" + draw_steps_per_mm(MBASE(3)); say_z(103, MBASE(3)); // "Z" + #if HAS_HOTEND + draw_steps_per_mm(MBASE(4)); say_e(103, MBASE(4)); // "E" + #endif + #endif + } + + Draw_Back_First(); + LOOP_L_N(i, 3 + ENABLED(HAS_HOTEND)) Draw_Menu_Line(i + 1, ICON_StepX + i); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 210, MBASE(1), planner.settings.axis_steps_per_mm[X_AXIS] * MINUNITMULT); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 210, MBASE(2), planner.settings.axis_steps_per_mm[Y_AXIS] * MINUNITMULT); + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 210, MBASE(3), planner.settings.axis_steps_per_mm[Z_AXIS] * MINUNITMULT); + #if HAS_HOTEND + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Color_Bg_Black, 3, 1, 210, MBASE(4), planner.settings.axis_steps_per_mm[E_AXIS] * MINUNITMULT); + #endif +} + +/* Motion */ +void HMI_Motion() { + ENCODER_DiffState encoder_diffState = get_encoder_state(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + + // Avoid flicker by updating only the previous menu + if (encoder_diffState == ENCODER_DIFF_CW) { + if (select_motion.inc(1 + MOTION_CASE_TOTAL)) Move_Highlight(1, select_motion.now); + } + else if (encoder_diffState == ENCODER_DIFF_CCW) { + if (select_motion.dec()) Move_Highlight(-1, select_motion.now); + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + switch (select_motion.now) { + case 0: // Back + checkkey = Control; + select_control.set(CONTROL_CASE_MOVE); + index_control = MROWS; + Draw_Control_Menu(); + break; + case MOTION_CASE_RATE: // Max speed + checkkey = MaxSpeed; + select_speed.reset(); + Draw_Max_Speed_Menu(); + break; + case MOTION_CASE_ACCEL: // Max acceleration + checkkey = MaxAcceleration; + select_acc.reset(); + Draw_Max_Accel_Menu(); + break; + #if HAS_CLASSIC_JERK + case MOTION_CASE_JERK: // Max jerk + checkkey = MaxJerk; + select_jerk.reset(); + Draw_Max_Jerk_Menu(); + break; + #endif + case MOTION_CASE_STEPS: // Steps per mm + checkkey = Step; + select_step.reset(); + Draw_Steps_Menu(); + break; + default: break; + } + } + DWIN_UpdateLCD(); +} + +/* Info */ +void HMI_Info() { + ENCODER_DiffState encoder_diffState = get_encoder_state(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + if (encoder_diffState == ENCODER_DIFF_ENTER) { + #if HAS_ONESTEP_LEVELING + checkkey = Control; + select_control.set(CONTROL_CASE_INFO); + Draw_Control_Menu(); + #else + select_page.set(3); + Goto_MainMenu(); + #endif + } + DWIN_UpdateLCD(); +} + +/* Tune */ +void HMI_Tune() { + ENCODER_DiffState encoder_diffState = get_encoder_state(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + + // Avoid flicker by updating only the previous menu + if (encoder_diffState == ENCODER_DIFF_CW) { + if (select_tune.inc(1 + TUNE_CASE_TOTAL)) { + if (select_tune.now > MROWS && select_tune.now > index_tune) { + index_tune = select_tune.now; + Scroll_Menu(DWIN_SCROLL_UP); + } + else { + Move_Highlight(1, select_tune.now + MROWS - index_tune); + } + } + } + else if (encoder_diffState == ENCODER_DIFF_CCW) { + if (select_tune.dec()) { + if (select_tune.now < index_tune - MROWS) { + index_tune--; + Scroll_Menu(DWIN_SCROLL_DOWN); + if (index_tune == MROWS) Draw_Back_First(); + } + else { + Move_Highlight(-1, select_tune.now + MROWS - index_tune); + } + } + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + switch (select_tune.now) { + case 0: { // Back + select_print.set(0); + Goto_PrintProcess(); + } + break; + case TUNE_CASE_SPEED: // Print speed + checkkey = PrintSpeed; + HMI_ValueStruct.print_speed = feedrate_percentage; + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(TUNE_CASE_SPEED + MROWS - index_tune), feedrate_percentage); + EncoderRate.enabled = true; + break; + #if HAS_HOTEND + case TUNE_CASE_TEMP: // Nozzle temp + checkkey = ETemp; + HMI_ValueStruct.E_Temp = thermalManager.temp_hotend[0].target; + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(TUNE_CASE_TEMP + MROWS - index_tune), thermalManager.temp_hotend[0].target); + EncoderRate.enabled = true; + break; + #endif + #if HAS_HEATED_BED + case TUNE_CASE_BED: // Bed temp + checkkey = BedTemp; + HMI_ValueStruct.Bed_Temp = thermalManager.temp_bed.target; + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(TUNE_CASE_BED + MROWS - index_tune), thermalManager.temp_bed.target); + EncoderRate.enabled = true; + break; + #endif + #if HAS_FAN + case TUNE_CASE_FAN: // Fan speed + checkkey = FanSpeed; + HMI_ValueStruct.Fan_speed = thermalManager.fan_speed[0]; + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(TUNE_CASE_FAN + MROWS - index_tune), thermalManager.fan_speed[0]); + EncoderRate.enabled = true; + break; + #endif + #if HAS_ZOFFSET_ITEM + case TUNE_CASE_ZOFF: // Z-offset + #if EITHER(HAS_BED_PROBE, BABYSTEPPING) + checkkey = Homeoffset; + HMI_ValueStruct.offset_value = BABY_Z_VAR * 100; + DWIN_Draw_Signed_Float(font8x16, Select_Color, 2, 2, 202, MBASE(TUNE_CASE_ZOFF + MROWS - index_tune), HMI_ValueStruct.offset_value); + EncoderRate.enabled = true; + #else + // Apply workspace offset, making the current position 0,0,0 + queue.inject_P(PSTR("G92 X0 Y0 Z0")); + HMI_AudioFeedback(); + #endif + break; + #endif + default: break; + } + } + DWIN_UpdateLCD(); +} + +#if HAS_PREHEAT + + /* PLA Preheat */ + void HMI_PLAPreheatSetting() { + ENCODER_DiffState encoder_diffState = get_encoder_state(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + + // Avoid flicker by updating only the previous menu + if (encoder_diffState == ENCODER_DIFF_CW) { + if (select_PLA.inc(1 + PREHEAT_CASE_TOTAL)) Move_Highlight(1, select_PLA.now); + } + else if (encoder_diffState == ENCODER_DIFF_CCW) { + if (select_PLA.dec()) Move_Highlight(-1, select_PLA.now); + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + switch (select_PLA.now) { + case 0: // Back + checkkey = TemperatureID; + select_temp.now = TEMP_CASE_PLA; + HMI_ValueStruct.show_mode = -1; + Draw_Temperature_Menu(); + break; + #if HAS_HOTEND + case PREHEAT_CASE_TEMP: // Nozzle temperature + checkkey = ETemp; + HMI_ValueStruct.E_Temp = ui.material_preset[0].hotend_temp; + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(PREHEAT_CASE_TEMP), ui.material_preset[0].hotend_temp); + EncoderRate.enabled = true; + break; + #endif + #if HAS_HEATED_BED + case PREHEAT_CASE_BED: // Bed temperature + checkkey = BedTemp; + HMI_ValueStruct.Bed_Temp = ui.material_preset[0].bed_temp; + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(PREHEAT_CASE_BED), ui.material_preset[0].bed_temp); + EncoderRate.enabled = true; + break; + #endif + #if HAS_FAN + case PREHEAT_CASE_FAN: // Fan speed + checkkey = FanSpeed; + HMI_ValueStruct.Fan_speed = ui.material_preset[0].fan_speed; + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(PREHEAT_CASE_FAN), ui.material_preset[0].fan_speed); + EncoderRate.enabled = true; + break; + #endif + #if ENABLED(EEPROM_SETTINGS) + case 4: { // Save PLA configuration + const bool success = settings.save(); + HMI_AudioFeedback(success); + } break; + #endif + default: break; + } + } + DWIN_UpdateLCD(); + } + + /* ABS Preheat */ + void HMI_ABSPreheatSetting() { + ENCODER_DiffState encoder_diffState = get_encoder_state(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + + // Avoid flicker by updating only the previous menu + if (encoder_diffState == ENCODER_DIFF_CW) { + if (select_ABS.inc(1 + PREHEAT_CASE_TOTAL)) Move_Highlight(1, select_ABS.now); + } + else if (encoder_diffState == ENCODER_DIFF_CCW) { + if (select_ABS.dec()) Move_Highlight(-1, select_ABS.now); + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + switch (select_ABS.now) { + case 0: // Back + checkkey = TemperatureID; + select_temp.now = TEMP_CASE_ABS; + HMI_ValueStruct.show_mode = -1; + Draw_Temperature_Menu(); + break; + #if HAS_HOTEND + case PREHEAT_CASE_TEMP: // Set nozzle temperature + checkkey = ETemp; + HMI_ValueStruct.E_Temp = ui.material_preset[1].hotend_temp; + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(PREHEAT_CASE_TEMP), ui.material_preset[1].hotend_temp); + EncoderRate.enabled = true; + break; + #endif + #if HAS_HEATED_BED + case PREHEAT_CASE_BED: // Set bed temperature + checkkey = BedTemp; + HMI_ValueStruct.Bed_Temp = ui.material_preset[1].bed_temp; + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(PREHEAT_CASE_BED), ui.material_preset[1].bed_temp); + EncoderRate.enabled = true; + break; + #endif + #if HAS_FAN + case PREHEAT_CASE_FAN: // Set fan speed + checkkey = FanSpeed; + HMI_ValueStruct.Fan_speed = ui.material_preset[1].fan_speed; + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 216, MBASE(PREHEAT_CASE_FAN), ui.material_preset[1].fan_speed); + EncoderRate.enabled = true; + break; + #endif + #if ENABLED(EEPROM_SETTINGS) + case PREHEAT_CASE_SAVE: { // Save ABS configuration + const bool success = settings.save(); + HMI_AudioFeedback(success); + } break; + #endif + default: break; + } + } + DWIN_UpdateLCD(); + } + +#endif + +/* Max Speed */ +void HMI_MaxSpeed() { + ENCODER_DiffState encoder_diffState = get_encoder_state(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + + // Avoid flicker by updating only the previous menu + if (encoder_diffState == ENCODER_DIFF_CW) { + if (select_speed.inc(1 + 3 + ENABLED(HAS_HOTEND))) Move_Highlight(1, select_speed.now); + } + else if (encoder_diffState == ENCODER_DIFF_CCW) { + if (select_speed.dec()) Move_Highlight(-1, select_speed.now); + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + if (WITHIN(select_speed.now, 1, 4)) { + checkkey = MaxSpeed_value; + HMI_flag.feedspeed_axis = AxisEnum(select_speed.now - 1); + HMI_ValueStruct.Max_Feedspeed = planner.settings.max_feedrate_mm_s[HMI_flag.feedspeed_axis]; + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 4, 210, MBASE(select_speed.now), HMI_ValueStruct.Max_Feedspeed); + EncoderRate.enabled = true; + } + else { // Back + checkkey = Motion; + select_motion.now = MOTION_CASE_RATE; + Draw_Motion_Menu(); + } + } + DWIN_UpdateLCD(); +} + +/* Max Acceleration */ +void HMI_MaxAcceleration() { + ENCODER_DiffState encoder_diffState = get_encoder_state(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + + // Avoid flicker by updating only the previous menu + if (encoder_diffState == ENCODER_DIFF_CW) { + if (select_acc.inc(1 + 3 + ENABLED(HAS_HOTEND))) Move_Highlight(1, select_acc.now); + } + else if (encoder_diffState == ENCODER_DIFF_CCW) { + if (select_acc.dec()) Move_Highlight(-1, select_acc.now); + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + if (WITHIN(select_acc.now, 1, 4)) { + checkkey = MaxAcceleration_value; + HMI_flag.acc_axis = AxisEnum(select_acc.now - 1); + HMI_ValueStruct.Max_Acceleration = planner.settings.max_acceleration_mm_per_s2[HMI_flag.acc_axis]; + DWIN_Draw_IntValue(true, true, 0, font8x16, Color_White, Select_Color, 4, 210, MBASE(select_acc.now), HMI_ValueStruct.Max_Acceleration); + EncoderRate.enabled = true; + } + else { // Back + checkkey = Motion; + select_motion.now = MOTION_CASE_ACCEL; + Draw_Motion_Menu(); + } + } + DWIN_UpdateLCD(); +} + +#if HAS_CLASSIC_JERK + /* Max Jerk */ + void HMI_MaxJerk() { + ENCODER_DiffState encoder_diffState = get_encoder_state(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + + // Avoid flicker by updating only the previous menu + if (encoder_diffState == ENCODER_DIFF_CW) { + if (select_jerk.inc(1 + 3 + ENABLED(HAS_HOTEND))) Move_Highlight(1, select_jerk.now); + } + else if (encoder_diffState == ENCODER_DIFF_CCW) { + if (select_jerk.dec()) Move_Highlight(-1, select_jerk.now); + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + if (WITHIN(select_jerk.now, 1, 4)) { + checkkey = MaxJerk_value; + HMI_flag.jerk_axis = AxisEnum(select_jerk.now - 1); + HMI_ValueStruct.Max_Jerk = planner.max_jerk[HMI_flag.jerk_axis] * MINUNITMULT; + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 1, 210, MBASE(select_jerk.now), HMI_ValueStruct.Max_Jerk); + EncoderRate.enabled = true; + } + else { // Back + checkkey = Motion; + select_motion.now = MOTION_CASE_JERK; + Draw_Motion_Menu(); + } + } + DWIN_UpdateLCD(); + } +#endif // HAS_CLASSIC_JERK + +/* Step */ +void HMI_Step() { + ENCODER_DiffState encoder_diffState = get_encoder_state(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + + // Avoid flicker by updating only the previous menu + if (encoder_diffState == ENCODER_DIFF_CW) { + if (select_step.inc(1 + 3 + ENABLED(HAS_HOTEND))) Move_Highlight(1, select_step.now); + } + else if (encoder_diffState == ENCODER_DIFF_CCW) { + if (select_step.dec()) Move_Highlight(-1, select_step.now); + } + else if (encoder_diffState == ENCODER_DIFF_ENTER) { + if (WITHIN(select_step.now, 1, 4)) { + checkkey = Step_value; + HMI_flag.step_axis = AxisEnum(select_step.now - 1); + HMI_ValueStruct.Max_Step = planner.settings.axis_steps_per_mm[HMI_flag.step_axis] * MINUNITMULT; + DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 1, 210, MBASE(select_step.now), HMI_ValueStruct.Max_Step); + EncoderRate.enabled = true; + } + else { // Back + checkkey = Motion; + select_motion.now = MOTION_CASE_STEPS; + Draw_Motion_Menu(); + } + } + DWIN_UpdateLCD(); +} + +void HMI_Init() { + HMI_SDCardInit(); + + for (uint16_t t = 0; t <= 100; t += 2) { + DWIN_ICON_Show(ICON, ICON_Bar, 15, 260); + DWIN_Draw_Rectangle(1, Color_Bg_Black, 15 + t * 242 / 100, 260, 257, 280); + DWIN_UpdateLCD(); + delay(20); + } + + HMI_SetLanguage(); +} + +void DWIN_Update() { + EachMomentUpdate(); // Status update + HMI_SDCardUpdate(); // SD card update + DWIN_HandleScreen(); // Rotary encoder update +} + +void EachMomentUpdate() { + static millis_t next_rts_update_ms = 0; + const millis_t ms = millis(); + if (PENDING(ms, next_rts_update_ms)) return; + next_rts_update_ms = ms + DWIN_SCROLL_UPDATE_INTERVAL; + + // variable update + update_variable(); + + if (checkkey == PrintProcess) { + // if print done + if (HMI_flag.print_finish && !HMI_flag.done_confirm_flag) { + HMI_flag.print_finish = false; + HMI_flag.done_confirm_flag = true; + + TERN_(POWER_LOSS_RECOVERY, recovery.cancel()); + + planner.finish_and_disable(); + + // show percent bar and value + Percentrecord = 0; + Draw_Print_ProgressBar(); + + // show print done confirm + DWIN_Draw_Rectangle(1, Color_Bg_Black, 0, 250, DWIN_WIDTH - 1, STATUS_Y); + DWIN_ICON_Show(ICON, HMI_IsChinese() ? ICON_Confirm_C : ICON_Confirm_E, 86, 283); + } + else if (HMI_flag.pause_flag != printingIsPaused()) { + // print status update + HMI_flag.pause_flag = printingIsPaused(); + if (HMI_flag.pause_flag) ICON_Continue(); else ICON_Pause(); + } + } + + // pause after homing + if (HMI_flag.pause_action && printingIsPaused() && !planner.has_blocks_queued()) { + HMI_flag.pause_action = false; + #if ENABLED(PAUSE_HEAT) + #if HAS_HEATED_BED + tempbed = thermalManager.temp_bed.target; + #endif + #if HAS_HOTEND + temphot = thermalManager.temp_hotend[0].target; + #endif + thermalManager.disable_all_heaters(); + #endif + queue.inject_P(PSTR("G1 F1200 X0 Y0")); + } + + if (card.isPrinting() && checkkey == PrintProcess) { // print process + const uint8_t card_pct = card.percentDone(); + static uint8_t last_cardpercentValue = 101; + if (last_cardpercentValue != card_pct) { // print percent + last_cardpercentValue = card_pct; + if (card_pct) { + Percentrecord = card_pct; + Draw_Print_ProgressBar(); + } + } + + duration_t elapsed = print_job_timer.duration(); // print timer + + // Print time so far + static uint16_t last_Printtime = 0; + const uint16_t min = (elapsed.value % 3600) / 60; + if (last_Printtime != min) { // 1 minute update + last_Printtime = min; + Draw_Print_ProgressElapsed(); + } + + // Estimate remaining time every 20 seconds + static millis_t next_remain_time_update = 0; + if (Percentrecord > 1 && ELAPSED(ms, next_remain_time_update) && !HMI_flag.heat_flag) { + remain_time = (elapsed.value - dwin_heat_time) / (Percentrecord * 0.01f) - (elapsed.value - dwin_heat_time); + next_remain_time_update += 20 * 1000UL; + Draw_Print_ProgressRemain(); + } + } + else if (dwin_abort_flag && !HMI_flag.home_flag) { // Print Stop + dwin_abort_flag = false; + HMI_ValueStruct.print_speed = feedrate_percentage = 100; + dwin_zoffset = TERN0(HAS_BED_PROBE, probe.offset.z); + + planner.finish_and_disable(); + + #if DISABLED(SD_ABORT_NO_COOLDOWN) + thermalManager.disable_all_heaters(); + #endif + + select_page.set(0); + Goto_MainMenu(); + } + #if ENABLED(POWER_LOSS_RECOVERY) + else if (DWIN_lcd_sd_status && recovery.dwin_flag) { // resume print before power off + static bool recovery_flag = false; + + recovery.dwin_flag = false; + recovery_flag = true; + + auto update_selection = [&](const bool sel) { + HMI_flag.select_flag = sel; + const uint16_t c1 = sel ? Color_Bg_Window : Select_Color; + DWIN_Draw_Rectangle(0, c1, 25, 306, 126, 345); + DWIN_Draw_Rectangle(0, c1, 24, 305, 127, 346); + const uint16_t c2 = sel ? Select_Color : Color_Bg_Window; + DWIN_Draw_Rectangle(0, c2, 145, 306, 246, 345); + DWIN_Draw_Rectangle(0, c2, 144, 305, 247, 346); + }; + + Popup_Window_Resume(); + update_selection(true); + + // TODO: Get the name of the current file from someplace + // + //(void)recovery.interrupted_file_exists(); + char * const name = card.longest_filename(); + const int8_t npos = _MAX(0U, DWIN_WIDTH - strlen(name) * (MENU_CHR_W)) / 2; + DWIN_Draw_String(false, true, font8x16, Popup_Text_Color, Color_Bg_Window, npos, 252, name); + DWIN_UpdateLCD(); + + while (recovery_flag) { + ENCODER_DiffState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState != ENCODER_DIFF_NO) { + if (encoder_diffState == ENCODER_DIFF_ENTER) { + recovery_flag = false; + if (HMI_flag.select_flag) break; + TERN_(POWER_LOSS_RECOVERY, queue.inject_P(PSTR("M1000C"))); + HMI_StartFrame(true); + return; + } + else + update_selection(encoder_diffState == ENCODER_DIFF_CW); + + DWIN_UpdateLCD(); + } + } + + select_print.set(0); + HMI_ValueStruct.show_mode = 0; + queue.inject_P(PSTR("M1000")); + Goto_PrintProcess(); + Draw_Status_Area(true); + } + #endif + DWIN_UpdateLCD(); +} + +void DWIN_HandleScreen() { + switch (checkkey) { + case MainMenu: HMI_MainMenu(); break; + case SelectFile: HMI_SelectFile(); break; + case Prepare: HMI_Prepare(); break; + case Control: HMI_Control(); break; + case Leveling: break; + case PrintProcess: HMI_Printing(); break; + case Print_window: HMI_PauseOrStop(); break; + case AxisMove: HMI_AxisMove(); break; + case TemperatureID: HMI_Temperature(); break; + case Motion: HMI_Motion(); break; + case Info: HMI_Info(); break; + case Tune: HMI_Tune(); break; + #if HAS_PREHEAT + case PLAPreheat: HMI_PLAPreheatSetting(); break; + case ABSPreheat: HMI_ABSPreheatSetting(); break; + #endif + case MaxSpeed: HMI_MaxSpeed(); break; + case MaxAcceleration: HMI_MaxAcceleration(); break; + case MaxJerk: HMI_MaxJerk(); break; + case Step: HMI_Step(); break; + case Move_X: HMI_Move_X(); break; + case Move_Y: HMI_Move_Y(); break; + case Move_Z: HMI_Move_Z(); break; + #if HAS_HOTEND + case Extruder: HMI_Move_E(); break; + case ETemp: HMI_ETemp(); break; + #endif + #if EITHER(HAS_BED_PROBE, BABYSTEPPING) + case Homeoffset: HMI_Zoffset(); break; + #endif + #if HAS_HEATED_BED + case BedTemp: HMI_BedTemp(); break; + #endif + #if HAS_PREHEAT + case FanSpeed: HMI_FanSpeed(); break; + #endif + case PrintSpeed: HMI_PrintSpeed(); break; + case MaxSpeed_value: HMI_MaxFeedspeedXYZE(); break; + case MaxAcceleration_value: HMI_MaxAccelerationXYZE(); break; + case MaxJerk_value: HMI_MaxJerkXYZE(); break; + case Step_value: HMI_StepXYZE(); break; + default: break; + } +} + +void DWIN_CompletedHoming() { + HMI_flag.home_flag = false; + if (checkkey == Last_Prepare) { + checkkey = Prepare; + select_prepare.now = PREPARE_CASE_HOME; + index_prepare = MROWS; + Draw_Prepare_Menu(); + } + else if (checkkey == Back_Main) { + HMI_ValueStruct.print_speed = feedrate_percentage = 100; + dwin_zoffset = TERN0(HAS_BED_PROBE, probe.offset.z); + planner.finish_and_disable(); + Goto_MainMenu(); + } +} + +void DWIN_CompletedLeveling() { + if (checkkey == Leveling) Goto_MainMenu(); +} + +#endif // DWIN_CREALITY_LCD diff --git a/Marlin/src/lcd/dwin/dwin.h b/Marlin/src/lcd/dwin/e3v2/dwin.h similarity index 66% rename from Marlin/src/lcd/dwin/dwin.h rename to Marlin/src/lcd/dwin/e3v2/dwin.h index 3446a0d4c1..5bff2e9f78 100644 --- a/Marlin/src/lcd/dwin/dwin.h +++ b/Marlin/src/lcd/dwin/e3v2/dwin.h @@ -25,13 +25,20 @@ * DWIN by Creality3D */ -#include "dwin_lcd.h" +#include "../dwin_lcd.h" #include "rotary_encoder.h" -#include "../../libs/BL24CXX.h" +#include "../../../libs/BL24CXX.h" -#include +#include "../../../inc/MarlinConfigPre.h" -enum processID { +#if ANY(HAS_HOTEND, HAS_HEATED_BED, HAS_FAN) && PREHEAT_COUNT + #define HAS_PREHEAT 1 + #if PREHEAT_COUNT < 2 + #error "Creality DWIN requires two material preheat presets." + #endif +#endif + +enum processID : uint8_t { // Process ID MainMenu, SelectFile, @@ -44,7 +51,7 @@ enum processID { Motion, Info, Tune, - #if HAS_HOTEND + #if HAS_PREHEAT PLAPreheat, ABSPreheat, #endif @@ -52,8 +59,8 @@ enum processID { MaxSpeed_value, MaxAcceleration, MaxAcceleration_value, - MaxCorner, - MaxCorner_value, + MaxJerk, + MaxJerk_value, Step, Step_value, @@ -150,7 +157,7 @@ enum processID { #define ICON_MaxSpeed 51 #define ICON_MaxAccelerated 52 -#define ICON_MaxCorner 53 +#define ICON_MaxJerk 53 #define ICON_Step 54 #define ICON_PrintSize 55 #define ICON_Version 56 @@ -164,10 +171,10 @@ enum processID { #define ICON_MaxAccY 64 #define ICON_MaxAccZ 65 #define ICON_MaxAccE 66 -#define ICON_MaxSpeedCornerX 67 -#define ICON_MaxSpeedCornerY 68 -#define ICON_MaxSpeedCornerZ 69 -#define ICON_MaxSpeedCornerE 70 +#define ICON_MaxSpeedJerkX 67 +#define ICON_MaxSpeedJerkY 68 +#define ICON_MaxSpeedJerkZ 69 +#define ICON_MaxSpeedJerkE 70 #define ICON_StepX 71 #define ICON_StepY 72 #define ICON_StepZ 73 @@ -207,18 +214,20 @@ enum processID { #define font32x64 0x09 // Color -#define White 0xFFFF -#define Background_window 0x31E8 // Popup background color -#define Background_blue 0x1125 // Dark blue background color -#define Background_black 0x0841 // black background color -#define Font_window 0xD6BA // Popup font background color +#define Color_White 0xFFFF +#define Color_Yellow 0xFF0F +#define Color_Bg_Window 0x31E8 // Popup background color +#define Color_Bg_Blue 0x1125 // Dark blue background color +#define Color_Bg_Black 0x0841 // Black background color +#define Color_Bg_Red 0xF00F // Red background color +#define Popup_Text_Color 0xD6BA // Popup font background color #define Line_Color 0x3A6A // Split line color -#define Rectangle_Color 0xEE2F // blue square cursor color -#define Percent_Color 0xFE29 // percentage color -#define BarFill_Color 0x10E4 // fill color of progress bar -#define Select_Color 0x33BB // selected color +#define Rectangle_Color 0xEE2F // Blue square cursor color +#define Percent_Color 0xFE29 // Percentage color +#define BarFill_Color 0x10E4 // Fill color of progress bar +#define Select_Color 0x33BB // Selected color -extern int checkkey, last_checkkey; +extern uint8_t checkkey; extern float zprobe_zoffset; extern char print_filename[16]; @@ -227,51 +236,48 @@ extern millis_t dwin_heat_time; typedef struct { TERN_(HAS_HOTEND, int16_t E_Temp = 0); TERN_(HAS_HEATED_BED, int16_t Bed_Temp = 0); - TERN_(HAS_FAN, int16_t Fan_speed = 0); + TERN_(HAS_PREHEAT, int16_t Fan_speed = 0); int16_t print_speed = 100; float Max_Feedspeed = 0; float Max_Acceleration = 0; - float Max_Corner = 0; + float Max_Jerk = 0; float Max_Step = 0; float Move_X_scale = 0; float Move_Y_scale = 0; float Move_Z_scale = 0; - #if EXTRUDERS + #if HAS_HOTEND float Move_E_scale = 0; #endif float offset_value = 0; char show_mode = 0; // -1: Temperature control 0: Printing temperature } HMI_value_t; +#define DWIN_CHINESE 123 +#define DWIN_ENGLISH 0 + typedef struct { - bool language_chinese; // 0: EN, 1: CN + uint8_t language; bool pause_flag:1; + bool pause_action:1; bool print_finish:1; - bool confirm_flag:1; + bool done_confirm_flag:1; bool select_flag:1; bool home_flag:1; bool heat_flag:1; // 0: heating done 1: during heating - #if HAS_HOTEND + #if ENABLED(PREVENT_COLD_EXTRUSION) bool ETempTooLow_flag:1; #endif #if HAS_LEVELING bool leveling_offset_flag:1; #endif #if HAS_FAN - char feedspeed_flag; + AxisEnum feedspeed_axis; #endif - char acc_flag; - char corner_flag; - char step_flag; -} HMI_Flag; + AxisEnum acc_axis, jerk_axis, step_axis; +} HMI_Flag_t; extern HMI_value_t HMI_ValueStruct; -extern HMI_Flag HMI_flag; - -// Language -void HMI_SetLanguage(void); -void HMI_SetAndSaveLanguageWestern(void); -void HMI_SetAndSaveLanguageChinese(void); +extern HMI_Flag_t HMI_flag; // Show ICO void ICON_Print(bool show); @@ -285,44 +291,47 @@ void ICON_Pause(bool show); void ICON_Continue(bool show); void ICON_Stop(bool show); -// Popup window tips +#if HAS_HOTEND || HAS_HEATED_BED + // Popup message window + void DWIN_Popup_Temperature(const bool toohigh); +#endif + #if HAS_HOTEND - void Popup_Window_Temperature(const bool toohigh); - void Popup_Window_ETempTooLow(void); + void Popup_Window_ETempTooLow(); #endif -void Popup_Window_Resume(void); -void Popup_Window_Home(void); -void Popup_Window_Leveling(void); +void Popup_Window_Resume(); +void Popup_Window_Home(const bool parking=false); +void Popup_Window_Leveling(); -void Goto_PrintProcess(void); -void Goto_MainMenu(void); +void Goto_PrintProcess(); +void Goto_MainMenu(); // Variable control -void HMI_Move_X(void); -void HMI_Move_Y(void); -void HMI_Move_Z(void); -void HMI_Move_E(void); +void HMI_Move_X(); +void HMI_Move_Y(); +void HMI_Move_Z(); +void HMI_Move_E(); -void HMI_Zoffset(void); +void HMI_Zoffset(); -TERN_(HAS_HOTEND, void HMI_ETemp(void)); -TERN_(HAS_HEATED_BED, void HMI_BedTemp(void)); -TERN_(HAS_FAN, void HMI_FanSpeed(void)); +TERN_(HAS_HOTEND, void HMI_ETemp()); +TERN_(HAS_HEATED_BED, void HMI_BedTemp()); +TERN_(HAS_FAN, void HMI_FanSpeed()); -void HMI_PrintSpeed(void); +void HMI_PrintSpeed(); -void HMI_MaxFeedspeedXYZE(void); -void HMI_MaxAccelerationXYZE(void); -void HMI_MaxCornerXYZE(void); -void HMI_StepXYZE(void); +void HMI_MaxFeedspeedXYZE(); +void HMI_MaxAccelerationXYZE(); +void HMI_MaxJerkXYZE(); +void HMI_StepXYZE(); -void update_variable(void); -void show_plus_or_minus(uint8_t size, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value); +void update_variable(); +void DWIN_Draw_Signed_Float(uint8_t size, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, long value); // SD Card -void HMI_SDCardInit(void); -void HMI_SDCardUpdate(void); +void HMI_SDCardInit(); +void HMI_SDCardUpdate(); // Main Process void Icon_print(bool value); @@ -331,34 +340,34 @@ void Icon_temperature(bool value); void Icon_leveling(bool value); // Other -bool Pause_HeatStatus(); -void HMI_StartFrame(const bool with_update); // startup screen -void HMI_MainMenu(void); // main process screen -void HMI_SelectFile(void); // file page -void HMI_Printing(void); // print page -void HMI_Prepare(void); // prepare page -void HMI_Control(void); // control page -void HMI_Leveling(void); // Level the page -void HMI_AxisMove(void); // Axis movement menu -void HMI_Temperature(void); // Temperature menu -void HMI_Motion(void); // Sports menu -void HMI_Info(void); // Information menu -void HMI_Tune(void); // Adjust the menu - -#if HAS_HOTEND - void HMI_PLAPreheatSetting(void); // PLA warm-up setting - void HMI_ABSPreheatSetting(void); // ABS warm-up setting +void Draw_Status_Area(const bool with_update); // Status Area +void HMI_StartFrame(const bool with_update); // Prepare the menu view +void HMI_MainMenu(); // Main process screen +void HMI_SelectFile(); // File page +void HMI_Printing(); // Print page +void HMI_Prepare(); // Prepare page +void HMI_Control(); // Control page +void HMI_Leveling(); // Level the page +void HMI_AxisMove(); // Axis movement menu +void HMI_Temperature(); // Temperature menu +void HMI_Motion(); // Sports menu +void HMI_Info(); // Information menu +void HMI_Tune(); // Adjust the menu + +#if HAS_PREHEAT + void HMI_PLAPreheatSetting(); // PLA warm-up setting + void HMI_ABSPreheatSetting(); // ABS warm-up setting #endif -void HMI_MaxSpeed(void); // Maximum speed submenu -void HMI_MaxAcceleration(void); // Maximum acceleration submenu -void HMI_MaxCorner(void); // Maximum corner speed submenu -void HMI_Step(void); // transmission ratio +void HMI_MaxSpeed(); // Maximum speed submenu +void HMI_MaxAcceleration(); // Maximum acceleration submenu +void HMI_MaxJerk(); // Maximum jerk speed submenu +void HMI_Step(); // Transmission ratio -void HMI_Init(void); -void DWIN_Update(void); -void EachMomentUpdate(void); -void DWIN_HandleScreen(void); +void HMI_Init(); +void DWIN_Update(); +void EachMomentUpdate(); +void DWIN_HandleScreen(); -void DWIN_CompletedHoming(void); -void DWIN_CompletedLeveling(void); +void DWIN_CompletedHoming(); +void DWIN_CompletedLeveling(); diff --git a/Marlin/src/lcd/dwin/rotary_encoder.cpp b/Marlin/src/lcd/dwin/e3v2/rotary_encoder.cpp similarity index 84% rename from Marlin/src/lcd/dwin/rotary_encoder.cpp rename to Marlin/src/lcd/dwin/e3v2/rotary_encoder.cpp index 62e2cda351..d39c6cfbd5 100644 --- a/Marlin/src/lcd/dwin/rotary_encoder.cpp +++ b/Marlin/src/lcd/dwin/e3v2/rotary_encoder.cpp @@ -20,41 +20,39 @@ * */ -/** - ****************************************************************************** - * @file rotary_encoder.cpp - * @author LEO / Creality3D - * @date 2019/07/06 - * @version 2.0.1 - * @brief 旋转编码器操作函数 - ****************************************************************************** -**/ +/***************************************************************************** + * @file rotary_encoder.cpp + * @author LEO / Creality3D + * @date 2019/07/06 + * @version 2.0.1 + * @brief Rotary encoder functions + *****************************************************************************/ -#include "../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfigPre.h" #if ENABLED(DWIN_CREALITY_LCD) #include "rotary_encoder.h" -#include "../../MarlinCore.h" -#include "../../HAL/shared/Delay.h" +#include "../../../MarlinCore.h" +#include "../../../HAL/shared/Delay.h" #if HAS_BUZZER - #include "../../libs/buzzer.h" + #include "../../../libs/buzzer.h" #endif #include ENCODER_Rate EncoderRate; -/*蜂鸣器响*/ +// Buzzer void Encoder_tick(void) { WRITE(BEEPER_PIN, 1); delay(10); WRITE(BEEPER_PIN, 0); } -/*编码器初始化 PB12:Encoder_A PB13:Encoder_B PB14:Encoder_C*/ +// Encoder initialization void Encoder_Configuration(void) { #if BUTTON_EXISTS(EN1) SET_INPUT_PULLUP(BTN_EN1); @@ -70,8 +68,7 @@ void Encoder_Configuration(void) { #endif } -millis_t next_click_update_ms; -/*接收数据解析 返回值:ENCODER_DIFF_NO,无状态; ENCODER_DIFF_CW,顺时针旋转; ENCODER_DIFF_CCW,逆时针旋转; ENCODER_DIFF_ENTER,按下*/ +// Analyze encoder value and return state ENCODER_DiffState Encoder_ReceiveAnalyze(void) { const millis_t now = millis(); static unsigned char lastEncoderBits; @@ -82,6 +79,7 @@ ENCODER_DiffState Encoder_ReceiveAnalyze(void) { if (BUTTON_PRESSED(EN1)) newbutton |= 0x01; if (BUTTON_PRESSED(EN2)) newbutton |= 0x02; if (BUTTON_PRESSED(ENC)) { + static millis_t next_click_update_ms; if (ELAPSED(now, next_click_update_ms)) { next_click_update_ms = millis() + 300; Encoder_tick(); @@ -126,16 +124,16 @@ ENCODER_DiffState Encoder_ReceiveAnalyze(void) { int32_t encoderMultiplier = 1; // if must encoder rati multiplier - if (EncoderRate.encoderRateEnabled) { - const float abs_diff = ABS(temp_diff); - const float encoderMovementSteps = abs_diff / (ENCODER_PULSES_PER_STEP); + if (EncoderRate.enabled) { + const float abs_diff = ABS(temp_diff), + encoderMovementSteps = abs_diff / (ENCODER_PULSES_PER_STEP); if (EncoderRate.lastEncoderTime) { // Note that the rate is always calculated between two passes through the // loop and that the abs of the temp_diff value is tracked. const float encoderStepRate = encoderMovementSteps / float(ms - EncoderRate.lastEncoderTime) * 1000; - if (encoderStepRate >= ENCODER_100X_STEPS_PER_SEC) encoderMultiplier = 100; - else if (encoderStepRate >= ENCODER_10X_STEPS_PER_SEC) encoderMultiplier = 10; - else if (encoderStepRate >= ENCODER_5X_STEPS_PER_SEC) encoderMultiplier = 5; + if (encoderStepRate >= ENCODER_100X_STEPS_PER_SEC) encoderMultiplier = 100; + else if (encoderStepRate >= ENCODER_10X_STEPS_PER_SEC) encoderMultiplier = 10; + else if (encoderStepRate >= ENCODER_5X_STEPS_PER_SEC) encoderMultiplier = 5; } EncoderRate.lastEncoderTime = ms; } @@ -154,22 +152,22 @@ ENCODER_DiffState Encoder_ReceiveAnalyze(void) { #if PIN_EXISTS(LCD_LED) - /*取低24位有效 24Bit: G7 G6 G5 G4 G3 G2 G1 G0 R7 R6 R5 R4 R3 R2 R1 R0 B7 B6 B5 B4 B3 B2 B1 B0*/ + // Take the low 24 valid bits 24Bit: G7 G6 G5 G4 G3 G2 G1 G0 R7 R6 R5 R4 R3 R2 R1 R0 B7 B6 B5 B4 B3 B2 B1 B0 unsigned int LED_DataArray[LED_NUM]; - /*LED灯操作*/ + // LED light operation void LED_Action(void) { LED_Control(RGB_SCALE_WARM_WHITE,0x0F); delay(30); LED_Control(RGB_SCALE_WARM_WHITE,0x00); } - /*LED初始化*/ + // LED initialization void LED_Configuration(void) { SET_OUTPUT(LCD_LED_PIN); } - /*LED写数据*/ + // LED write data void LED_WriteData(void) { unsigned char tempCounter_LED, tempCounter_Bit; for (tempCounter_LED = 0; tempCounter_LED < LED_NUM; tempCounter_LED++) { @@ -189,12 +187,14 @@ ENCODER_DiffState Encoder_ReceiveAnalyze(void) { } } - /*LED控制 RGB_Scale:RGB色彩配比 luminance:亮度(0~0xFF)*/ + // LED control + // RGB_Scale: RGB color ratio + // luminance: brightness (0~0xFF) void LED_Control(unsigned char RGB_Scale, unsigned char luminance) { unsigned char temp_Counter; for (temp_Counter = 0; temp_Counter < LED_NUM; temp_Counter++) { LED_DataArray[temp_Counter] = 0; - switch(RGB_Scale) { + switch (RGB_Scale) { case RGB_SCALE_R10_G7_B5: LED_DataArray[temp_Counter] = (luminance*10/10) << 8 | (luminance*7/10) << 16 | luminance*5/10; break; case RGB_SCALE_R10_G7_B4: LED_DataArray[temp_Counter] = (luminance*10/10) << 8 | (luminance*7/10) << 16 | luminance*4/10; break; case RGB_SCALE_R10_G8_B7: LED_DataArray[temp_Counter] = (luminance*10/10) << 8 | (luminance*8/10) << 16 | luminance*7/10; break; @@ -203,14 +203,17 @@ ENCODER_DiffState Encoder_ReceiveAnalyze(void) { LED_WriteData(); } - /*LED渐变控制 RGB_Scale:RGB色彩配比 luminance:亮度(0~0xFF) change_Time:渐变时间(ms)*/ + // LED gradient control + // RGB_Scale: RGB color ratio + // luminance: brightness (0~0xFF) + // change_Time: gradient time (ms) void LED_GraduallyControl(unsigned char RGB_Scale, unsigned char luminance, unsigned int change_Interval) { unsigned char temp_Counter; unsigned char LED_R_Data[LED_NUM], LED_G_Data[LED_NUM], LED_B_Data[LED_NUM]; bool LED_R_Flag = 0, LED_G_Flag = 0, LED_B_Flag = 0; for (temp_Counter = 0; temp_Counter < LED_NUM; temp_Counter++) { - switch(RGB_Scale) { + switch (RGB_Scale) { case RGB_SCALE_R10_G7_B5: { LED_R_Data[temp_Counter] = luminance*10/10; LED_G_Data[temp_Counter] = luminance*7/10; @@ -246,6 +249,6 @@ ENCODER_DiffState Encoder_ReceiveAnalyze(void) { } } -#endif +#endif // LCD_LED #endif // DWIN_CREALITY_LCD diff --git a/Marlin/src/lcd/dwin/rotary_encoder.h b/Marlin/src/lcd/dwin/e3v2/rotary_encoder.h similarity index 67% rename from Marlin/src/lcd/dwin/rotary_encoder.h rename to Marlin/src/lcd/dwin/e3v2/rotary_encoder.h index 5c5a8f86a2..93e54839d6 100644 --- a/Marlin/src/lcd/dwin/rotary_encoder.h +++ b/Marlin/src/lcd/dwin/e3v2/rotary_encoder.h @@ -21,18 +21,16 @@ */ #pragma once -/** - ****************************************************************************** +/***************************************************************************** * @file rotary_encoder.h * @author LEO / Creality3D * @date 2019/07/06 * @version 2.0.1 - * @brief 旋转编码器操作函数 - ****************************************************************************** -**/ + * @brief Rotary encoder functions + ****************************************************************************/ -#include "../../inc/MarlinConfig.h" -#include "../../MarlinCore.h" +#include "../../../inc/MarlinConfig.h" +#include "../../../MarlinCore.h" /*********************** Encoder Set ***********************/ @@ -46,7 +44,7 @@ #define BUTTON_PRESSED(BN) !READ(BTN_## BN) typedef struct { - bool encoderRateEnabled = 0; + bool enabled = false; int encoderMoveValue = 0; millis_t lastEncoderTime = 0; } ENCODER_Rate; @@ -54,19 +52,18 @@ typedef struct { extern ENCODER_Rate EncoderRate; typedef enum { - ENCODER_DIFF_NO = 0, - ENCODER_DIFF_CW = 1, - ENCODER_DIFF_CCW = 2, - ENCODER_DIFF_ENTER = 3 + ENCODER_DIFF_NO = 0, // no state + ENCODER_DIFF_CW = 1, // clockwise rotation + ENCODER_DIFF_CCW = 2, // counterclockwise rotation + ENCODER_DIFF_ENTER = 3 // click } ENCODER_DiffState; -/*编码器初始化 PB12:Encoder_A PB13:Encoder_B PB14:Encoder_C*/ +// Encoder initialization void Encoder_Configuration(void); -/*接收数据解析 返回值:ENCODER_DIFF_NO,无状态; ENCODER_DIFF_CW,顺时针旋转; ENCODER_DIFF_CCW,逆时针旋转; ENCODER_DIFF_ENTER,按下*/ +// Analyze encoder value and return state ENCODER_DiffState Encoder_ReceiveAnalyze(void); - /*********************** Encoder LED ***********************/ #if PIN_EXISTS(LCD_LED) @@ -78,28 +75,30 @@ ENCODER_DiffState Encoder_ReceiveAnalyze(void); #define RGB_SCALE_R10_G7_B5 1 #define RGB_SCALE_R10_G7_B4 2 #define RGB_SCALE_R10_G8_B7 3 - #define RGB_SCALE_NEUTRAL_WHITE RGB_SCALE_R10_G7_B5 //正白 - #define RGB_SCALE_WARM_WHITE RGB_SCALE_R10_G7_B4 //暖白 - #define RGB_SCALE_COOL_WHITE RGB_SCALE_R10_G8_B7 //冷白 + #define RGB_SCALE_NEUTRAL_WHITE RGB_SCALE_R10_G7_B5 + #define RGB_SCALE_WARM_WHITE RGB_SCALE_R10_G7_B4 + #define RGB_SCALE_COOL_WHITE RGB_SCALE_R10_G8_B7 extern unsigned int LED_DataArray[LED_NUM]; - /*状态LED初始化*/ - void STATE_LED_Configuration(void); - - /*LED灯操作*/ + // LED light operation void LED_Action(void); - /*LED初始化*/ + // LED initialization void LED_Configuration(void); - /*LED写数据*/ + // LED write data void LED_WriteData(void); - /*LED控制 RGB_Scale:RGB色彩配比 luminance:亮度(0~0xFF)*/ + // LED control + // RGB_Scale: RGB color ratio + // luminance: brightness (0~0xFF) void LED_Control(unsigned char RGB_Scale, unsigned char luminance); - /*LED渐变控制 RGB_Scale:RGB色彩配比 luminance:亮度(0~0xFF) change_Time:渐变时间(ms)*/ + // LED gradient control + // RGB_Scale: RGB color ratio + // luminance: brightness (0~0xFF) + // change_Time: gradient time (ms) void LED_GraduallyControl(unsigned char RGB_Scale, unsigned char luminance, unsigned int change_Interval); -#endif +#endif // LCD_LED diff --git a/Marlin/src/lcd/extui/anycubic_chiron_lcd.cpp b/Marlin/src/lcd/extui/anycubic_chiron_lcd.cpp index 889a25b859..a7f9a7a0c3 100644 --- a/Marlin/src/lcd/extui/anycubic_chiron_lcd.cpp +++ b/Marlin/src/lcd/extui/anycubic_chiron_lcd.cpp @@ -21,7 +21,7 @@ */ /** - * anycubic_chiron_lcd.cpp + * lcd/extui/anycubic_chiron_lcd.cpp * * Anycubic Chiron TFT support for Marlin */ @@ -31,505 +31,90 @@ #if ENABLED(ANYCUBIC_LCD_CHIRON) #include "ui_api.h" +#include "lib/anycubic_chiron/chiron_tft.h" -#if ENABLED(AUTO_BED_LEVELING_BILINEAR) - #if GRID_MAX_POINTS_X != 5 || GRID_MAX_POINTS_Y != 5 - #error ANYCUBIC CHIRON LCD requires a 5x5 bed leveling grid (GRID_MAX_POINTS_X and GRID_MAX_POINTS_Y) - #endif -#else - #error ANYCUBIC CHIRON LCD requires AUTO_BED_LEVELING_BILINEAR enabled -#endif - -#if DISABLED(FILAMENT_RUNOUT_SENSOR) - #error ANYCUBIC CHIRON LCD requires FILAMENT_RUNOUT_SENSOR enabled -#endif - -#if ENABLED(POWER_LOSS_RECOVERY) - #error ANYCUBIC CHIRON LCD does not currently support POWER_LOSS_RECOVERY -#endif - -static bool is_auto_leveling = false; -static bool is_printing_from_sd = false; -static bool is_out_of_filament = false; - -static void sendNewLine(void) { - ANYCUBIC_LCD_SERIAL.write('\r'); - ANYCUBIC_LCD_SERIAL.write('\n'); -} - -static void send(const char *str) { - ANYCUBIC_LCD_SERIAL.print(str); -} - -static void sendLine(const char *str) { - send(str); - sendNewLine(); -} - -static void send_P(PGM_P str) { - while (const char c = pgm_read_byte(str++)) - ANYCUBIC_LCD_SERIAL.write(c); -} - -static void sendLine_P(PGM_P str) { - send_P(str); - sendNewLine(); -} - -static void sendValue_P(PGM_P prefix, int value) { - send_P(prefix); - ANYCUBIC_LCD_SERIAL.print(value); -} - -static void sendValue_P(PGM_P prefix, float value) { - send_P(prefix); - ANYCUBIC_LCD_SERIAL.print(value); -} - -static void sendValueLine_P(PGM_P prefix, int value) { - send_P(prefix); - ANYCUBIC_LCD_SERIAL.print(value); - sendNewLine(); -} - -static void sendValueLine_P(PGM_P prefix, float value) { - send_P(prefix); - ANYCUBIC_LCD_SERIAL.print(value); - sendNewLine(); -} - -static int parseIntArgument(const char *buffer, char letterId) { - char *p = strchr(buffer, letterId); - if (!p) - return -1; - return atoi(p+1); -} - -static float parseFloatArgument(const char *buffer, char letterId) { - char *p = strchr(buffer, letterId); - if (!p) - return NAN; - return strtof(p+1, nullptr); -} - -static int mmToHundredths(float x) { - // Round - if (x >= 0) - x += 0.005f; - else - x -= 0.005f; - return (int)(x * 100.0f); -} - -static float hundredthsToMm(int x) { - return x / 100.0f; -} - -#define SEND_PGM(str) send_P(PSTR(str)) -#define SENDLINE_PGM(str) sendLine_P(PSTR(str)) -#define SENDVALUE_PGM(prefix, value) sendValue_P(PSTR(prefix), value) -#define SENDVALUELINE_PGM(prefix, value) sendValueLine_P(PSTR(prefix), value) +using namespace Anycubic; namespace ExtUI { - static void moveAxis(float delta, feedRate_t feedrate, axis_t axis) { - float pos = getAxisPosition_mm(axis); - pos += delta; - setAxisPosition_mm(pos, axis, feedrate); - } - - static void handleCmd(const char *rx) { - static FileList fileList; - static char selectedFileShortName[8+1+3+1]; - - if (rx[0] != 'A') { - SERIAL_ECHOPGM("Unexpected RX: "); - SERIAL_ECHOLN(rx); - - return; - } - - const int cmd = atoi(&rx[1]); - - // Uncomment for debugging RX - //if (cmd > 7 && cmd != 20) { - // SERIAL_ECHOPGM("RX: "); - // SERIAL_ECHOLN(rx); - //} - - switch (cmd) { - case 0: // Get Hotend Actual Temperature - SENDVALUELINE_PGM("A0V ", (int)getActualTemp_celsius(E0)); - break; - case 1: // Get Hotend Target Temperature - SENDVALUELINE_PGM("A1V ", (int)getTargetTemp_celsius(E0)); - break; - case 2: // Get Bed Actual Temperature - SENDVALUELINE_PGM("A2V ", (int)getActualTemp_celsius(BED)); - break; - case 3: // Get Bed Target Temperature - SENDVALUELINE_PGM("A3V ", (int)getTargetTemp_celsius(BED)); - break; - case 4: // Get Fan Speed - SENDVALUELINE_PGM("A4V ", (int)getTargetFan_percent(FAN0)); - break; - case 5: // Get Current Coordinates - SENDVALUE_PGM("A5V X: ", getAxisPosition_mm(X)); - SENDVALUE_PGM(" Y: ", getAxisPosition_mm(Y)); - SENDVALUE_PGM(" Z: ", getAxisPosition_mm(Z)); - sendNewLine(); - break; - case 6: // Get SD Card Print Status - if (isPrintingFromMedia()) - SENDVALUELINE_PGM("A6V ", (int)getProgress_percent()); - else - SENDLINE_PGM("A6V ---"); - break; - case 7: // Get Printing Time - if (isPrinting()) { - const int totalMinutes = getProgress_seconds_elapsed() / 60; - SENDVALUE_PGM("A7V ", (int)(totalMinutes/60)); - SENDVALUE_PGM(" H ", (int)(totalMinutes%60)); - SENDLINE_PGM(" M"); - } else { - SENDLINE_PGM("A7V 999:999"); - } - break; - case 8: // Get SD Card File List - if (isMediaInserted()) { - const int startIndex = parseIntArgument(rx, 'S'); - SENDLINE_PGM("FN "); - for (int i = 0, fileIndex = 0, numFiles = 0; i < (int)fileList.count() && numFiles < 4; i++) { - fileList.seek(i); - if (!fileList.isDir()) { - if (fileIndex >= startIndex) { - sendLine(fileList.shortFilename()); - sendLine(fileList.longFilename()); - numFiles++; - } - fileIndex++; - } - } - SENDLINE_PGM("END"); - } else { - SENDLINE_PGM("J02"); - } - break; - case 9: // Pause SD Card Print - if (isPrintingFromMedia()) { - pausePrint(); - is_printing_from_sd = false; - SENDLINE_PGM("J05"); - } else { - SENDLINE_PGM("J16"); // Print stopped - } - break; - case 10: // Resume SD Card Print - if (is_out_of_filament) { - is_out_of_filament = false; - // Filament change did eject the old filament automatically, - // now continue and load the new one - setUserConfirmed(); - SENDLINE_PGM("J04"); // Printing from SD card - } else if (isPrintingFromMediaPaused()) { - resumePrint(); - SENDLINE_PGM("J04"); // Printing from SD card - } - break; - case 11: // Stop SD Card Print - if (isPrintingFromMedia()) { - stopPrint(); - is_printing_from_sd = false; - SENDLINE_PGM("J16"); // Print stopped - } - break; - //case 12: // Kill - // break; - case 13: // Select File - if (!isPrinting()) { - // Store selected file name - char *p = strchr(rx, ' '); - if (p != nullptr && strlen(p+1) < sizeof(selectedFileShortName)) { - strcpy(selectedFileShortName, p+1); - SENDLINE_PGM("J20"); // Open succeeded - } - else - SENDLINE_PGM("J21"); // Open failed - } - break; - case 14: // Start Print - if (!isPrinting() && strcmp(selectedFileShortName, "") != 0) { - printFile(selectedFileShortName); - is_printing_from_sd = true; - SENDLINE_PGM("J04"); // Printing from SD card - } - break; - case 15: // Resume from power outage - // This is not supported, just report print as completed - SENDLINE_PGM("J16"); // Print stopped - break; - case 16: // Set Hotend Target Temperature - { - int temp = parseIntArgument(rx, 'S'); - if (temp >= 0) - setTargetTemp_celsius(temp, E0); - } - break; - case 17: // Set Bed Target Temperature - { - int temp = parseIntArgument(rx, 'S'); - if (temp >= 0) - setTargetTemp_celsius(temp, BED); - } - break; - case 18: // Set Fan Speed - { - int temp = parseIntArgument(rx, 'S'); - if (temp >= 0) - setTargetFan_percent(temp, FAN0); - } - break; - case 19: // Disable Motors - injectCommands_P(PSTR("M84")); - break; - case 20: // Get/Set Printing Speed - { - int newPerc = parseIntArgument(rx, 'S'); - if (newPerc >= 0) - setFeedrate_percent(newPerc); - else - SENDVALUELINE_PGM("A20V ", (int)getFeedrate_percent()); - } - break; - case 21: // Home axes - if (!isPrinting()) { - const bool hasX = strchr(rx, 'X') != nullptr, - hasY = strchr(rx, 'Y') != nullptr, - hasZ = strchr(rx, 'Z') != nullptr, - hasC = strchr(rx, 'C') != nullptr; - if (hasX || hasY || hasZ) { - if (hasX) injectCommands_P(PSTR("G28 X")); - if (hasY) injectCommands_P(PSTR("G28 Y")); - if (hasZ) injectCommands_P(PSTR("G28 Z")); - } else if (hasC) { - injectCommands_P(PSTR("G28")); - } - } - break; - case 22: // Move axes - if (!isPrinting()) { - const int feedrate = parseIntArgument(rx, 'F') / 60; - float delta; - if (!isnan(delta = parseFloatArgument(rx, 'X'))) - moveAxis(delta, feedrate, X); - else if (!isnan(delta = parseFloatArgument(rx, 'Y'))) - moveAxis(delta, feedrate, Y); - else if (!isnan(delta = parseFloatArgument(rx, 'Z'))) - moveAxis(delta, feedrate, Z); - } - break; - case 23: // Preheat PLA - setTargetTemp_celsius(PREHEAT_1_TEMP_HOTEND, E0); - setTargetTemp_celsius(PREHEAT_1_TEMP_BED, BED); - SENDLINE_PGM("OK"); - break; - case 24: // Preheat ABS - setTargetTemp_celsius(PREHEAT_2_TEMP_HOTEND, E0); - setTargetTemp_celsius(PREHEAT_2_TEMP_BED, BED); - SENDLINE_PGM("OK"); - break; - case 25: // Cool down - setTargetTemp_celsius(0, E0); - setTargetTemp_celsius(0, BED); - SENDLINE_PGM("J12"); - break; - case 26: // Refresh SD Card - fileList.refresh(); - break; - //case 27: // Adjust Servo Angles - // break; - //case 28: // Filament Test - // break; - case 29: // Get Bed Autolevel Grid - { - int x = parseIntArgument(rx, 'X'), - y = parseIntArgument(rx, 'Y'); - if (x != -1 && y != -1) { - xy_uint8_t coord; - coord.set(x, y); - const int value = mmToHundredths(getMeshPoint(coord)); - SENDVALUELINE_PGM("A29V ", value); - } - } - break; - case 30: // Autolevel - if (strchr(rx, 'S')) { // Autoleveling started by clicking "PROBE" and then "OK" - // Note: - // We check for completion by monitoring the command queue. - // Since it will become empty *while* processing the last injected command, - // we enqueue an extra 10ms delay so we can the determine when all the others - // have completed. - if (isMachineHomed()) - injectCommands_P(PSTR("G29\nG4 P10")); - else - injectCommands_P(PSTR("G28\nG29\nG4 P10")); - is_auto_leveling = true; - } else { // Entering Autoleveling screen - if (isPrinting()) - SENDLINE_PGM("J24"); // Disallow autoleveling - else - SENDLINE_PGM("J26"); // Allow autoleveling - } - break; - case 31: // Set Bed Autolevel Z offset - if (strchr(rx, 'G')) { // Get - SENDVALUELINE_PGM("A31V ", getZOffset_mm()); - } else if (strchr(rx, 'S')) { // Set - float delta = parseFloatArgument(rx, 'S'); - delta = constrain(delta, -1.0, 1.0); - setZOffset_mm(getZOffset_mm() + delta); - - SENDVALUELINE_PGM("A31V ", getZOffset_mm()); - } else if (strchr(rx, 'D')) { // Save - injectCommands_P(PSTR("M500")); - } - break; - //case 32: // ? - // break; - case 33: // Get Version Info - SENDLINE_PGM("J33 " SHORT_BUILD_VERSION); - break; - case 34: // Set Bed Autolevel Grid - { - int x = parseIntArgument(rx, 'X'), - y = parseIntArgument(rx, 'Y'), - v = parseIntArgument(rx, 'V'); - if (x != -1 && y != -1 && v != -1) { // Set new value - float value = hundredthsToMm(v); - value = constrain(value, -10, 10); + void onStartup() { Chiron.Startup(); } - xy_uint8_t coord; - coord.set(x, y); - setMeshPoint(coord, value); - } else if (strchr(rx, 'S')) { // Save (apply new values) - injectCommands_P(PSTR("M500")); - } else if (strchr(rx, 'C')) { // Cancel (discard new values) - injectCommands_P(PSTR("M501")); - } - } - break; - } - } + void onIdle() { Chiron.IdleLoop(); } - #define RX_LEN_MAX 63 - static void parseSerialRx() { - static char rxBuffer[RX_LEN_MAX+1]; - static uint8_t rxLen = 0; - - while (ANYCUBIC_LCD_SERIAL.available()) { - const char c = ANYCUBIC_LCD_SERIAL.read(); - switch (c) { - case '\r': case '\n': - if (rxLen > 0 && rxLen <= RX_LEN_MAX) { - rxBuffer[rxLen] = '\0'; // Terminate string - handleCmd(rxBuffer); - } - rxLen = 0; - break; - default: - if (rxLen < RX_LEN_MAX) - rxBuffer[rxLen++] = c; - else { - rxLen = 0xFF; // Overrun - SERIAL_ECHOPGM("Warning: dropping long received line"); - } - break; - } - } + void onPrinterKilled(PGM_P const error, PGM_P const component) { + Chiron.PrinterKilled(error,component); } - static void detectPrintFromSdCompletion() { - // Note: printFile() queues some commands that actually start the print, so isPrintingFromMedia() - // initially returns false - if (is_printing_from_sd && !commandsInQueue() && !isPrintingFromMedia()) { - is_printing_from_sd = false; - SENDLINE_PGM("J14"); // Print done - } - } + void onMediaInserted() { Chiron.MediaEvent(AC_media_inserted); } + void onMediaError() { Chiron.MediaEvent(AC_media_error); } + void onMediaRemoved() { Chiron.MediaEvent(AC_media_removed); } - static void detectAutolevelingCompletion() { - if (is_auto_leveling && !commandsInQueue()) { - is_auto_leveling = false; - injectCommands_P(PSTR("M500")); - SENDLINE_PGM("J25"); // Autoleveling done - } + void onPlayTone(const uint16_t frequency, const uint16_t duration) { + #if ENABLED(SPEAKER) + ::tone(BEEPER_PIN, frequency, duration); + #endif } - void onStartup() { - ANYCUBIC_LCD_SERIAL.begin(115200); - sendNewLine(); - SENDLINE_PGM("J17"); // Reset - delay_ms(10); - SENDLINE_PGM("J12"); // Ready - } + void onPrintTimerStarted() { Chiron.TimerEvent(AC_timer_started); } + void onPrintTimerPaused() { Chiron.TimerEvent(AC_timer_paused); } + void onPrintTimerStopped() { Chiron.TimerEvent(AC_timer_stopped); } + void onFilamentRunout(const extruder_t) { Chiron.FilamentRunout(); } + void onUserConfirmRequired(const char * const msg) { Chiron.ConfirmationRequest(msg); } + void onStatusChanged(const char * const msg) { Chiron.StatusChange(msg); } - void onIdle() { - parseSerialRx(); - detectAutolevelingCompletion(); - detectPrintFromSdCompletion(); - } + void onFactoryReset() {} - void onPrinterKilled(PGM_P const error, PGM_P const component) { } + void onStoreSettings(char *buff) { + // Called when saving to EEPROM (i.e. M500). If the ExtUI needs + // permanent data to be stored, it can write up to eeprom_data_size bytes + // into buff. - void onMediaInserted() { - SENDLINE_PGM("J00"); // SD Inserted + // Example: + // static_assert(sizeof(myDataStruct) <= ExtUI::eeprom_data_size); + // memcpy(buff, &myDataStruct, sizeof(myDataStruct)); } - void onMediaError() { } + void onLoadSettings(const char *buff) { + // Called while loading settings from EEPROM. If the ExtUI + // needs to retrieve data, it should copy up to eeprom_data_size bytes + // from buff - void onMediaRemoved() { - SENDLINE_PGM("J01"); // SD Removed + // Example: + // static_assert(sizeof(myDataStruct) <= ExtUI::eeprom_data_size); + // memcpy(&myDataStruct, buff, sizeof(myDataStruct)); } - void onPlayTone(const uint16_t frequency, const uint16_t duration) { - tone(BEEPER_PIN, frequency, duration); + void onConfigurationStoreWritten(bool success) { + // Called after the entire EEPROM has been written, + // whether successful or not. } - void onPrintTimerStarted() { } - - void onPrintTimerPaused() { } - - void onPrintTimerStopped() { } - - void onFilamentRunout(const extruder_t extruder) { - is_out_of_filament = true; - SENDLINE_PGM("J23"); // Filament runout - SENDLINE_PGM("J18"); // Print paused - // Note: printer will unload filament automatically + void onConfigurationStoreRead(bool success) { + // Called after the entire EEPROM has been read, + // whether successful or not. } - void onUserConfirmRequired(const char * const msg) { } - - void onStatusChanged(const char * const msg) { } - - void onFactoryReset() { } - - void onStoreSettings(char *buff) { } - - void onLoadSettings(const char *buff) { } - - void onConfigurationStoreWritten(bool success) { } - - void onConfigurationStoreRead(bool success) { } + #if HAS_MESH + void onMeshUpdate(const int8_t xpos, const int8_t ypos, const float zval) { + // Called when any mesh points are updated + //SERIAL_ECHOLNPAIR("onMeshUpdate() x:", xpos, " y:", ypos, " z:", zval); + } - void onMeshUpdate(const int8_t xpos, const int8_t ypos, const float zval) { } + void onMeshUpdate(const int8_t xpos, const int8_t ypos, const ExtUI::probe_state_t state) { + // Called to indicate a special condition + //SERIAL_ECHOLNPAIR("onMeshUpdate() x:", xpos, " y:", ypos, " state:", state); + } + #endif #if ENABLED(POWER_LOSS_RECOVERY) - void onPowerLossResume() { } + // Called on resume from power-loss + void onPowerLossResume() { Chiron.PowerLossRecovery(); } #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/lib/anycubic_chiron/FileNavigator.cpp b/Marlin/src/lcd/extui/lib/anycubic_chiron/FileNavigator.cpp new file mode 100644 index 0000000000..fb4c84abb4 --- /dev/null +++ b/Marlin/src/lcd/extui/lib/anycubic_chiron/FileNavigator.cpp @@ -0,0 +1,162 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * lcd/extui/lib/FileNavigator.cpp + * + * Extensible_UI implementation for Anycubic Chiron + * Written By Nick Wells, 2020 [https://github.com/SwiftNick] + * (not affiliated with Anycubic, Ltd.) + */ + +/*************************************************************************** + * The AC panel wants files in block of 4 and can only display a flat list * + * This library allows full folder traversal. * + ***************************************************************************/ + +#include "../../../../inc/MarlinConfigPre.h" + +#if ENABLED(ANYCUBIC_LCD_CHIRON) + +#include "FileNavigator.h" +#include "chiron_tft.h" + +using namespace ExtUI; + +namespace Anycubic { + + FileList FileNavigator::filelist; // Instance of the Marlin file API + char FileNavigator::currentfoldername[MAX_PATH_LEN]; // Current folder path + uint16_t FileNavigator::lastindex; + uint8_t FileNavigator::folderdepth; + uint16_t FileNavigator::currentindex; // override the panel request + + FileNavigator::FileNavigator() { reset(); } + + void FileNavigator::reset() { + currentfoldername[0] = '\0'; + folderdepth = 0; + currentindex = 0; + lastindex = 0; + // Start at root folder + while (!filelist.isAtRootDir()) filelist.upDir(); + refresh(); + } + + void FileNavigator::refresh() { filelist.refresh(); } + + void FileNavigator::getFiles(uint16_t index) { + uint8_t files = 4; + if (index == 0) currentindex = 0; + + // Each time we change folder we reset the file index to 0 and keep track + // of the current position as the TFT panel isnt aware of folders trees. + if (index > 0) { + --currentindex; // go back a file to take account off the .. we added to the root. + if (index > lastindex) + currentindex += files; + else + currentindex = currentindex < 4 ? 0 : currentindex - files; + } + lastindex = index; + + #if ACDEBUG(AC_FILE) + SERIAL_ECHOLNPAIR("index=", index, " currentindex=", currentindex); + #endif + + if (currentindex == 0 && folderdepth > 0) { // Add a link to go up a folder + TFTSer.println("<<"); + TFTSer.println(".."); + files--; + } + + for (uint16_t seek = currentindex; seek < currentindex + files; seek++) { + if (filelist.seek(seek)) { + sendFile(); + #if ACDEBUG(AC_FILE) + SERIAL_ECHOLNPAIR("-", seek, " '", filelist.longFilename(), "' '", currentfoldername, "", filelist.shortFilename(), "'\n"); + #endif + } + } + } + + void FileNavigator::sendFile() { + // send the file and folder info to the panel + // this info will be returned when the file is selected + // Permitted special characters in file name -_*#~ + // Panel can display 22 characters per line + if (filelist.isDir()) { + //TFTSer.print(currentfoldername); + TFTSer.println(filelist.shortFilename()); + TFTSer.print(filelist.shortFilename()); + TFTSer.println("/"); + } + else { + // Logical Name + TFTSer.print("/"); + if (folderdepth > 0) TFTSer.print(currentfoldername); + + TFTSer.println(filelist.shortFilename()); + + // Display Name + TFTSer.println(filelist.longFilename()); + } + } + void FileNavigator::changeDIR(char *folder) { + #if ACDEBUG(AC_FILE) + SERIAL_ECHOLNPAIR("currentfolder: ", currentfoldername, " New: ", folder); + #endif + if (folderdepth >= MAX_FOLDER_DEPTH) return; // limit the folder depth + strcat(currentfoldername, folder); + strcat(currentfoldername, "/"); + filelist.changeDir(folder); + refresh(); + folderdepth++; + currentindex = 0; + } + + void FileNavigator::upDIR() { + filelist.upDir(); + refresh(); + folderdepth--; + currentindex = 0; + // Remove the last child folder from the stored path + if (folderdepth == 0) { + currentfoldername[0] = '\0'; + reset(); + } + else { + char *pos = nullptr; + for (uint8_t f = 0; f < folderdepth; f++) + pos = strchr(currentfoldername, '/'); + + *(pos + 1) = '\0'; + } + #if ACDEBUG(AC_FILE) + SERIAL_ECHOLNPAIR("depth: ", folderdepth, " currentfoldername: ", currentfoldername); + #endif + } + + char* FileNavigator::getCurrentFolderName() { return currentfoldername; } +} + +#endif // ANYCUBIC_LCD_CHIRON diff --git a/Marlin/src/lcd/extui/lib/anycubic_chiron/FileNavigator.h b/Marlin/src/lcd/extui/lib/anycubic_chiron/FileNavigator.h new file mode 100644 index 0000000000..8e03614a46 --- /dev/null +++ b/Marlin/src/lcd/extui/lib/anycubic_chiron/FileNavigator.h @@ -0,0 +1,56 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * lcd/extui/lib/FileNavigator.h + * + * Extensible_UI implementation for Anycubic Chiron + * Written By Nick Wells, 2020 [https://github.com/SwiftNick] + * (not affiliated with Anycubic, Ltd.) + */ + +#include "chiron_tft_defs.h" +#include "../../ui_api.h" + +using namespace ExtUI; + +namespace Anycubic { + class FileNavigator { + public: + FileNavigator(); + void reset(); + void getFiles(uint16_t); + void upDIR(); + void changeDIR(char *); + void sendFile(); + void refresh(); + char * getCurrentFolderName(); + private: + static FileList filelist; + static char currentfoldername[MAX_PATH_LEN]; + static uint16_t lastindex; + static uint8_t folderdepth; + static uint16_t currentindex; + }; + extern FileNavigator filenavigator; +} diff --git a/Marlin/src/lcd/extui/lib/anycubic_chiron/Tunes.cpp b/Marlin/src/lcd/extui/lib/anycubic_chiron/Tunes.cpp new file mode 100644 index 0000000000..f09c4db3f2 --- /dev/null +++ b/Marlin/src/lcd/extui/lib/anycubic_chiron/Tunes.cpp @@ -0,0 +1,62 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * lcd/extui/lib/Tunes.cpp + * + * Extensible_UI implementation for Anycubic Chiron + * Written By Nick Wells, 2020 [https://github.com/SwiftNick] + * (not affiliated with Anycubic, Ltd.) + */ + +/*********************************************************************** + * A Utility to play tunes using the buzzer in the printer controller. * + * See Tunes.h for note and tune definitions. * + ***********************************************************************/ + +#include "../../../../inc/MarlinConfigPre.h" + +#if ENABLED(ANYCUBIC_LCD_CHIRON) + +#include "Tunes.h" +#include "../../ui_api.h" + +namespace Anycubic { + + void PlayTune(uint8_t beeperPin, const uint16_t *tune, uint8_t speed=1) { + uint8_t pos = 1; + uint16_t wholenotelen = tune[0] / speed; + do { + uint16_t freq = tune[pos]; + uint16_t notelen = wholenotelen / tune[pos + 1]; + + ::tone(beeperPin, freq, notelen); + ExtUI::delay_ms(notelen); + pos += 2; + + if (pos >= MAX_TUNE_LENGTH) break; + } while (tune[pos] != n_END); + } + +} + +#endif // ANYCUBIC_LCD_CHIRON diff --git a/Marlin/src/lcd/extui/lib/anycubic_chiron/Tunes.h b/Marlin/src/lcd/extui/lib/anycubic_chiron/Tunes.h new file mode 100644 index 0000000000..1bafec43ad --- /dev/null +++ b/Marlin/src/lcd/extui/lib/anycubic_chiron/Tunes.h @@ -0,0 +1,224 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * lcd/extui/lib/Tunes.h + * + * Extensible_UI implementation for Anycubic Chiron + * Written By Nick Wells, 2020 [https://github.com/SwiftNick] + * (not affiliated with Anycubic, Ltd.) + */ + +/************************************************************************** + * Notes definition from https://pages.mtu.edu/~suits/NoteFreqCalcs.html * + * * + * The format of a tune is: * + * {,,, ,, ... } * + * * + * 1) The first value is the length of a whole note in milliseconds * + * 2) Then a sequence of pitch and duration pairs * + * 3) Finally the END marker so your tunes can be any length up to * + * MAX_TUNE_LEN * + *************************************************************************/ + +#include + +#define MAX_TUNE_LENGTH 128 + +// Special notes! +#define n_P 0 // silence or pause +#define n_END 10000 // end of tune marker + +// Note duration divisors +#define l_T1 1 +#define l_T2 2 +#define l_T3 3 +#define l_T4 4 +#define l_T8 8 +#define l_T16 16 + +// Note Frequency +#define n_C0 16 +#define n_CS0 17 +#define n_D0 18 +#define n_DS0 19 +#define n_E0 21 +#define n_F0 22 +#define n_FS0 23 +#define n_G0 25 +#define n_GS0 26 +#define n_A0 28 +#define n_AS0 29 +#define n_B0 31 +#define n_C1 33 +#define n_CS1 35 +#define n_D1 37 +#define n_DS1 39 +#define n_E1 41 +#define n_F1 44 +#define n_FS1 46 +#define n_G1 49 +#define n_GS1 52 +#define n_A1 55 +#define n_AS1 58 +#define n_B1 62 +#define n_C2 65 +#define n_CS2 69 +#define n_D2 73 +#define n_DS2 78 +#define n_E2 82 +#define n_F2 87 +#define n_FS2 93 +#define n_G2 98 +#define n_GS2 104 +#define n_A2 110 +#define n_AS2 117 +#define n_B2 123 +#define n_C3 131 +#define n_CS3 139 +#define n_D3 147 +#define n_DS3 156 +#define n_E3 165 +#define n_F3 175 +#define n_FS3 185 +#define n_G3 196 +#define n_GS3 208 +#define n_A3 220 +#define n_AS3 233 +#define n_B3 247 +#define n_C4 262 +#define n_CS4 277 +#define n_D4 294 +#define n_DS4 311 +#define n_E4 330 +#define n_F4 349 +#define n_FS4 370 +#define n_G4 392 +#define n_GS4 415 +#define n_A4 440 +#define n_AS4 466 +#define n_B4 494 +#define n_C5 523 +#define n_CS5 554 +#define n_D5 587 +#define n_DS5 622 +#define n_E5 659 +#define n_F5 698 +#define n_FS5 740 +#define n_G5 784 +#define n_GS5 831 +#define n_A5 880 +#define n_AS5 932 +#define n_B5 988 +#define n_C6 1047 +#define n_CS6 1109 +#define n_D6 1175 +#define n_DS6 1245 +#define n_E6 1319 +#define n_F6 1397 +#define n_FS6 1480 +#define n_G6 1568 +#define n_GS6 1661 +#define n_A6 1760 +#define n_AS6 1865 +#define n_B6 1976 +#define n_C7 2093 +#define n_CS7 2217 +#define n_D7 2349 +#define n_DS7 2489 +#define n_E7 2637 +#define n_F7 2794 +#define n_FS7 2960 +#define n_G7 3136 +#define n_GS7 3322 +#define n_A7 3520 +#define n_AS7 3729 +#define n_B7 3951 +#define n_C8 4186 +#define n_CS8 4435 +#define n_D8 4699 +#define n_DS8 4978 +#define n_E8 5274 +#define n_F8 5587 +#define n_FS8 5920 +#define n_G8 6272 +#define n_GS8 6645 +#define n_A8 7040 +#define n_AS8 7459 +#define n_B8 7902 + +namespace Anycubic { + + void PlayTune(uint8_t beeperPin, const uint16_t *tune, uint8_t speed); + + // Only uncomment the tunes you are using to save memory + // This will help you write tunes! + // https://www.apronus.com/music/flashpiano.htm + + const uint16_t SOS[] = { + 250, + n_G6,l_T3, n_P,l_T3, n_G6,l_T3, n_P,l_T3, n_G6,l_T3, n_P,l_T1, + n_G6,l_T1, n_P,l_T3, n_G6,l_T1, n_P,l_T3, n_G6,l_T1, n_P,l_T1, + n_G6,l_T3, n_P,l_T3, n_G6,l_T3, n_P,l_T3, n_G6,l_T3, n_P,l_T1, + n_END + }; + + const uint16_t BeepBeep[] = { + 500, + n_C7,l_T8, n_P,l_T16, n_C7,l_T8, n_P,l_T8, + n_END + }; + + const uint16_t BeepBeepBeeep[] = { + 1000, + n_G7,l_T4, n_P,l_T16, n_G7,l_T4, n_P,l_T8, n_G7,l_T2, + n_END + }; + + const uint16_t Anycubic_PowerOn[] = { + 1000, + n_F7,l_T8, n_P,l_T8, n_C7,l_T8, n_P,l_T8, n_D7,l_T8, n_P,l_T8, + n_E7,l_T8, n_P,l_T8, n_D7,l_T4, n_P,l_T4, n_G7,l_T4, n_P,l_T4, + n_A7,l_T2, n_P,l_T1, + n_END + }; + + const uint16_t GB_PowerOn[] = { + 500, + n_C6,l_T4, n_P,l_T16, n_C7,l_T2, n_P,l_T8, + n_END + }; + + const uint16_t Heater_Timedout[] = { + 1000, + n_C6,l_T1, + n_END + }; + + const uint16_t FilamentOut[] = { + 1000, + n_AS7,l_T4, n_P,l_T16, n_FS7,l_T2, + n_END + }; + +} diff --git a/Marlin/src/lcd/extui/lib/anycubic_chiron/chiron_tft.cpp b/Marlin/src/lcd/extui/lib/anycubic_chiron/chiron_tft.cpp new file mode 100644 index 0000000000..5e492573e7 --- /dev/null +++ b/Marlin/src/lcd/extui/lib/anycubic_chiron/chiron_tft.cpp @@ -0,0 +1,896 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * lcd/extui/lib/chiron_tft.cpp + * + * Extensible_UI implementation for Anycubic Chiron + * Written By Nick Wells, 2020 [https://github.com/SwiftNick] + * (not affiliated with Anycubic, Ltd.) + */ + +#include "../../../../inc/MarlinConfigPre.h" + +#if ENABLED(ANYCUBIC_LCD_CHIRON) + +#include "chiron_tft.h" +#include "Tunes.h" +#include "FileNavigator.h" + +#include "../../../../gcode/queue.h" +#include "../../../../sd/cardreader.h" +#include "../../../../libs/numtostr.h" +#include "../../../../MarlinCore.h" +namespace Anycubic { + + printer_state_t ChironTFT::printer_state; + paused_state_t ChironTFT::pause_state; + heater_state_t ChironTFT::hotend_state; + heater_state_t ChironTFT::hotbed_state; + xy_uint8_t ChironTFT::selectedmeshpoint; + char ChironTFT::selectedfile[MAX_PATH_LEN]; + char ChironTFT::panel_command[MAX_CMND_LEN]; + uint8_t ChironTFT::command_len; + float ChironTFT::live_Zoffset; + file_menu_t ChironTFT::file_menu; + + ChironTFT::ChironTFT(){} + + void ChironTFT::Startup() { + selectedfile[0] = '\0'; + panel_command[0] = '\0'; + command_len = 0; + printer_state = AC_printer_idle; + pause_state = AC_paused_idle; + hotend_state = AC_heater_off; + hotbed_state = AC_heater_off; + live_Zoffset = 0.0; + file_menu = AC_menu_file; + + // Setup pins for powerloss detection + // Two IO pins are connected on the Trigorilla Board + // On a power interruption the OUTAGECON_PIN goes low. + + #if ENABLED(POWER_LOSS_RECOVERY) + OUT_WRITE(OUTAGECON_PIN, HIGH); + #endif + + // Filament runout is handled by Marlin settings in Configuration.h + // set FIL_RUNOUT_STATE HIGH // Pin state indicating that filament is NOT present. + // enable FIL_RUNOUT_PULLUP + + TFTSer.begin(115200); + + // Signal Board has reset + SendtoTFTLN(AC_msg_main_board_has_reset); + + safe_delay(200); + + // Enable levelling and Disable end stops during print + // as Z home places nozzle above the bed so we need to allow it past the end stops + injectCommands_P(AC_cmnd_enable_levelling); //M211 S0\n")); + + // Startup tunes are defined in Tunes.h + //PlayTune(BEEPER_PIN, Anycubic_PowerOn, 1); + PlayTune(BEEPER_PIN, GB_PowerOn, 1); + #if ACDEBUGLEVEL + SERIAL_ECHOLNPAIR("AC Debug Level ", ACDEBUGLEVEL); + #endif + SendtoTFTLN(AC_msg_ready); + } + + void ChironTFT::IdleLoop() { + if (ReadTFTCommand()) { + ProcessPanelRequest(); + command_len = 0; + } + CheckHeaters(); + } + + void ChironTFT::PrinterKilled(PGM_P error,PGM_P component) { + SendtoTFTLN(AC_msg_kill_lcd); + #if ACDEBUG(AC_MARLIN) + SERIAL_ECHOLNPAIR("PrinterKilled()\nerror: ", error , "\ncomponent: ", component); + #endif + } + + void ChironTFT::MediaEvent(media_event_t event) { + #if ACDEBUG(AC_MARLIN) + SERIAL_ECHOLNPAIR("ProcessMediaStatus() ", event); + #endif + switch (event) { + case AC_media_inserted: + SendtoTFTLN(AC_msg_sd_card_inserted); + break; + + case AC_media_removed: + SendtoTFTLN(AC_msg_sd_card_removed); + break; + + case AC_media_error: + SendtoTFTLN(AC_msg_no_sd_card); + break; + } + } + + void ChironTFT::TimerEvent(timer_event_t event) { + #if ACDEBUG(AC_MARLIN) + SERIAL_ECHOLNPAIR("TimerEvent() ", event); + SERIAL_ECHOLNPAIR("Printer State: ", printer_state); + #endif + + switch (event) { + case AC_timer_started: { + live_Zoffset = 0.0; // reset print offset + setSoftEndstopState(false); // disable endstops to print + printer_state = AC_printer_printing; + SendtoTFTLN(AC_msg_print_from_sd_card); + } break; + + case AC_timer_paused: { + printer_state = AC_printer_paused; + pause_state = AC_paused_idle; + SendtoTFTLN(AC_msg_paused); + } break; + + case AC_timer_stopped: { + if (printer_state != AC_printer_idle) { + printer_state = AC_printer_stopping; + SendtoTFTLN(AC_msg_print_complete); + } + setSoftEndstopState(true); // enable endstops + } break; + } + } + + void ChironTFT::FilamentRunout() { + #if ACDEBUG(AC_MARLIN) + SERIAL_ECHOLNPAIR("FilamentRunout() printer_state ", printer_state); + #endif + // 1 Signal filament out + SendtoTFTLN(isPrintingFromMedia() ? AC_msg_filament_out_alert : AC_msg_filament_out_block); + //printer_state = AC_printer_filament_out; + PlayTune(BEEPER_PIN, FilamentOut, 1); + } + + void ChironTFT::ConfirmationRequest(const char * const msg) { + // M108 continue + #if ACDEBUG(AC_MARLIN) + SERIAL_ECHOLNPAIR("ConfirmationRequest() ", msg, " printer_state:", printer_state); + #endif + switch (printer_state) { + case AC_printer_pausing: { + if ( (strcmp_P(msg, MARLIN_msg_print_paused) == 0 ) || (strcmp_P(msg, MARLIN_msg_nozzle_parked) == 0 ) ) { + SendtoTFTLN(AC_msg_paused); // enable continue button + printer_state = AC_printer_paused; + } + } break; + + case AC_printer_resuming_from_power_outage: + case AC_printer_printing: + case AC_printer_paused: { + // Heater timout, send acknowledgement + if (strcmp_P(msg, MARLIN_msg_heater_timeout) == 0 ) { + pause_state = AC_paused_heater_timed_out; + SendtoTFTLN(AC_msg_paused); // enable continue button + PlayTune(BEEPER_PIN,Heater_Timedout,1); + } + // Reheat finished, send acknowledgement + else if (strcmp_P(msg, MARLIN_msg_reheat_done) == 0 ) { + pause_state = AC_paused_idle; + SendtoTFTLN(AC_msg_paused); // enable continue button + } + // Filament Purging, send acknowledgement enter run mode + else if (strcmp_P(msg, MARLIN_msg_filament_purging) == 0 ) { + pause_state = AC_paused_purging_filament; + SendtoTFTLN(AC_msg_paused); // enable continue button + } + } break; + default: + break; + } + } + + void ChironTFT::StatusChange(const char * const msg) { + #if ACDEBUG(AC_MARLIN) + SERIAL_ECHOLNPAIR("StatusChange() ", msg); + SERIAL_ECHOLNPAIR("printer_state:", printer_state); + #endif + bool msg_matched = false; + // The only way to get printer status is to parse messages + // Use the state to minimise the work we do here. + switch (printer_state) { + case AC_printer_probing: { + // If probing completes ok save the mesh and park + if (strcmp_P(msg, MARLIN_msg_ready) == 0 ) { + injectCommands_P(PSTR("M500\nG27")); + SendtoTFTLN(AC_msg_probing_complete); + printer_state = AC_printer_idle; + msg_matched = true; + } + // If probing fails dont save the mesh raise the probe above the bad point + if (strcmp_P(msg, MARLIN_msg_probing_failed) == 0 ) { + PlayTune(BEEPER_PIN, BeepBeepBeeep, 1); + injectCommands_P(PSTR("G1 Z50 F500")); + SendtoTFTLN(AC_msg_probing_complete); + printer_state = AC_printer_idle; + msg_matched = true; + } + } break; + + case AC_printer_printing: { + if (strcmp_P(msg, MARLIN_msg_reheating) == 0 ) { + SendtoTFTLN(AC_msg_paused); // enable continue button + msg_matched = true; + } + } break; + + case AC_printer_pausing: { + if (strcmp_P(msg, MARLIN_msg_print_paused) == 0 ) { + SendtoTFTLN(AC_msg_paused); + printer_state = AC_printer_paused; + pause_state = AC_paused_idle; + msg_matched = true; + } + } break; + + case AC_printer_stopping: { + if (strcmp_P(msg, MARLIN_msg_print_aborted) == 0 ) { + SendtoTFTLN(AC_msg_stop); + printer_state = AC_printer_idle; + msg_matched = true; + } + } break; + default: + break; + } + + // If not matched earlier see if this was a heater message + if (!msg_matched) { + if (strcmp_P(msg, MARLIN_msg_extruder_heating) == 0) { + SendtoTFTLN(AC_msg_nozzle_heating); + hotend_state = AC_heater_temp_set; + } + else if (strcmp_P(msg, MARLIN_msg_bed_heating) == 0) { + SendtoTFTLN(AC_msg_bed_heating); + hotbed_state = AC_heater_temp_set; + } + } + } + + void ChironTFT::PowerLossRecovery() { + printer_state = AC_printer_resuming_from_power_outage; // Play tune to notify user we can recover. + PlayTune(BEEPER_PIN, SOS, 1); + SERIAL_ECHOLNPGM("Resuming from power outage..."); + SERIAL_ECHOLNPGM("Select SD file then press resume"); + } + + void ChironTFT::SendtoTFT(PGM_P str) { // A helper to print PROGMEN string to the panel + #if ACDEBUG(AC_SOME) + serialprintPGM(str); + #endif + while (const char c = pgm_read_byte(str++)) TFTSer.print(c); + } + + void ChironTFT::SendtoTFTLN(PGM_P str = nullptr) { + if (str != nullptr) { + #if ACDEBUG(AC_SOME) + SERIAL_ECHO("> "); + #endif + SendtoTFT(str); + #if ACDEBUG(AC_SOME) + SERIAL_EOL(); + #endif + } + TFTSer.println(""); + } + + bool ChironTFT::ReadTFTCommand() { + bool command_ready = false; + while( (TFTSer.available() > 0) && (command_len < MAX_CMND_LEN) ) { + panel_command[command_len] = TFTSer.read(); + if(panel_command[command_len] == '\n') { + command_ready = true; + break; + } + command_len++; + } + + if(command_ready) { + panel_command[command_len] = 0x00; + #if ACDEBUG(AC_ALL) + SERIAL_ECHOLNPAIR("< ", panel_command); + #endif + #if ACDEBUG(AC_SOME) + // Ignore status request commands + uint8_t req = atoi(&panel_command[1]); + if (req > 7 && req != 20) { + SERIAL_ECHOLNPAIR("> ", panel_command); + SERIAL_ECHOLNPAIR("printer_state:", printer_state); + } + #endif + } + return command_ready; + } + + int8_t ChironTFT::Findcmndpos(const char * buff, char q) { + bool found = false; + int8_t pos = 0; + do { + if (buff[pos] == q) { + found = true; + break; + } + pos ++; + } while(pos < MAX_CMND_LEN); + if (found) return pos; + return -1; + } + + void ChironTFT::CheckHeaters() { + uint8_t faultDuration = 0; float temp = 0; + + // if the hotend temp is abnormal, confirm state before signalling panel + temp = getActualTemp_celsius(E0); + if ( (temp <= HEATER_0_MINTEMP) || (temp >= HEATER_0_MAXTEMP) ) { + do { + faultDuration ++; + if (faultDuration >= AC_HEATER_FAULT_VALIDATION_TIME) { + SendtoTFTLN(AC_msg_nozzle_temp_abnormal); + SERIAL_ECHOLNPAIR("Extruder temp abnormal! : ", temp); + break; + } + delay_ms(500); + temp = getActualTemp_celsius(E0); + } while ((temp <= HEATER_0_MINTEMP) || (temp >= HEATER_0_MAXTEMP) ); + } + + // if the hotbed temp is abnormal, confirm state before signalling panel + faultDuration = 0; + temp = getActualTemp_celsius(BED); + if ( (temp <= BED_MINTEMP) || (temp >= BED_MAXTEMP) ) { + do { + faultDuration ++; + if (faultDuration >= AC_HEATER_FAULT_VALIDATION_TIME) { + SendtoTFTLN(AC_msg_nozzle_temp_abnormal); + SERIAL_ECHOLNPAIR_P("Bed temp abnormal! : ", temp); + break; + } + delay_ms(500); + temp = getActualTemp_celsius(E0); + } while ((temp <= BED_MINTEMP) || (temp >= BED_MAXTEMP) ); + } + + // Update panel with hotend heater status + if (hotend_state != AC_heater_temp_reached) { + if ( WITHIN( getActualTemp_celsius(E0) - getTargetTemp_celsius(E0), -1, 1 ) ) { + SendtoTFTLN(AC_msg_nozzle_heating_done); + hotend_state = AC_heater_temp_reached; + } + } + + // Update panel with bed heater status + if (hotbed_state != AC_heater_temp_reached) { + if ( WITHIN( getActualTemp_celsius(BED) - getTargetTemp_celsius(BED), -0.5, 0.5 ) ) { + SendtoTFTLN(AC_msg_bed_heating_done); + hotbed_state = AC_heater_temp_reached; + } + } + } + + void ChironTFT::SendFileList(int8_t startindex) { + // respond to panel request for 4 files starting at index + #if ACDEBUG(AC_INFO) + SERIAL_ECHOLNPAIR("## SendFileList ## ", startindex); + #endif + SendtoTFTLN(PSTR("FN ")); + filenavigator.getFiles(startindex); + SendtoTFTLN(PSTR("END")); + } + + void ChironTFT::SelectFile() { + strncpy(selectedfile,panel_command+4,command_len-4); + selectedfile[command_len-5] = '\0'; + #if ACDEBUG(AC_FILE) + SERIAL_ECHOLNPAIR_F(" Selected File: ",selectedfile); + #endif + switch (selectedfile[0]) { + case '/': // Valid file selected + SendtoTFTLN(AC_msg_sd_file_open_success); + break; + + case '<': // .. (go up folder level) + filenavigator.upDIR(); + SendtoTFTLN(AC_msg_sd_file_open_failed); + SendFileList( 0 ); + break; + default: // enter sub folder + filenavigator.changeDIR(selectedfile); + SendtoTFTLN(AC_msg_sd_file_open_failed); + SendFileList( 0 ); + break; + } + } + + void ChironTFT::InjectCommandandWait(PGM_P cmd) { + //injectCommands_P(cmnd); queue.enqueue_now_P(cmd); + //SERIAL_ECHOLN(PSTR("Inject>")); + } + + void ChironTFT::ProcessPanelRequest() { + // Break these up into logical blocks // as its easier to navigate than one huge switch case! + int8_t req = atoi(&panel_command[1]); + + // Information requests A0 - A8 and A33 + if (req <= 8 || req == 33) PanelInfo(req); + + // Simple Actions A9 - A28 + else if ( req <= 28) PanelAction(req); + + // Process Initiation + else if (req <= 34) PanelProcess(req); + + else SendtoTFTLN(); + } + + void ChironTFT::PanelInfo(uint8_t req) { + // information requests A0-A8 and A33 + switch (req) { + case 0: // A0 Get HOTEND Temp + SendtoTFT(PSTR("A0V ")); + TFTSer.println(getActualTemp_celsius(E0)); + break; + + case 1: // A1 Get HOTEND Target Temp + SendtoTFT(PSTR("A1V ")); + TFTSer.println(getTargetTemp_celsius(E0)); + break; + + case 2: // A2 Get BED Temp + SendtoTFT(PSTR("A2V ")); + TFTSer.println(getActualTemp_celsius(BED)); + break; + + case 3: // A3 Get BED Target Temp + SendtoTFT(PSTR("A3V ")); + TFTSer.println(getTargetTemp_celsius(BED)); + break; + + case 4: // A4 Get FAN Speed + SendtoTFT(PSTR("A4V ")); + TFTSer.println(getActualFan_percent(FAN0)); + break; + + case 5: // A5 Get Current Coordinates + SendtoTFT(PSTR("A5V X: ")); + TFTSer.print(getAxisPosition_mm(X)); + SendtoTFT(PSTR(" Y: ")); + TFTSer.print(getAxisPosition_mm(Y)); + SendtoTFT(PSTR(" Z: ")); + TFTSer.println(getAxisPosition_mm(Z)); + break; + + case 6: // A6 Get printing progress + if (isPrintingFromMedia()) { + SendtoTFT(PSTR("A6V ")); + TFTSer.println(ui8tostr2(getProgress_percent())); + + } + else + SendtoTFTLN(PSTR("A6V ---")); + break; + + case 7: { // A7 Get Printing Time + uint32_t time = getProgress_seconds_elapsed() / 60; + SendtoTFT(PSTR("A7V ")); + TFTSer.print(ui8tostr2(time / 60)); + SendtoTFT(PSTR(" H ")); + TFTSer.print(ui8tostr2(time % 60)); + SendtoTFT(PSTR(" M")); + #if ACDEBUG(AC_ALL) + SERIAL_ECHOLNPAIR("Print time ", ui8tostr2(time / 60), ":", ui8tostr2(time % 60)); + #endif + } break; + + case 8: // A8 Get SD Card list A8 S0 + if (!isMediaInserted()) safe_delay(500); + if (!isMediaInserted()) // Make sure the card is removed + SendtoTFTLN(AC_msg_no_sd_card); + else if (panel_command[3] == 'S') + SendFileList( atoi( &panel_command[4] ) ); + break; + + case 33: // A33 Get firmware info + SendtoTFT(PSTR("J33 ")); + SendtoTFTLN(PSTR(SHORT_BUILD_VERSION)); + break; + } + } + + void ChironTFT::PanelAction(uint8_t req) { + switch (req) { + case 9: // A9 Pause SD print + if (isPrintingFromMedia()) { + SendtoTFTLN(AC_msg_pause); + pausePrint(); + printer_state = AC_printer_pausing; + } + else + SendtoTFTLN(AC_msg_stop); + break; + + case 10: // A10 Resume SD Print + if (pause_state == AC_paused_idle || printer_state == AC_printer_resuming_from_power_outage) + resumePrint(); + else + setUserConfirmed(); + break; + + case 11: // A11 Stop SD print + if (isPrintingFromMedia()) { + printer_state = AC_printer_stopping; + stopPrint(); + } + else { + if (printer_state == AC_printer_resuming_from_power_outage) + injectCommands_P(PSTR("M1000 C\n")); // Cancel recovery + SendtoTFTLN(AC_msg_stop); + printer_state = AC_printer_idle; + } + break; + + case 12: // A12 Kill printer + kill(); // from marlincore.h + break; + + case 13: // A13 Select file + SelectFile(); + break; + + case 14: { // A14 Start Printing + // Allows printer to restart the job if we dont want to recover + if (printer_state == AC_printer_resuming_from_power_outage) { + injectCommands_P(PSTR("M1000 C\n")); // Cancel recovery + printer_state = AC_printer_idle; + } + #if ACDebugLevel >= 1 + SERIAL_ECHOLNPAIR_F("Print: ", selectedfile); + #endif + // the card library needs a path starting // but the File api doesn't... + char file[MAX_PATH_LEN]; + file[0] = '/'; + strcpy(file + 1, selectedfile); + printFile(file); + SendtoTFTLN(AC_msg_print_from_sd_card); + } break; + + case 15: // A15 Resuming from outage + if (printer_state == AC_printer_resuming_from_power_outage) + // Need to home here to restore the Z position + injectCommands_P(AC_cmnd_power_loss_recovery); + + injectCommands_P(PSTR("M1000\n")); // home and start recovery + break; + + case 16: { // A16 Set HotEnd temp A17 S170 + const float set_Htemp = atof(&panel_command[5]); + hotend_state = set_Htemp ? AC_heater_temp_set : AC_heater_off; + switch ((char)panel_command[4]) { + // Set Temp + case 'S': case 'C': setTargetTemp_celsius(set_Htemp, E0); + } + } break; + + case 17: { // A17 Set bed temp + const float set_Btemp = atof(&panel_command[5]); + hotbed_state = set_Btemp ? AC_heater_temp_set : AC_heater_off; + if (panel_command[4] == 'S') + setTargetTemp_celsius(set_Btemp, BED); + } break; + + case 18: // A18 Set Fan Speed + if (panel_command[4] == 'S') + setTargetFan_percent(atof(&panel_command[5]), FAN0); + break; + + case 19: // A19 Motors off + if (!isPrinting()) { + disable_all_steppers(); // from marlincore.h + SendtoTFTLN(AC_msg_ready); + } + break; + + case 20: // A20 Read/write print speed + if (panel_command[4] == 'S') + setFeedrate_percent(atoi(&panel_command[5])); + else { + SendtoTFT(PSTR("A20V ")); + TFTSer.println(getFeedrate_percent()); + } + break; + + case 21: // A21 Home Axis A21 X + if (!isPrinting()) { + switch ((char)panel_command[4]) { + case 'X': injectCommands_P(PSTR("G28 X\n")); break; + case 'Y': injectCommands_P(PSTR("G28 Y\n")); break; + case 'Z': injectCommands_P(PSTR("G28 Z\n")); break; + case 'C': injectCommands_P(PSTR("G28\n")); break; + } + } + break; + + case 22: // A22 Move Axis A22 Y +10F3000 + // Ignore request if printing + if (!isPrinting()) { + // setAxisPosition_mm() uses pre defined manual feedrates so ignore the feedrate from the panel + setSoftEndstopState(true); // enable endstops + float newposition = atof(&panel_command[6]); + + #if ACDEBUG(AC_ACTION) + SERIAL_ECHOLNPAIR("Nudge ", panel_command[4], " axis ", newposition); + #endif + + switch (panel_command[4]) { + case 'X': setAxisPosition_mm(getAxisPosition_mm(X) + newposition, X); break; + case 'Y': setAxisPosition_mm(getAxisPosition_mm(Y) + newposition, Y); break; + case 'Z': setAxisPosition_mm(getAxisPosition_mm(Z) + newposition, Z); break; + case 'E': // The only time we get this command is from the filament load/unload menu + // the standard movement is too slow so we will use the load unlod GCode to speed it up a bit + if (canMove(E0) && !commandsInQueue()) + injectCommands_P(newposition > 0 ? AC_cmnd_manual_load_filament : AC_cmnd_manual_unload_filament); + break; + } + } + break; + + case 23: // A23 Preheat PLA + // Ignore request if printing + if (!isPrinting()) { + // Temps defined in configuration.h + setTargetTemp_celsius(PREHEAT_1_TEMP_BED, BED); + setTargetTemp_celsius(PREHEAT_1_TEMP_HOTEND, E0); + SendtoTFTLN(); + hotbed_state = AC_heater_temp_set; + hotend_state = AC_heater_temp_set; + } + break; + + case 24: // A24 Preheat ABS + // Ignore request if printing + if (!isPrinting()) { + setTargetTemp_celsius(PREHEAT_2_TEMP_BED, BED); + setTargetTemp_celsius(PREHEAT_2_TEMP_HOTEND, E0); + SendtoTFTLN(); + hotbed_state = AC_heater_temp_set; + hotend_state = AC_heater_temp_set; + } + break; + + case 25: // A25 Cool Down + // Ignore request if printing + if (!isPrinting()) { + setTargetTemp_celsius(0, E0); + setTargetTemp_celsius(0, BED); + SendtoTFTLN(AC_msg_ready); + hotbed_state = AC_heater_off; + hotend_state = AC_heater_off; + } + break; + + case 26: // A26 Refresh SD + // M22 M21 maybe needed here to reset sd card + filenavigator.reset(); + break; + + case 27: // A27 Servo Angles adjust + break; + + case 28: // A28 Filament set A28 O/C + // Ignore request if printing + if (isPrinting()) break; + SendtoTFTLN(); + break; + } + } + + void ChironTFT::PanelProcess(uint8_t req) { + switch (req) { + case 29: { // A29 Read Mesh Point A29 X1 Y1 + xy_uint8_t pos; + float pos_z; + pos.x = atoi(&panel_command[5]); + pos.y = atoi(&panel_command[8]); + pos_z = getMeshPoint(pos); + + SendtoTFT(PSTR("A29V ")); + TFTSer.println(pos_z * 100); + if (!isPrinting()) { + setSoftEndstopState(true); // disable endstops + // If the same meshpoint is selected twice in a row, move the head to that ready for adjustment + if ((selectedmeshpoint.x == pos.x) && (selectedmeshpoint.y == pos.y)) { + if (!isPositionKnown()) + injectCommands_P(PSTR("G28\n")); // home + + if (isPositionKnown()) { + #if ACDEBUG(AC_INFO) + SERIAL_ECHOLNPAIR("Moving to mesh point at x: ", pos.x, " y: ", pos.y, " z: ", pos_z); + #endif + // Go up before moving + setAxisPosition_mm(3.0,Z); + + setAxisPosition_mm(17 + (93 * pos.x), X); + setAxisPosition_mm(20 + (93 * pos.y), Y); + setAxisPosition_mm(0.0, Z); + #if ACDEBUG(AC_INFO) + SERIAL_ECHOLNPAIR("Current Z: ", getAxisPosition_mm(Z)); + #endif + } + } + selectedmeshpoint.x = pos.x; + selectedmeshpoint.y = pos.y; + } + } break; + + case 30: { // A30 Auto leveling + if (panel_command[3] == 'S') { // Start probing + // Ignore request if printing + if (isPrinting()) + SendtoTFTLN(AC_msg_probing_not_allowed); // forbid auto leveling + else { + injectCommands_P(isMachineHomed() ? PSTR("G29") : PSTR("G28\nG29")); + printer_state = AC_printer_probing; + SendtoTFTLN(AC_msg_start_probing); + } + } + else SendtoTFTLN(AC_msg_start_probing); + } break; + + case 31: { // A31 Adjust all Probe Points + switch (panel_command[3]) { + case 'C': // Restore and apply original offsets + if (!isPrinting()) { + injectCommands_P(PSTR("M501\nM420 S1\n")); + selectedmeshpoint.x = 99; + selectedmeshpoint.y = 99; + } + break; + case 'D': // Save Z Offset tables and restore levelling state + if (!isPrinting()) { + setAxisPosition_mm(1.0,Z); + injectCommands_P(PSTR("M500\n")); + selectedmeshpoint.x = 99; + selectedmeshpoint.y = 99; + } + break; + case 'G': // Get current offset + SendtoTFT(PSTR("A31V ")); + // When printing use the live z Offset position + // we will use babystepping to move the print head + if (isPrinting()) + TFTSer.println(live_Zoffset); + else { + TFTSer.println(getZOffset_mm()); + selectedmeshpoint.x = 99; + selectedmeshpoint.y = 99; + } + break; + case 'S': { // Set offset (adjusts all points by value) + float Zshift = atof(&panel_command[4]); + setSoftEndstopState(false); // disable endstops + // Allow temporary Z position nudging during print + // From the levelling panel use the all points UI to adjust the print pos. + if (isPrinting()) { + #if ACDEBUG(AC_INFO) + SERIAL_ECHOLNPAIR("Change Zoffset from:", live_Zoffset, " to ", live_Zoffset + Zshift); + #endif + if (isAxisPositionKnown(Z)) { + #if ACDEBUG(AC_INFO) + const float currZpos = getAxisPosition_mm(Z); + SERIAL_ECHOLNPAIR("Nudge Z pos from ", currZpos, " to ", currZpos + constrain(Zshift, -0.05, 0.05)); + #endif + // Use babystepping to adjust the head position + int16_t steps = mmToWholeSteps(constrain(Zshift,-0.05,0.05), Z); + #if ACDEBUG(AC_INFO) + SERIAL_ECHOLNPAIR("Steps to move Z: ", steps); + #endif + babystepAxis_steps(steps, Z); + live_Zoffset += Zshift; + } + SendtoTFT(PSTR("A31V ")); + TFTSer.println(live_Zoffset); + } + else { + GRID_LOOP(x, y) { + const xy_uint8_t pos { x, y }; + const float currval = getMeshPoint(pos); + setMeshPoint(pos, constrain(currval + Zshift, AC_LOWEST_MESHPOINT_VAL, 2)); + } + const float currZOffset = getZOffset_mm(); + #if ACDEBUG(AC_INFO) + SERIAL_ECHOLNPAIR("Change probe offset from ", currZOffset, " to ", currZOffset + Zshift); + #endif + + setZOffset_mm(currZOffset + Zshift); + SendtoTFT(PSTR("A31V ")); + TFTSer.println(getZOffset_mm()); + + if (isAxisPositionKnown(Z)) { + // Move Z axis + const float currZpos = getAxisPosition_mm(Z); + #if ACDEBUG(AC_INFO) + SERIAL_ECHOLNPAIR("Move Z pos from ", currZpos, " to ", currZpos + constrain(Zshift, -0.05, 0.05)); + #endif + setAxisPosition_mm(currZpos+constrain(Zshift,-0.05,0.05),Z); + } + } + } break; + } // end switch + } break; + + case 32: { // A32 clean leveling beep flag + // Ignore request if printing + //if (isPrinting()) break; + //injectCommands_P(PSTR("M500\nM420 S1\nG1 Z10 F240\nG1 X0 Y0 F6000")); + //TFTSer.println(""); + } break; + + // A33 firmware info request seet PanelInfo() + + case 34: { // A34 Adjust single mesh point A34 C/S X1 Y1 V123 + if (panel_command[3] == 'C') { // Restore original offsets + injectCommands_P(PSTR("M501\nM420 S1")); + selectedmeshpoint.x = 99; + selectedmeshpoint.y = 99; + //printer_state = AC_printer_idle; + } + else { + xy_uint8_t pos; + pos.x = atoi(&panel_command[5]); + pos.y = atoi(&panel_command[8]); + + float currmesh = getMeshPoint(pos); + float newval = atof(&panel_command[11])/100; + #if ACDEBUG(AC_INFO) + SERIAL_ECHOLNPAIR("Change mesh point x:", pos.x, " y:", pos.y); + SERIAL_ECHOLNPAIR("from ", currmesh, " to ", newval); + #endif + // Update Meshpoint + setMeshPoint(pos,newval); + if ( (printer_state == AC_printer_idle) || (printer_state == AC_printer_probing) ) {//!isPrinting()) { + // if we are at the current mesh point indicated on the panel Move Z pos +/- 0.05mm ( The panel changes the mesh value by +/- 0.05mm on each button press) + if ((selectedmeshpoint.x == pos.x) && (selectedmeshpoint.y == pos.y)) { + setSoftEndstopState(false); + float currZpos = getAxisPosition_mm(Z); + #if ACDEBUG(AC_INFO) + SERIAL_ECHOLNPAIR("Move Z pos from ", currZpos, " to ", currZpos + constrain(newval - currmesh, -0.05, 0.05)); + #endif + setAxisPosition_mm(currZpos + constrain(newval - currmesh, -0.05, 0.05), Z); + } + } + } + } break; + } + } +} // namespace + +#endif // ANYCUBIC_LCD_CHIRON diff --git a/Marlin/src/lcd/extui/lib/anycubic_chiron/chiron_tft.h b/Marlin/src/lcd/extui/lib/anycubic_chiron/chiron_tft.h new file mode 100644 index 0000000000..267f2fe978 --- /dev/null +++ b/Marlin/src/lcd/extui/lib/anycubic_chiron/chiron_tft.h @@ -0,0 +1,77 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * lcd/extui/lib/chiron_tft.h + * + * Extensible_UI implementation for Anycubic Chiron + * Written By Nick Wells, 2020 [https://github.com/SwiftNick] + * (not affiliated with Anycubic, Ltd.) + */ + +#include "chiron_tft_defs.h" +#include "../../../../inc/MarlinConfigPre.h" +#include "../../ui_api.h" +namespace Anycubic { + + class ChironTFT { + static printer_state_t printer_state; + static paused_state_t pause_state; + static heater_state_t hotend_state; + static heater_state_t hotbed_state; + static xy_uint8_t selectedmeshpoint; + static char panel_command[MAX_CMND_LEN]; + static uint8_t command_len; + static char selectedfile[MAX_PATH_LEN]; + static float live_Zoffset; + static file_menu_t file_menu; + public: + ChironTFT(); + void Startup(); + void IdleLoop(); + void PrinterKilled(PGM_P,PGM_P); + void MediaEvent(media_event_t); + void TimerEvent(timer_event_t); + void FilamentRunout(); + void ConfirmationRequest(const char * const ); + void StatusChange(const char * const ); + void PowerLossRecovery(); + + private: + void SendtoTFT(PGM_P); + void SendtoTFTLN(PGM_P); + bool ReadTFTCommand(); + int8_t Findcmndpos(const char *, char); + void CheckHeaters(); + void SendFileList(int8_t); + void SelectFile(); + void InjectCommandandWait(PGM_P); + void ProcessPanelRequest(); + void PanelInfo(uint8_t); + void PanelAction(uint8_t); + void PanelProcess(uint8_t); + }; + + extern ChironTFT Chiron; + +} diff --git a/Marlin/src/lcd/extui/lib/anycubic_chiron/chiron_tft_defs.h b/Marlin/src/lcd/extui/lib/anycubic_chiron/chiron_tft_defs.h new file mode 100644 index 0000000000..937bdfde33 --- /dev/null +++ b/Marlin/src/lcd/extui/lib/anycubic_chiron/chiron_tft_defs.h @@ -0,0 +1,151 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * lcd/extui/lib/chiron_defs.h + * + * Extensible_UI implementation for Anycubic Chiron + * Written By Nick Wells, 2020 [https://github.com/SwiftNick] + * (not affiliated with Anycubic, Ltd.) + */ + +#pragma once +#include "../../../../inc/MarlinConfigPre.h" +//#define ACDEBUGLEVEL 255 + +#if ACDEBUGLEVEL + // Bit-masks for selective debug: + enum ACDebugMask : uint8_t { + AC_INFO = 1, + AC_ACTION = 2, + AC_FILE = 4, + AC_PANEL = 8, + AC_MARLIN = 16, + AC_SOME = 32, + AC_ALL = 64 + }; + #define ACDEBUG(mask) ( ((mask) & ACDEBUGLEVEL) == mask ) // Debug flag macro +#else + #define ACDEBUG(mask) false +#endif + +#define TFTSer LCD_SERIAL // Serial interface for TFT panel now uses marlinserial +#define MAX_FOLDER_DEPTH 4 // Limit folder depth TFT has a limit for the file path +#define MAX_CMND_LEN 16 * MAX_FOLDER_DEPTH // Maximum Length for a Panel command +#define MAX_PATH_LEN 16 * MAX_FOLDER_DEPTH // Maximum number of characters in a SD file path + +#define AC_HEATER_FAULT_VALIDATION_TIME 5 // number of 1/2 second loops before signalling a heater fault +#define AC_LOWEST_MESHPOINT_VAL -7.00 // The lowest value you can set for a single mesh point offset + + // TFT panel commands +#define AC_msg_sd_card_inserted PSTR("J00") +#define AC_msg_sd_card_removed PSTR("J01") +#define AC_msg_no_sd_card PSTR("J02") +#define AC_msg_usb_connected PSTR("J03") +#define AC_msg_print_from_sd_card PSTR("J04") +#define AC_msg_pause PSTR("J05") +#define AC_msg_nozzle_heating PSTR("J06") +#define AC_msg_nozzle_heating_done PSTR("J07") +#define AC_msg_bed_heating PSTR("J08") +#define AC_msg_bed_heating_done PSTR("J09") +#define AC_msg_nozzle_temp_abnormal PSTR("J10") +#define AC_msg_kill_lcd PSTR("J11") +#define AC_msg_ready PSTR("J12") +#define AC_msg_low_nozzle_temp PSTR("J13") +#define AC_msg_print_complete PSTR("J14") +#define AC_msg_filament_out_alert PSTR("J15") +#define AC_msg_stop PSTR("J16") +#define AC_msg_main_board_has_reset PSTR("J17") +#define AC_msg_paused PSTR("J18") +#define AC_msg_j19_unknown PSTR("J19") +#define AC_msg_sd_file_open_success PSTR("J20") +#define AC_msg_sd_file_open_failed PSTR("J21") +#define AC_msg_level_monitor_finished PSTR("J22") +#define AC_msg_filament_out_block PSTR("J23") +#define AC_msg_probing_not_allowed PSTR("J24") +#define AC_msg_probing_complete PSTR("J25") +#define AC_msg_start_probing PSTR("J26") +#define AC_msg_version PSTR("J27") + +#define MARLIN_msg_start_probing PSTR("Probing Point 1/25") +#define MARLIN_msg_probing_failed PSTR("Probing Failed") +#define MARLIN_msg_ready PSTR("3D Printer Ready.") +#define MARLIN_msg_print_paused PSTR("Print Paused") +#define MARLIN_msg_print_aborted PSTR("Print Aborted") +#define MARLIN_msg_extruder_heating PSTR("E Heating...") +#define MARLIN_msg_bed_heating PSTR("Bed Heating...") + +#define MARLIN_msg_nozzle_parked PSTR("Nozzle Parked") +#define MARLIN_msg_heater_timeout PSTR("Heater Timeout") +#define MARLIN_msg_reheating PSTR("Reheating...") +#define MARLIN_msg_reheat_done PSTR("Reheat finished.") +#define MARLIN_msg_filament_purging PSTR("Filament Purging...") +#define MARLIN_msg_special_pause PSTR("PB") +#define AC_cmnd_auto_unload_filament PSTR("M701") // Use Marlin unload routine +#define AC_cmnd_auto_load_filament PSTR("M702 M0 PB") // Use Marlin load routing then pause for user to clean nozzle + +#define AC_cmnd_manual_load_filament PSTR("M83\nG1 E50 F700\nM82") // replace the manual panel commands with something a little faster +#define AC_cmnd_manual_unload_filament PSTR("M83\nG1 E-50 F1200\nM82") +#define AC_cmnd_enable_levelling PSTR("M420 S1 V1") +#define AC_cmnd_power_loss_recovery PSTR("G28 X Y R5\nG28 Z") // Lift, home X and Y then home Z when in 'safe' position + +namespace Anycubic { + enum heater_state_t : uint8_t { + AC_heater_off, + AC_heater_temp_set, + AC_heater_temp_reached + }; + + enum paused_state_t : uint8_t { + AC_paused_heater_timed_out, + AC_paused_purging_filament, + AC_paused_idle + }; + + enum printer_state_t : uint8_t { + AC_printer_idle, + AC_printer_probing, + AC_printer_printing, + AC_printer_pausing, + AC_printer_paused, + AC_printer_stopping, + AC_printer_resuming_from_power_outage + }; + + enum timer_event_t : uint8_t { + AC_timer_started, + AC_timer_paused, + AC_timer_stopped + }; + + enum media_event_t : uint8_t { + AC_media_inserted, + AC_media_removed, + AC_media_error + }; + enum file_menu_t : uint8_t { + AC_menu_file, + AC_menu_command, + AC_menu_change_to_file, + AC_menu_change_to_command + }; +} diff --git a/Marlin/src/lcd/extui/lib/anycubic_i3mega/anycubic_i3mega_lcd.cpp b/Marlin/src/lcd/extui/lib/anycubic_i3mega/anycubic_i3mega_lcd.cpp index 1c9b9299fc..b383cee09c 100644 --- a/Marlin/src/lcd/extui/lib/anycubic_i3mega/anycubic_i3mega_lcd.cpp +++ b/Marlin/src/lcd/extui/lib/anycubic_i3mega/anycubic_i3mega_lcd.cpp @@ -24,15 +24,17 @@ #if ENABLED(ANYCUBIC_LCD_I3MEGA) #include "anycubic_i3mega_lcd.h" +#include "../../ui_api.h" +#include "../../../../libs/numtostr.h" +#include "../../../../module/motion.h" // for A20 read printing speed feedrate_percentage +#include "../../../../MarlinCore.h" // for quickstop_stepper and disable_steppers #include "../../../../inc/MarlinConfig.h" -#include "../../ui_api.h" -#include "../../../../MarlinCore.h" // for quickstop_stepper and disable_steppers // command sending macro's with debugging capability #define SEND_PGM(x) send_P(PSTR(x)) #define SENDLINE_PGM(x) sendLine_P(PSTR(x)) -#define SEND_PGM_VAL(x,y) (send_P(PSTR(x)), sendLine(itostr3(y))) +#define SEND_PGM_VAL(x,y) (send_P(PSTR(x)), sendLine(i8tostr3rj(y))) #define SEND(x) send(x) #define SENDLINE(x) sendLine(x) #if ENABLED(ANYCUBIC_LCD_DEBUG) @@ -43,27 +45,15 @@ #define SENDLINE_DBG_PGM_VAL(x,y,z) sendLine_P(PSTR(x)) #endif - AnycubicTFTClass AnycubicTFT; -char _conv[8]; - -char *itostr2(const uint8_t &x) { - // sprintf(conv,"%5.1f",x); - int xx = x; - _conv[0] = (xx / 10) % 10 + '0'; - _conv[1] = (xx) % 10 + '0'; - _conv[2] = 0; - return _conv; -} - static void sendNewLine(void) { - ANYCUBIC_LCD_SERIAL.write('\r'); - ANYCUBIC_LCD_SERIAL.write('\n'); + LCD_SERIAL.write('\r'); + LCD_SERIAL.write('\n'); } static void send(const char *str) { - ANYCUBIC_LCD_SERIAL.print(str); + LCD_SERIAL.print(str); } static void sendLine(const char *str) { @@ -73,7 +63,7 @@ static void sendLine(const char *str) { static void send_P(PGM_P str) { while (const char c = pgm_read_byte(str++)) - ANYCUBIC_LCD_SERIAL.write(c); + LCD_SERIAL.write(c); } static void sendLine_P(PGM_P str) { @@ -81,49 +71,23 @@ static void sendLine_P(PGM_P str) { sendNewLine(); } -#ifndef ULTRA_LCD - #define DIGIT(n) ('0' + (n)) - #define DIGIMOD(n, f) DIGIT((n) / (f) % 10) - #define RJDIGIT(n, f) ((n) >= (f) ? DIGIMOD(n, f) : ' ') - #define MINUSOR(n, alt) (n >= 0 ? (alt) : (n = -n, '-')) - - char* itostr3(const int x) { - int xx = x; - _conv[4] = MINUSOR(xx, RJDIGIT(xx, 100)); - _conv[5] = RJDIGIT(xx, 10); - _conv[6] = DIGIMOD(xx, 1); - return &_conv[4]; - } - -// Convert signed float to fixed-length string with 023.45 / -23.45 format - char *ftostr32(const float &x) { - long xx = x * 100; - _conv[1] = MINUSOR(xx, DIGIMOD(xx, 10000)); - _conv[2] = DIGIMOD(xx, 1000); - _conv[3] = DIGIMOD(xx, 100); - _conv[4] = '.'; - _conv[5] = DIGIMOD(xx, 10); - _conv[6] = DIGIMOD(xx, 1); - return &_conv[1]; - } - -#endif - AnycubicTFTClass::AnycubicTFTClass() {} void AnycubicTFTClass::OnSetup() { - ANYCUBIC_LCD_SERIAL.begin(115200); + #ifndef LCD_BAUDRATE + #define LCD_BAUDRATE 115200 + #endif + LCD_SERIAL.begin(LCD_BAUDRATE); + SENDLINE_DBG_PGM("J17", "TFT Serial Debug: Main board reset... J17"); // J17 Main board reset ExtUI::delay_ms(10); // initialise the state of the key pins running on the tft #if ENABLED(SDSUPPORT) && PIN_EXISTS(SD_DETECT) - pinMode(SD_DETECT_PIN, INPUT); - WRITE(SD_DETECT_PIN, HIGH); + SET_INPUT_PULLUP(SD_DETECT_PIN); #endif #if ENABLED(FILAMENT_RUNOUT_SENSOR) - pinMode(FIL_RUNOUT_PIN, INPUT); - WRITE(FIL_RUNOUT_PIN, HIGH); + SET_INPUT_PULLUP(FIL_RUNOUT_PIN); #endif mediaPrintingState = AMPRINTSTATE_NOT_PRINTING; @@ -178,7 +142,7 @@ void AnycubicTFTClass::OnKillTFT() { void AnycubicTFTClass::OnSDCardStateChange(bool isInserted) { #if ENABLED(ANYCUBIC_LCD_DEBUG) SERIAL_ECHOPGM("TFT Serial Debug: OnSDCardStateChange event triggered..."); - SERIAL_ECHO(itostr2(isInserted)); + SERIAL_ECHO(ui8tostr2(isInserted)); SERIAL_EOL(); #endif DoSDCardStateCheck(); @@ -412,6 +376,7 @@ void AnycubicTFTClass::RenderCurrentFileList() { uint16_t selectedNumber = 0; SelectedDirectory[0] = 0; SelectedFile[0] = 0; + ExtUI::FileList currentFileList; SENDLINE_PGM("FN "); // Filelist start @@ -427,7 +392,7 @@ void AnycubicTFTClass::RenderCurrentFileList() { if (SpecialMenu) RenderSpecialMenu(selectedNumber); - else + else if (selectedNumber <= currentFileList.count()) RenderCurrentFolder(selectedNumber); } SENDLINE_PGM("END"); // Filelist stop @@ -572,8 +537,8 @@ void AnycubicTFTClass::OnPrintTimerStopped() { void AnycubicTFTClass::GetCommandFromTFT() { char *starpos = NULL; - while (ANYCUBIC_LCD_SERIAL.available() > 0 && TFTbuflen < TFTBUFSIZE) { - serial3_char = ANYCUBIC_LCD_SERIAL.read(); + while (LCD_SERIAL.available() > 0 && TFTbuflen < TFTBUFSIZE) { + serial3_char = LCD_SERIAL.read(); if (serial3_char == '\n' || serial3_char == '\r' || serial3_char == ':' || @@ -618,62 +583,53 @@ void AnycubicTFTClass::GetCommandFromTFT() { case 3: { // A3 GET HOTBED TARGET TEMP float heatedBedTargetTemp = ExtUI::getTargetTemp_celsius((ExtUI::heater_t) ExtUI::BED); SEND_PGM_VAL("A3V ", int(heatedBedTargetTemp + 0.5)); - } - break; + } break; - case 4: // A4 GET FAN SPEED - { + case 4: { // A4 GET FAN SPEED float fanPercent = ExtUI::getActualFan_percent(ExtUI::FAN0); fanPercent = constrain(fanPercent, 0, 100); SEND_PGM_VAL("A4V ", int(fanPercent)); - } - break; + } break; - case 5: // A5 GET CURRENT COORDINATE - { + case 5: { // A5 GET CURRENT COORDINATE float xPostition = ExtUI::getAxisPosition_mm(ExtUI::X); float yPostition = ExtUI::getAxisPosition_mm(ExtUI::Y); float zPostition = ExtUI::getAxisPosition_mm(ExtUI::Z); SEND_PGM("A5V X: "); - ANYCUBIC_LCD_SERIAL.print(xPostition); + LCD_SERIAL.print(xPostition); SEND_PGM(" Y: "); - ANYCUBIC_LCD_SERIAL.print(yPostition); + LCD_SERIAL.print(yPostition); SEND_PGM(" Z: "); - ANYCUBIC_LCD_SERIAL.print(zPostition); + LCD_SERIAL.print(zPostition); SENDLINE_PGM(""); - } - break; + } break; case 6: // A6 GET SD CARD PRINTING STATUS #if ENABLED(SDSUPPORT) if (ExtUI::isPrintingFromMedia()) { SEND_PGM("A6V "); - if (ExtUI::isMediaInserted()) { - SENDLINE(itostr3(int(ExtUI::getProgress_percent()))); - } - else { + if (ExtUI::isMediaInserted()) + SENDLINE(ui8tostr3rj(ExtUI::getProgress_percent())); + else SENDLINE_DBG_PGM("J02", "TFT Serial Debug: No SD Card mounted to return printing status... J02"); - } } - else { + else SENDLINE_PGM("A6V ---"); - } #endif break; case 7: { // A7 GET PRINTING TIME - uint32_t elapsedSeconds = ExtUI::getProgress_seconds_elapsed(); + const uint32_t elapsedSeconds = ExtUI::getProgress_seconds_elapsed(); SEND_PGM("A7V "); if (elapsedSeconds != 0) { // print time - uint32_t elapsedMinutes = elapsedSeconds / 60; - SEND(itostr2(elapsedMinutes / 60)); + const uint32_t elapsedMinutes = elapsedSeconds / 60; + SEND(ui8tostr2(elapsedMinutes / 60)); SEND_PGM(" H "); - SEND(itostr2(elapsedMinutes % 60)); + SEND(ui8tostr2(elapsedMinutes % 60)); SENDLINE_PGM(" M"); } - else { + else SENDLINE_PGM(" 999:999"); - } } break; @@ -688,7 +644,6 @@ void AnycubicTFTClass::GetCommandFromTFT() { #if ENABLED(SDSUPPORT) if (ExtUI::isPrintingFromMedia()) PausePrint(); - #endif break; @@ -696,14 +651,11 @@ void AnycubicTFTClass::GetCommandFromTFT() { #if ENABLED(SDSUPPORT) if (ExtUI::isPrintingFromMediaPaused()) ResumePrint(); - #endif break; case 11: // A11 STOP SD PRINT - #if ENABLED(SDSUPPORT) - StopPrint(); - #endif + TERN_(SDSUPPORT, StopPrint()); break; case 12: // A12 kill @@ -744,7 +696,6 @@ void AnycubicTFTClass::GetCommandFromTFT() { #if ENABLED(SDSUPPORT) if (!ExtUI::isPrinting() && strlen(SelectedFile) > 0) StartPrint(); - #endif break; @@ -767,8 +718,7 @@ void AnycubicTFTClass::GetCommandFromTFT() { } break; - case 17:// A17 set heated bed temp - { + case 17: { // A17 set heated bed temp unsigned int tempbed; if (CodeSeen('S')) { tempbed = constrain(CodeValue(), 0, 100); @@ -777,19 +727,17 @@ void AnycubicTFTClass::GetCommandFromTFT() { } break; - case 18:// A18 set fan speed - { + case 18: { // A18 set fan speed float fanPercent; if (CodeSeen('S')) { fanPercent = CodeValue(); fanPercent = constrain(fanPercent, 0, 100); ExtUI::setTargetFan_percent(fanPercent, ExtUI::FAN0); } - else { + else fanPercent = 100; - } - ExtUI::setTargetFan_percent(fanPercent, ExtUI::FAN0); + ExtUI::setTargetFan_percent(fanPercent, ExtUI::FAN0); SENDLINE_PGM(""); } break; @@ -803,14 +751,11 @@ void AnycubicTFTClass::GetCommandFromTFT() { SENDLINE_PGM(""); break; - case 20: { // A20 read printing speed - int16_t feedrate_percentage = 100; - + case 20: // A20 read printing speed if (CodeSeen('S')) feedrate_percentage = constrain(CodeValue(), 40, 999); else SEND_PGM_VAL("A20V ", feedrate_percentage); - } break; case 21: // A21 all home diff --git a/Marlin/src/lcd/extui/lib/anycubic_i3mega/anycubic_i3mega_lcd.h b/Marlin/src/lcd/extui/lib/anycubic_i3mega/anycubic_i3mega_lcd.h index ee011f1dfe..a4ecf5604f 100644 --- a/Marlin/src/lcd/extui/lib/anycubic_i3mega/anycubic_i3mega_lcd.h +++ b/Marlin/src/lcd/extui/lib/anycubic_i3mega/anycubic_i3mega_lcd.h @@ -23,12 +23,6 @@ #include "../../../../inc/MarlinConfigPre.h" #include "../../../../sd/SdFatConfig.h" // for the FILENAME_LENGTH macro -char *itostr2(const uint8_t &x); -#ifndef ULTRA_LCD - char *itostr3(const int); - char *ftostr32(const float &); -#endif - #define TFTBUFSIZE 4 #define TFT_MAX_CMD_SIZE 96 diff --git a/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp b/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp index b788587c94..8577b76ce6 100644 --- a/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp +++ b/Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.cpp @@ -59,23 +59,13 @@ constexpr uint8_t DGUS_CMD_READVAR = 0x83; bool dguslcd_local_debug; // = false; #endif -#define dgusserial DGUS_SERIAL - void DGUSDisplay::InitDisplay() { - dgusserial.begin(DGUS_BAUDRATE); - - if (true - #if ENABLED(POWER_LOSS_RECOVERY) - && !recovery.valid() - #endif - ) - RequestScreen( - #if ENABLED(SHOW_BOOTSCREEN) - DGUSLCD_SCREEN_BOOT - #else - DGUSLCD_SCREEN_MAIN - #endif - ); + #ifndef LCD_BAUDRATE + #define LCD_BAUDRATE 115200 + #endif + LCD_SERIAL.begin(LCD_BAUDRATE); + if (TERN1(POWER_LOSS_RECOVERY, !recovery.valid())) + RequestScreen(TERN(SHOW_BOOTSCREEN, DGUSLCD_SCREEN_BOOT, DGUSLCD_SCREEN_MAIN)); } void DGUSDisplay::WriteVariable(uint16_t adr, const void* values, uint8_t valueslen, bool isstr) { @@ -89,7 +79,7 @@ void DGUSDisplay::WriteVariable(uint16_t adr, const void* values, uint8_t values strend = true; x = ' '; } - dgusserial.write(x); + LCD_SERIAL.write(x); } } @@ -133,41 +123,41 @@ void DGUSDisplay::WriteVariablePGM(uint16_t adr, const void* values, uint8_t val strend = true; x = ' '; } - dgusserial.write(x); + LCD_SERIAL.write(x); } } void DGUSDisplay::ProcessRx() { - #if ENABLED(DGUS_SERIAL_STATS_RX_BUFFER_OVERRUNS) - if (!dgusserial.available() && dgusserial.buffer_overruns()) { + #if ENABLED(SERIAL_STATS_RX_BUFFER_OVERRUNS) + if (!LCD_SERIAL.available() && LCD_SERIAL.buffer_overruns()) { // Overrun, but reset the flag only when the buffer is empty // We want to extract as many as valid datagrams possible... DEBUG_ECHOPGM("OVFL"); rx_datagram_state = DGUS_IDLE; - //dgusserial.reset_rx_overun(); - dgusserial.flush(); + //LCD_SERIAL.reset_rx_overun(); + LCD_SERIAL.flush(); } #endif uint8_t receivedbyte; - while (dgusserial.available()) { + while (LCD_SERIAL.available()) { switch (rx_datagram_state) { case DGUS_IDLE: // Waiting for the first header byte - receivedbyte = dgusserial.read(); + receivedbyte = LCD_SERIAL.read(); //DEBUG_ECHOPAIR("< ",x); if (DGUS_HEADER1 == receivedbyte) rx_datagram_state = DGUS_HEADER1_SEEN; break; case DGUS_HEADER1_SEEN: // Waiting for the second header byte - receivedbyte = dgusserial.read(); + receivedbyte = LCD_SERIAL.read(); //DEBUG_ECHOPAIR(" ",x); rx_datagram_state = (DGUS_HEADER2 == receivedbyte) ? DGUS_HEADER2_SEEN : DGUS_IDLE; break; case DGUS_HEADER2_SEEN: // Waiting for the length byte - rx_datagram_len = dgusserial.read(); + rx_datagram_len = LCD_SERIAL.read(); DEBUG_ECHOPAIR(" (", rx_datagram_len, ") "); // Telegram min len is 3 (command and one word of payload) @@ -175,10 +165,10 @@ void DGUSDisplay::ProcessRx() { break; case DGUS_WAIT_TELEGRAM: // wait for complete datagram to arrive. - if (dgusserial.available() < rx_datagram_len) return; + if (LCD_SERIAL.available() < rx_datagram_len) return; Initialized = true; // We've talked to it, so we defined it as initialized. - uint8_t command = dgusserial.read(); + uint8_t command = LCD_SERIAL.read(); DEBUG_ECHOPAIR("# ", command); @@ -186,7 +176,7 @@ void DGUSDisplay::ProcessRx() { unsigned char tmp[rx_datagram_len - 1]; unsigned char *ptmp = tmp; while (readlen--) { - receivedbyte = dgusserial.read(); + receivedbyte = LCD_SERIAL.read(); DEBUG_ECHOPAIR(" ", receivedbyte); *ptmp++ = receivedbyte; } @@ -229,19 +219,19 @@ void DGUSDisplay::ProcessRx() { } } -size_t DGUSDisplay::GetFreeTxBuffer() { return DGUS_SERIAL_GET_TX_BUFFER_FREE(); } +size_t DGUSDisplay::GetFreeTxBuffer() { return SERIAL_GET_TX_BUFFER_FREE(); } void DGUSDisplay::WriteHeader(uint16_t adr, uint8_t cmd, uint8_t payloadlen) { - dgusserial.write(DGUS_HEADER1); - dgusserial.write(DGUS_HEADER2); - dgusserial.write(payloadlen + 3); - dgusserial.write(cmd); - dgusserial.write(adr >> 8); - dgusserial.write(adr & 0xFF); + LCD_SERIAL.write(DGUS_HEADER1); + LCD_SERIAL.write(DGUS_HEADER2); + LCD_SERIAL.write(payloadlen + 3); + LCD_SERIAL.write(cmd); + LCD_SERIAL.write(adr >> 8); + LCD_SERIAL.write(adr & 0xFF); } void DGUSDisplay::WritePGM(const char str[], uint8_t len) { - while (len--) dgusserial.write(pgm_read_byte(str++)); + while (len--) LCD_SERIAL.write(pgm_read_byte(str++)); } void DGUSDisplay::loop() { diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp index 0c38c8216c..2c466ffd04 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp @@ -42,7 +42,6 @@ constexpr uint32_t flash_eeprom_version = 1; * 0 16 DATA STORAGE AREA * 16 1 VERSIONING DATA * 17 inf MEDIA STORAGE AREA - * */ #define DATA_STORAGE_SIZE_64K @@ -188,7 +187,7 @@ bool UIFlashStorage::is_present = false; } void UIFlashStorage::initialize() { - for(uint8_t i = 0; i < 10; i++) { + for (uint8_t i = 0; i < 10; i++) { if (check_known_device()) { is_present = true; break; @@ -239,7 +238,7 @@ bool UIFlashStorage::is_present = false; uint16_t stride = 4 + block_size; int32_t read_offset = -1; - for(uint32_t offset = 0; offset < (data_storage_area_size - stride); offset += stride) { + for (uint32_t offset = 0; offset < (data_storage_area_size - stride); offset += stride) { uint32_t delim; spi_read_begin(offset); spi_read_bulk (&delim, sizeof(delim)); @@ -395,9 +394,8 @@ bool UIFlashStorage::is_present = false; uint32_t UIFlashStorage::get_media_file_start(uint8_t slot) { uint32_t addr = media_storage_addr + sizeof(uint32_t) * media_storage_slots; spi_read_begin(media_storage_addr); - for(uint8_t i = 0; i < slot; i++) { + for (uint8_t i = 0; i < slot; i++) addr += spi_read_32(); - } spi_read_end(); return addr; } @@ -442,7 +440,7 @@ bool UIFlashStorage::is_present = false; addr = get_media_file_start(slot); // Write out the file itself - for(;;) { + for (;;) { const int16_t nBytes = reader.read(buff, write_page_size); if (nBytes == -1) { SERIAL_ECHOLNPGM("Failed to read from file"); @@ -450,8 +448,7 @@ bool UIFlashStorage::is_present = false; } addr = write(addr, buff, nBytes); - if (nBytes != write_page_size) - break; + if (nBytes != write_page_size) break; TERN_(EXTENSIBLE_UI, ExtUI::yield()); } diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.h index 1bb35a5995..a9fdb5c5c7 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.h @@ -133,6 +133,7 @@ class CLCD { static void set_brightness (uint8_t brightness); static uint8_t get_brightness(); static void host_cmd (unsigned char host_command, unsigned char byte2); + static uint32_t dl_size() {return CLCD::mem_read_32(REG::CMD_DL) & 0x1FFF;} static void get_font_metrics (uint8_t font, struct FontMetrics &fm); static uint16_t get_text_width(const uint8_t font, const char *str); diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/resolutions.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/resolutions.h index dd4be7a793..2429e30e79 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/resolutions.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/resolutions.h @@ -32,7 +32,6 @@ * Selecting an LCD Display * Version 2.1 * Issue Date: 2017-11-14 - * */ #define COMPUTE_REGS_FROM_DATASHEET \ constexpr uint16_t Hoffset = thfp + thb - 1; \ diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/dl_cache.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/dl_cache.cpp index 728e433154..baed9f8502 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/dl_cache.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/dl_cache.cpp @@ -32,7 +32,8 @@ * * The cache memory begins with a table at * DL_CACHE_START: each table entry contains - * an address and size for a cached DL slot. + * an address, size and used bytes for a cached + * DL slot. * * Immediately following the table is the * DL_FREE_ADDR, which points to free cache @@ -44,11 +45,14 @@ * * DL_CACHE_START slot0_addr 4 * slot0_size 4 + * slot0_used 4 * slot1_addr 4 * slot1_size 4 + * slot1_used 4 * ... * slotN_addr 4 * slotN_size 4 + * slotN_used 4 * DL_FREE_ADDR dl_free_ptr 4 * cached data * ... @@ -57,7 +61,7 @@ */ #define DL_CACHE_START MAP::RAM_G_SIZE - 0xFFFF -#define DL_FREE_ADDR DL_CACHE_START + DL_CACHE_SLOTS * 8 +#define DL_FREE_ADDR DL_CACHE_START + DL_CACHE_SLOTS * 12 using namespace FTDI; @@ -65,13 +69,12 @@ using namespace FTDI; void DLCache::init() { CLCD::mem_write_32(DL_FREE_ADDR, DL_FREE_ADDR + 4); - for(uint8_t slot = 0; slot < DL_CACHE_SLOTS; slot++) { - save_slot(slot, 0, 0); - } + for (uint8_t slot = 0; slot < DL_CACHE_SLOTS; slot++) + save_slot(slot, 0, 0, 0); } bool DLCache::has_data() { - return dl_size != 0; + return dl_slot_size != 0; } bool DLCache::wait_until_idle() { @@ -93,12 +96,12 @@ bool DLCache::wait_until_idle() { * that it can be appended later. The memory is * dynamically allocated following DL_FREE_ADDR. * - * If num_bytes is provided, then that many bytes + * If min_bytes is provided, then that many bytes * will be reserved so that the cache may be re-written * later with potentially a bigger DL. */ -bool DLCache::store(uint32_t num_bytes /* = 0*/) { +bool DLCache::store(uint32_t min_bytes /* = 0*/) { CLCD::CommandFifo cmd; // Execute any commands already in the FIFO @@ -107,67 +110,69 @@ bool DLCache::store(uint32_t num_bytes /* = 0*/) { return false; // Figure out how long the display list is - uint32_t new_dl_size = CLCD::mem_read_32(REG::CMD_DL) & 0x1FFF; - uint32_t free_space = 0; - uint32_t dl_alloc = 0; + const uint32_t dl_size = CLCD::dl_size(); - if (dl_addr == 0) { + if (dl_slot_addr == 0) { // If we are allocating new space... - dl_addr = CLCD::mem_read_32(DL_FREE_ADDR); - free_space = MAP::RAM_G_SIZE - dl_addr; - dl_alloc = num_bytes ?: new_dl_size; - dl_size = new_dl_size; - } else { - // Otherwise, we can only store as much space - // as was previously allocated. - free_space = num_bytes ?: dl_size; - dl_alloc = 0; - dl_size = new_dl_size; + dl_slot_addr = CLCD::mem_read_32(DL_FREE_ADDR); + dl_slot_size = max(dl_size, min_bytes); + + const uint32_t free_space = MAP::RAM_G_SIZE - dl_slot_addr; + if (dl_slot_size <= free_space) { + CLCD::mem_write_32(DL_FREE_ADDR, dl_slot_addr + dl_slot_size); + } + else { + dl_slot_addr = 0; + dl_slot_size = 0; + dl_slot_used = 0; + } } - if (dl_size > free_space) { + if (dl_size > dl_slot_size) { // Not enough memory to cache the display list. #if ENABLED(TOUCH_UI_DEBUG) SERIAL_ECHO_START(); - SERIAL_ECHOPAIR ("Not enough space in GRAM to cache display list, free space: ", free_space); + SERIAL_ECHOPAIR ("Not enough space in GRAM to cache display list, free space: ", dl_slot_size); SERIAL_ECHOLNPAIR(" Required: ", dl_size); #endif + dl_slot_used = 0; + save_slot(); return false; - } else { + } + else { #if ENABLED(TOUCH_UI_DEBUG) SERIAL_ECHO_START(); - SERIAL_ECHOPAIR ("Saving DL to RAMG cache, bytes: ", dl_size); - SERIAL_ECHOLNPAIR(" Free space: ", free_space); + SERIAL_ECHOPAIR ("Saving DL to RAMG cache, bytes: ", dl_slot_used); + SERIAL_ECHOLNPAIR(" Free space: ", dl_slot_size); #endif - cmd.memcpy(dl_addr, MAP::RAM_DL, dl_size); + dl_slot_used = dl_size; + save_slot(); + cmd.memcpy(dl_slot_addr, MAP::RAM_DL, dl_slot_used); cmd.execute(); - save_slot(dl_slot, dl_addr, dl_size); - if (dl_alloc > 0) { - // If we allocated space dynamically, then adjust dl_free_addr. - CLCD::mem_write_32(DL_FREE_ADDR, dl_addr + dl_alloc); - } return true; } } -void DLCache::save_slot(uint8_t dl_slot, uint32_t dl_addr, uint32_t dl_size) { - CLCD::mem_write_32(DL_CACHE_START + dl_slot * 8 + 0, dl_addr); - CLCD::mem_write_32(DL_CACHE_START + dl_slot * 8 + 4, dl_size); +void DLCache::save_slot(uint8_t indx, uint32_t addr, uint16_t size, uint16_t used) { + CLCD::mem_write_32(DL_CACHE_START + indx * 12 + 0, addr); + CLCD::mem_write_32(DL_CACHE_START + indx * 12 + 4, size); + CLCD::mem_write_32(DL_CACHE_START + indx * 12 + 8, used); } -void DLCache::load_slot() { - dl_addr = CLCD::mem_read_32(DL_CACHE_START + dl_slot * 8 + 0); - dl_size = CLCD::mem_read_32(DL_CACHE_START + dl_slot * 8 + 4); +void DLCache::load_slot(uint8_t indx, uint32_t &addr, uint16_t &size, uint16_t &used) { + addr = CLCD::mem_read_32(DL_CACHE_START + indx * 12 + 0); + size = CLCD::mem_read_32(DL_CACHE_START + indx * 12 + 4); + used = CLCD::mem_read_32(DL_CACHE_START + indx * 12 + 8); } void DLCache::append() { CLCD::CommandFifo cmd; - cmd.append(dl_addr, dl_size); + cmd.append(dl_slot_addr, dl_slot_used); #if ENABLED(TOUCH_UI_DEBUG) cmd.execute(); wait_until_idle(); SERIAL_ECHO_START(); - SERIAL_ECHOPAIR ("Appending to DL from RAMG cache, bytes: ", dl_size); + SERIAL_ECHOPAIR ("Appending to DL from RAMG cache, bytes: ", dl_slot_used); SERIAL_ECHOLNPAIR(" REG_CMD_DL: ", CLCD::mem_read_32(REG::CMD_DL)); #endif } diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/dl_cache.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/dl_cache.h index 4ae4bce3ef..da927aeae2 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/dl_cache.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/dl_cache.h @@ -44,12 +44,16 @@ class DLCache { typedef FTDI::ftdi_registers REG; typedef FTDI::ftdi_memory_map MAP; - uint8_t dl_slot; - uint32_t dl_addr; - uint16_t dl_size; + uint8_t dl_slot_indx; + uint32_t dl_slot_addr; + uint16_t dl_slot_size; + uint16_t dl_slot_used; - void load_slot(); - static void save_slot(uint8_t dl_slot, uint32_t dl_addr, uint32_t dl_size); + void load_slot() {load_slot(dl_slot_indx, dl_slot_addr, dl_slot_size, dl_slot_used);} + void save_slot() {save_slot(dl_slot_indx, dl_slot_addr, dl_slot_size, dl_slot_used);} + + static void load_slot(uint8_t indx, uint32_t &addr, uint16_t &size, uint16_t &used); + static void save_slot(uint8_t indx, uint32_t addr, uint16_t size, uint16_t used); bool wait_until_idle(); @@ -57,12 +61,12 @@ class DLCache { static void init(); DLCache(uint8_t slot) { - dl_slot = slot; + dl_slot_indx = slot; load_slot(); } bool has_data(); - bool store(uint32_t num_bytes = 0); + bool store(uint32_t min_bytes = 0); void append(); }; 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 9c5599ebe8..3dd2b88b19 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 @@ -109,7 +109,6 @@ namespace FTDI { * - Handles auto-repetition by sending onTouchHeld to the active screen periodically. * - Plays touch feedback "click" sounds when appropriate. * - Performs debouncing to supress spurious touch events. - * */ void EventLoop::process_events() { // If the LCD is processing commands, don't check diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/ftdi_extended.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/ftdi_extended.h index e1904511b2..6e4d0668fe 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/ftdi_extended.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/ftdi_extended.h @@ -47,4 +47,5 @@ #include "sound_list.h" #include "polygon.h" #include "text_box.h" + #include "text_ellipsis.h" #endif diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/grid_layout.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/grid_layout.h index 1975d36af7..e3c3ebb39d 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/grid_layout.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/grid_layout.h @@ -74,12 +74,12 @@ #define DRAW_LAYOUT_GRID \ { \ cmd.cmd(LINE_WIDTH(4)); \ - for(int i = 1; i <= GRID_COLS; i++) { \ + for (int i = 1; i <= GRID_COLS; i++) { \ cmd.cmd(BEGIN(LINES)); \ cmd.cmd(VERTEX2F(GRID_X(i) *16, 0 *16)); \ cmd.cmd(VERTEX2F(GRID_X(i) *16, FTDI::display_height *16)); \ } \ - for(int i = 1; i < GRID_ROWS; i++) { \ + for (int i = 1; i < GRID_ROWS; i++) { \ cmd.cmd(BEGIN(LINES)); \ cmd.cmd(VERTEX2F(0 *16, GRID_Y(i) *16)); \ cmd.cmd(VERTEX2F(FTDI::display_width *16, GRID_Y(i) *16)); \ diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.cpp index bebee5467d..57a9e3e89b 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.cpp @@ -26,7 +26,7 @@ /********************** VIRTUAL DISPATCH DATA TYPE ******************************/ uint8_t ScreenRef::lookupScreen(onRedraw_func_t onRedraw_ptr) { - for(uint8_t type = 0; type < functionTableSize; type++) { + for (uint8_t type = 0; type < functionTableSize; type++) { if (GET_METHOD(type, onRedraw) == onRedraw_ptr) { return type; } @@ -50,9 +50,8 @@ void ScreenRef::setScreen(onRedraw_func_t onRedraw_ptr) { } void ScreenRef::initializeAll() { - for(uint8_t type = 0; type < functionTableSize; type++) { + for (uint8_t type = 0; type < functionTableSize; type++) GET_METHOD(type, onStartup)(); - } } /********************** SCREEN STACK ******************************/ diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.h index b12ab286e1..d1f84c8a6e 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/screen_types.h @@ -173,10 +173,21 @@ class UncachedScreen { template class CachedScreen { protected: + static void gfxError() { + using namespace FTDI; + CommandProcessor cmd; + cmd.cmd(CMD_DLSTART) + .cmd(CLEAR(true,true,true)) + .font(30) + .text(0, 0, display_width, display_height, F("GFX MEM FULL")); + } + static bool storeBackground() { DLCache dlcache(DL_SLOT); if (!dlcache.store(DL_SIZE)) { SERIAL_ECHO_MSG("CachedScreen::storeBackground() failed: not enough DL cache space"); + gfxError(); // Try to cache a shorter error message instead. + dlcache.store(DL_SIZE); return false; } return true; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp index 9600bd1289..3616f15ab6 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp @@ -34,7 +34,7 @@ namespace FTDI { const char *p = str; end = str; uint16_t lw = 0, result = 0; - for(;;) { + for (;;) { utf8_char_t c = get_utf8_char_and_inc(p); if (c == ' ' || c == '\n' || c == '\0') { if (lw < w || end == str) { @@ -60,7 +60,7 @@ namespace FTDI { const char *line_end; const uint16_t wrap_width = width; width = height = 0; - for(;;) { + for (;;) { uint16_t line_width = find_line_break(fm, wrap_width, line_start, line_end); if (line_end == line_start) break; width = max(width, line_width); @@ -78,7 +78,7 @@ namespace FTDI { FontMetrics fm(font); // Shrink the font until we find a font that fits - for(;;) { + for (;;) { box_width = w; measure_text_box(fm, str, box_width, box_height); if (box_width <= (uint16_t)w && box_height <= (uint16_t)h) break; @@ -91,7 +91,7 @@ namespace FTDI { const char *line_start = str; const char *line_end; - for(;;) { + for (;;) { find_line_break(fm, w, line_start, line_end); if (line_end == line_start) break; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.cpp new file mode 100644 index 0000000000..b2f62f060c --- /dev/null +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.cpp @@ -0,0 +1,80 @@ +/********************* + * text_ellipsis.cpp * + *********************/ + +/**************************************************************************** + * Written By Marcio Teixeira 2019 - Aleph Objects, Inc. * + * * + * This program is free software: you can redistribute it and/or modify * + * it under the terms of the GNU General Public License as published by * + * the Free Software Foundation, either version 3 of the License, or * + * (at your option) any later version. * + * * + * This program is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * + * GNU General Public License for more details. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +#include "ftdi_extended.h" + +#ifdef FTDI_EXTENDED + +namespace FTDI { + + /** + * Helper function for drawing text with ellipses. The str buffer may be modified and should have space for up to two extra characters. + */ + static void _draw_text_with_ellipsis(CommandProcessor& cmd, int16_t x, int16_t y, int16_t w, int16_t h, char *str, uint16_t options, uint8_t font) { + FontMetrics fm(font); + const int16_t ellipsisWidth = fm.get_char_width('.') * 3; + + // Compute the total line length, as well as + // the location in the string where it can + // split and still allow the ellipsis to fit. + int16_t lineWidth = 0; + char *breakPoint = str; + for (char* c = str; *c; c++) { + lineWidth += fm.get_char_width(*c); + if (lineWidth + ellipsisWidth < w) + breakPoint = c; + } + + if (lineWidth > w) { + *breakPoint = '\0'; + strcpy_P(breakPoint,PSTR("...")); + } + + cmd.apply_text_alignment(x, y, w, h, options); + #ifdef TOUCH_UI_USE_UTF8 + if (has_utf8_chars(str)) { + draw_utf8_text(cmd, x, y, str, font_size_t::from_romfont(font), options); + } else + #endif + { + cmd.CLCD::CommandFifo::text(x, y, font, options); + cmd.CLCD::CommandFifo::str(str); + } + } + + /** + * These functions draws text inside a bounding box, truncating the text and + * adding ellipsis if the text does not fit. + */ + void draw_text_with_ellipsis(CommandProcessor& cmd, int x, int y, int w, int h, const char *str, uint16_t options, uint8_t font) { + char tmp[strlen(str) + 3]; + strcpy(tmp, str); + _draw_text_with_ellipsis(cmd, x, y, w, h, tmp, options, font); + } + + void draw_text_with_ellipsis(CommandProcessor& cmd, int x, int y, int w, int h, progmem_str pstr, uint16_t options, uint8_t font) { + char tmp[strlen_P((const char*)pstr) + 3]; + strcpy_P(tmp, (const char*)pstr); + _draw_text_with_ellipsis(cmd, x, y, w, h, tmp, options, font); + } +} // namespace FTDI + +#endif // FTDI_EXTENDED diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.h new file mode 100644 index 0000000000..7852b7ec3e --- /dev/null +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.h @@ -0,0 +1,31 @@ +/******************* + * text_ellipsis.h * + *******************/ + +/**************************************************************************** + * Written By Marcio Teixeira 2020 - SynDaver Labs, Inc. * + * * + * This program is free software: you can redistribute it and/or modify * + * it under the terms of the GNU General Public License as published by * + * the Free Software Foundation, either version 3 of the License, or * + * (at your option) any later version. * + * * + * This program is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * + * GNU General Public License for more details. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +#pragma once + +/** + * This function draws text inside a bounding box, truncating the text and + * showing ellipsis if it does not fit. + */ +namespace FTDI { + void draw_text_with_ellipsis(class CommandProcessor& cmd, int x, int y, int w, int h, progmem_str str, uint16_t options = 0, uint8_t font = 31); + void draw_text_with_ellipsis(class CommandProcessor& cmd, int x, int y, int w, int h, const char *str, uint16_t options = 0, uint8_t font = 31); +} diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extras/poly_ui.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extras/poly_ui.h index 3abc6fca2d..a501de20ba 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extras/poly_ui.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extras/poly_ui.h @@ -16,7 +16,7 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #pragma once @@ -36,7 +36,7 @@ * * PolyReader r(data, N_ELEMENTS(data)); * - * for(r.start();r.has_more(); r.next()) { + * for (r.start();r.has_more(); r.next()) { * uint16_t x = r.x; * uint16_t y = r.y; * @@ -49,7 +49,6 @@ * ... * } * } - * */ class PolyReader { @@ -107,8 +106,8 @@ class PolyReader { } } - bool has_more() {return p != NULL;} - bool end_of_loop() {return start_x == eol;} + bool has_more() { return p != NULL; } + bool end_of_loop() { return start_x == eol; } }; /** @@ -129,7 +128,7 @@ class TransformedPolyReader : public PolyReader { */ static constexpr uint8_t fract_bits = 5; typedef int16_t fix_t; - fix_t makefix(float f) {return f * (1 << fract_bits);} + fix_t makefix(float f) { return f * (1 << fract_bits); } // First two rows of 3x3 transformation matrix fix_t a, b, c; @@ -254,6 +253,13 @@ class GenericPolyUI { draw_mode_t mode; public: + enum ButtonStyle : uint8_t { + FILL = 1, + STROKE = 2, + SHADOW = 4, + REGULAR = 7 + }; + typedef POLY_READER poly_reader_t; GenericPolyUI(CommandProcessor &c, draw_mode_t what = BOTH) : cmd(c), mode(what) {} @@ -276,7 +282,7 @@ class GenericPolyUI { Polygon p(cmd); p.begin_fill(); p.begin_loop(); - for(r.start();r.has_more();r.next()) { + for (r.start();r.has_more();r.next()) { p(r.x * 16, r.y * 16); if (r.end_of_loop()) { p.end_loop(); @@ -306,7 +312,7 @@ class GenericPolyUI { Polygon p(cmd); p.begin_stroke(); p.begin_loop(); - for(r.start();r.has_more(); r.next()) { + for (r.start();r.has_more(); r.next()) { p(r.x * 16, r.y * 16); if (r.end_of_loop()) { p.end_loop(); @@ -323,7 +329,7 @@ class GenericPolyUI { int16_t y_min = INT16_MAX; int16_t x_max = INT16_MIN; int16_t y_max = INT16_MIN; - for(r.start(); r.has_more(); r.next()) { + for (r.start(); r.has_more(); r.next()) { x_min = min(x_min, int16_t(r.x)); x_max = max(x_max, int16_t(r.x)); y_min = min(y_min, int16_t(r.y)); @@ -355,11 +361,11 @@ class GenericPolyUI { btn_shadow_depth = depth; } - void button(const uint8_t tag, poly_reader_t r) { + void button(const uint8_t tag, poly_reader_t r, uint8_t style = REGULAR) { using namespace FTDI; // Draw the shadow #if FTDI_API_LEVEL >= 810 - if (mode & BACKGROUND) { + if (mode & BACKGROUND && style & SHADOW) { cmd.cmd(SAVE_CONTEXT()); cmd.cmd(TAG(tag)); cmd.cmd(VERTEX_TRANSLATE_X(btn_shadow_depth * 16)); @@ -381,11 +387,15 @@ class GenericPolyUI { #endif // Draw the fill and stroke cmd.cmd(TAG(tag)); - cmd.cmd(COLOR_RGB(btn_fill_color)); - fill(r, false); - cmd.cmd(COLOR_RGB(btn_stroke_color)); - cmd.cmd(LINE_WIDTH(btn_stroke_width)); - stroke(r); + if (style & FILL) { + cmd.cmd(COLOR_RGB(btn_fill_color)); + fill(r, false); + } + if (style & STROKE) { + cmd.cmd(COLOR_RGB(btn_stroke_color)); + cmd.cmd(LINE_WIDTH(btn_stroke_width)); + stroke(r); + } cmd.cmd(RESTORE_CONTEXT()); } } diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/language/language_en.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/language/language_en.h index f2971087c1..bd64032729 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/language/language_en.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/language/language_en.h @@ -145,7 +145,9 @@ namespace Language_en { PROGMEM Language_Str MSG_TOUCH_CALIBRATION_PROMPT = u8"Touch the dots to calibrate"; PROGMEM Language_Str MSG_AUTOLEVEL_X_AXIS = u8"Level X Axis"; PROGMEM Language_Str MSG_BED_MAPPING_DONE = u8"Bed mapping finished"; - PROGMEM Language_Str MSG_RESET_BLTOUCH = u8"Reset BLTouch"; + PROGMEM Language_Str MSG_BED_MAPPING_INCOMPLETE = u8"Not all points probed"; + PROGMEM Language_Str MSG_LEVELING = u8"Leveling"; + PROGMEM Language_Str MSG_SHOW_MESH = u8"Show Bed Mesh"; #ifdef TOUCH_UI_LULZBOT_BIO PROGMEM Language_Str MSG_MOVE_TO_HOME = u8"Move to Home"; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/marlin_events.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/marlin_events.cpp index e06f9f3a29..fe68faefee 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/marlin_events.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/marlin_events.cpp @@ -61,7 +61,9 @@ namespace ExtUI { if (AT_SCREEN(StatusScreen) || isPrintingFromMedia()) StatusScreen::setStatusMessage(GET_TEXT_F(MSG_MEDIA_REMOVED)); - if (AT_SCREEN(FilesScreen)) GOTO_SCREEN(StatusScreen) + #if ENABLED(SDSUPPORT) + if (AT_SCREEN(FilesScreen)) GOTO_SCREEN(StatusScreen); + #endif } void onMediaError() { diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp index 35040734b4..67b077a553 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp @@ -55,11 +55,11 @@ void AdvancedSettingsMenu::onRedraw(draw_mode_t what) { #define ACCELERATION_POS BTN_POS(2,5), BTN_SIZE(1,1) #define ENDSTOPS_POS BTN_POS(1,6), BTN_SIZE(1,1) #define JERK_POS BTN_POS(2,6), BTN_SIZE(1,1) - #define OFFSETS_POS BTN_POS(1,7), BTN_SIZE(1,1) + #define CASE_LIGHT_POS BTN_POS(1,7), BTN_SIZE(1,1) #define BACKLASH_POS BTN_POS(2,7), BTN_SIZE(1,1) - #define CASE_LIGHT_POS BTN_POS(1,8), BTN_SIZE(1,1) + #define OFFSETS_POS BTN_POS(1,8), BTN_SIZE(1,1) #define TMC_HOMING_THRS_POS BTN_POS(2,8), BTN_SIZE(1,1) - #if EITHER(CASE_LIGHT_ENABLE, SENSORLESS_HOMING) + #if EITHER(HAS_MULTI_HOTEND, SENSORLESS_HOMING) #define BACK_POS BTN_POS(1,9), BTN_SIZE(2,1) #else #define BACK_POS BTN_POS(1,8), BTN_SIZE(2,1) @@ -98,8 +98,8 @@ void AdvancedSettingsMenu::onRedraw(draw_mode_t what) { .tag(13).button( TMC_CURRENT_POS, GET_TEXT_F(MSG_TMC_CURRENT)) .enabled(ENABLED(SENSORLESS_HOMING)) .tag(14).button( TMC_HOMING_THRS_POS, GET_TEXT_F(MSG_TMC_HOMING_THRS)) - .enabled(EITHER(HAS_MULTI_HOTEND, BLTOUCH)) - .tag(4) .button( OFFSETS_POS, GET_TEXT_F(TERN(HAS_MULTI_HOTEND, MSG_OFFSETS_MENU, MSG_RESET_BLTOUCH))) + .enabled(ENABLED(HAS_MULTI_HOTEND)) + .tag(4) .button( OFFSETS_POS, GET_TEXT_F(MSG_OFFSETS_MENU)) .enabled(EITHER(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR)) .tag(11).button( FILAMENT_POS, GET_TEXT_F(MSG_FILAMENT)) .tag(12).button( ENDSTOPS_POS, GET_TEXT_F(MSG_LCD_ENDSTOPS)) @@ -123,13 +123,9 @@ bool AdvancedSettingsMenu::onTouchEnd(uint8_t tag) { case 2: GOTO_SCREEN(ZOffsetScreen); break; #endif case 3: GOTO_SCREEN(StepsScreen); break; - case 4: - #if HAS_MULTI_HOTEND - GOTO_SCREEN(NozzleOffsetScreen); - #elif ENABLED(BLTOUCH) - injectCommands_P(PSTR("M280 P0 S60")); - #endif - break; + #if ENABLED(HAS_MULTI_HOTEND) + case 4: GOTO_SCREEN(NozzleOffsetScreen); break; + #endif case 5: GOTO_SCREEN(MaxVelocityScreen); break; case 6: GOTO_SCREEN(DefaultAccelerationScreen); break; case 7: GOTO_SCREEN(TERN(HAS_JUNCTION_DEVIATION, JunctionDeviationScreen, JerkScreen)); break; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bed_mesh_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bed_mesh_screen.cpp index 663555f05d..a11609dd97 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bed_mesh_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bed_mesh_screen.cpp @@ -222,7 +222,8 @@ bool BedMeshScreen::tagToPoint(uint8_t tag, uint8_t &x, uint8_t &y) { void BedMeshScreen::onEntry() { screen_data.BedMeshScreen.highlightedTag = 0; - screen_data.BedMeshScreen.count = 0; + screen_data.BedMeshScreen.count = GRID_MAX_POINTS; + screen_data.BedMeshScreen.message = screen_data.BedMeshScreen.MSG_NONE; BaseScreen::onEntry(); } @@ -251,6 +252,12 @@ void BedMeshScreen::drawHighlightedPointValue() { .colors(action_btn) .tag(1).button( OKAY_POS, GET_TEXT_F(MSG_BUTTON_OKAY)) .tag(0); + + switch (screen_data.BedMeshScreen.message) { + case screen_data.BedMeshScreen.MSG_MESH_COMPLETE: cmd.text(MESSAGE_POS, GET_TEXT_F(MSG_BED_MAPPING_DONE)); break; + case screen_data.BedMeshScreen.MSG_MESH_INCOMPLETE: cmd.text(MESSAGE_POS, GET_TEXT_F(MSG_BED_MAPPING_INCOMPLETE)); break; + default: break; + } } void BedMeshScreen::onRedraw(draw_mode_t what) { @@ -270,17 +277,13 @@ void BedMeshScreen::onRedraw(draw_mode_t what) { if (what & FOREGROUND) { constexpr float autoscale_max_amplitude = 0.03; - const bool levelingFinished = screen_data.BedMeshScreen.count >= GRID_MAX_POINTS; - const float levelingProgress = sq(float(screen_data.BedMeshScreen.count) / GRID_MAX_POINTS); - if (levelingFinished) { + const bool gotAllPoints = screen_data.BedMeshScreen.count >= GRID_MAX_POINTS; + if (gotAllPoints) { drawHighlightedPointValue(); - CommandProcessor cmd; - cmd.font(Theme::font_medium) - .text(MESSAGE_POS, GET_TEXT_F(MSG_BED_MAPPING_DONE)); } - + const float levelingProgress = sq(float(screen_data.BedMeshScreen.count) / GRID_MAX_POINTS); BedMeshScreen::drawMesh(INSET_POS(MESH_POS), ExtUI::getMeshArray(), - USE_POINTS | USE_HIGHLIGHT | USE_AUTOSCALE | (levelingFinished ? USE_COLORS : 0), + USE_POINTS | USE_HIGHLIGHT | USE_AUTOSCALE | (gotAllPoints ? USE_COLORS : 0), autoscale_max_amplitude * levelingProgress ); } @@ -306,12 +309,45 @@ void BedMeshScreen::onMeshUpdate(const int8_t, const int8_t, const float) { onRefresh(); } +bool BedMeshScreen::isMeshComplete(ExtUI::bed_mesh_t data) { + for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++) { + for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++) { + if (isnan(data[x][y])) { + return false; + } + } + } + return true; +} + void BedMeshScreen::onMeshUpdate(const int8_t x, const int8_t y, const ExtUI::probe_state_t state) { - if (state == ExtUI::PROBE_FINISH) { - screen_data.BedMeshScreen.highlightedTag = pointToTag(x, y); - screen_data.BedMeshScreen.count++; + switch (state) { + case ExtUI::MESH_START: + screen_data.BedMeshScreen.count = 0; + screen_data.BedMeshScreen.message = screen_data.BedMeshScreen.MSG_NONE; + break; + case ExtUI::MESH_FINISH: + if (screen_data.BedMeshScreen.count == GRID_MAX_POINTS && isMeshComplete(ExtUI::getMeshArray())) { + screen_data.BedMeshScreen.message = screen_data.BedMeshScreen.MSG_MESH_COMPLETE; + } else { + screen_data.BedMeshScreen.message = screen_data.BedMeshScreen.MSG_MESH_INCOMPLETE; + } + screen_data.BedMeshScreen.count = GRID_MAX_POINTS; + break; + case ExtUI::PROBE_START: + screen_data.BedMeshScreen.highlightedTag = pointToTag(x, y); + break; + case ExtUI::PROBE_FINISH: + screen_data.BedMeshScreen.count++; + break; } BedMeshScreen::onMeshUpdate(x, y, 0); } +void BedMeshScreen::startMeshProbe() { + GOTO_SCREEN(BedMeshScreen); + screen_data.BedMeshScreen.count = 0; + injectCommands_P(PSTR(BED_LEVELING_COMMANDS)); +} + #endif // TOUCH_UI_FTDI_EVE && HAS_MESH diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_status_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_status_screen.cpp index 6d72fc92a2..e881995f2e 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_status_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_status_screen.cpp @@ -29,7 +29,9 @@ #include "../ftdi_eve_lib/extras/poly_ui.h" -#ifdef TOUCH_UI_PORTRAIT +#if ENABLED(TOUCH_UI_COCOA_PRESS) + #include "cocoa_press_ui.h" +#elif ENABLED(TOUCH_UI_PORTRAIT) #include "bio_printer_ui_portrait.h" #else #include "bio_printer_ui_landscape.h" @@ -100,7 +102,7 @@ void StatusScreen::draw_temperature(draw_mode_t what) { // heating zones, but has no bed temperature cmd.cmd(COLOR_RGB(bg_text_enabled)); - cmd.font(font_medium); + cmd.font(font_xsmall); ui.bounds(POLY(h0_label), x, y, h, v); cmd.text(x, y, h, v, GET_TEXT_F(MSG_ZONE_1)); @@ -221,7 +223,7 @@ void StatusScreen::draw_syringe(draw_mode_t what) { ui.color(syringe_rgb); ui.fill(POLY(syringe_outline)); - ui.color(fill_rgb); + ui.color(fluid_rgb); ui.bounds(POLY(syringe_fluid), x, y, h, v); cmd.cmd(SAVE_CONTEXT()); cmd.cmd(SCISSOR_XY(x,y + v * (1.0 - fill_level))); @@ -245,23 +247,25 @@ void StatusScreen::draw_arrows(draw_mode_t what) { ui.button_stroke(stroke_rgb, 28); ui.button_shadow(shadow_rgb, shadow_depth); + constexpr uint8_t style = TERN(TOUCH_UI_COCOA_PRESS, PolyUI::FILL | PolyUI::SHADOW, PolyUI::REGULAR); + if ((what & BACKGROUND) || jog_xy) { - ui.button(1, POLY(x_neg)); - ui.button(2, POLY(x_pos)); - ui.button(3, POLY(y_neg)); - ui.button(4, POLY(y_pos)); + ui.button(1, POLY(x_neg), style); + ui.button(2, POLY(x_pos), style); + ui.button(3, POLY(y_neg), style); + ui.button(4, POLY(y_pos), style); } if ((what & BACKGROUND) || z_homed) { - ui.button(5, POLY(z_neg)); - ui.button(6, POLY(z_pos)); + ui.button(5, POLY(z_neg), style); + ui.button(6, POLY(z_pos), style); } if ((what & BACKGROUND) || e_homed) { #if DISABLED(TOUCH_UI_COCOA_PRESS) - ui.button(7, POLY(e_neg)); + ui.button(7, POLY(e_neg), style); #endif - ui.button(8, POLY(e_pos)); + ui.button(8, POLY(e_pos), style); } } @@ -300,13 +304,14 @@ void StatusScreen::draw_overlay_icons(draw_mode_t what) { PolyUI ui(cmd, what); if (what & FOREGROUND) { - ui.button_fill (fill_rgb); + ui.button_fill (TERN(TOUCH_UI_COCOA_PRESS, stroke_rgb, fill_rgb)); ui.button_stroke(stroke_rgb, 28); ui.button_shadow(shadow_rgb, shadow_depth); - if (!jog_xy) ui.button(12, POLY(padlock)); - if (!e_homed) ui.button(13, POLY(home_e)); - if (!z_homed) ui.button(14, POLY(home_z)); + constexpr uint8_t style = TERN(TOUCH_UI_COCOA_PRESS, PolyUI::FILL | PolyUI::SHADOW, PolyUI::REGULAR); + if (!jog_xy) ui.button(12, POLY(padlock), style); + if (!e_homed) ui.button(13, POLY(home_e), style); + if (!z_homed) ui.button(14, POLY(home_z), style); } } diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/boot_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/boot_screen.cpp index 2c2c0c6a18..4ce8f608f1 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/boot_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/boot_screen.cpp @@ -32,7 +32,7 @@ #ifdef SHOW_CUSTOM_BOOTSCREEN #ifdef TOUCH_UI_PORTRAIT - #include "../theme/_bootscreen_portrait.h" + #include "../theme/bootscreen_logo_portrait.h" #else #include "../theme/_bootscreen_landscape.h" #endif diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/endstop_state_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/endstop_state_screen.cpp index 6044d0a951..7f3f507fd6 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/endstop_state_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/endstop_state_screen.cpp @@ -96,7 +96,7 @@ void EndstopStatesScreen::onRedraw(draw_mode_t) { #else PIN_DISABLED(1, 4, GET_TEXT_F(MSG_RUNOUT_1), FIL_RUNOUT) #endif - #if ENABLED(FILAMENT_RUNOUT_SENSOR) && PIN_EXISTS(FIL_RUNOUT2) && EXTRUDERS > 1 + #if BOTH(HAS_MULTI_EXTRUDER, FILAMENT_RUNOUT_SENSOR) && PIN_EXISTS(FIL_RUNOUT2) PIN_ENABLED (3, 4, GET_TEXT_F(MSG_RUNOUT_2), FIL_RUNOUT2, FIL_RUNOUT_STATE) #else PIN_DISABLED(3, 4, GET_TEXT_F(MSG_RUNOUT_2), FIL_RUNOUT2) diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/filament_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/filament_menu.cpp index 575f75a74e..82ee118e4c 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/filament_menu.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/filament_menu.cpp @@ -30,6 +30,22 @@ using namespace FTDI; using namespace ExtUI; using namespace Theme; +#ifdef TOUCH_UI_PORTRAIT + #define GRID_ROWS 9 + #define GRID_COLS 2 + #define TITLE_POS BTN_POS(1,1), BTN_SIZE(2,1) + #define RUNOUT_SENSOR_POS BTN_POS(1,2), BTN_SIZE(2,1) + #define LIN_ADVANCE_POS BTN_POS(1,3), BTN_SIZE(2,1) + #define BACK_POS BTN_POS(1,9), BTN_SIZE(2,1) +#else + #define GRID_ROWS 6 + #define GRID_COLS 2 + #define TITLE_POS BTN_POS(1,1), BTN_SIZE(2,1) + #define RUNOUT_SENSOR_POS BTN_POS(1,2), BTN_SIZE(2,1) + #define LIN_ADVANCE_POS BTN_POS(1,3), BTN_SIZE(2,1) + #define BACK_POS BTN_POS(1,6), BTN_SIZE(2,1) +#endif + void FilamentMenu::onRedraw(draw_mode_t what) { if (what & BACKGROUND) { CommandProcessor cmd; @@ -41,47 +57,14 @@ void FilamentMenu::onRedraw(draw_mode_t what) { if (what & FOREGROUND) { CommandProcessor cmd; cmd.font(font_large) - #ifdef TOUCH_UI_PORTRAIT - #define GRID_ROWS 9 - #define GRID_COLS 2 - .text ( BTN_POS(1,1), BTN_SIZE(2,1), GET_TEXT_F(MSG_FILAMENT)) - .font(font_medium).colors(normal_btn) - .enabled( - #if ENABLED(FILAMENT_RUNOUT_SENSOR) - 1 - #endif - ) - .tag(2).button( BTN_POS(1,2), BTN_SIZE(2,1), GET_TEXT_F(MSG_RUNOUT_SENSOR)) - .enabled( - #if ENABLED(LIN_ADVANCE) - 1 - #endif - ) - .tag(3).button( BTN_POS(1,3), BTN_SIZE(2,1), GET_TEXT_F(MSG_LINEAR_ADVANCE)) - .colors(action_btn) - .tag(1) .button( BTN_POS(1,9), BTN_SIZE(2,1), GET_TEXT_F(MSG_BACK)); - #undef GRID_COLS - #undef GRID_ROWS - #else - #define GRID_ROWS 6 - #define GRID_COLS 3 - .text ( BTN_POS(1,1), BTN_SIZE(3,1), GET_TEXT_F(MSG_FILAMENT)) - .font(font_medium).colors(normal_btn) - .enabled( - #if ENABLED(FILAMENT_RUNOUT_SENSOR) - 1 - #endif - ) - .tag(2).button( BTN_POS(1,2), BTN_SIZE(3,1), GET_TEXT_F(MSG_RUNOUT_SENSOR)) - .enabled( - #if ENABLED(LIN_ADVANCE) - 1 - #endif - ) - .tag(3).button( BTN_POS(1,3), BTN_SIZE(3,1), GET_TEXT_F(MSG_LINEAR_ADVANCE)) - .colors(action_btn) - .tag(1) .button( BTN_POS(1,6), BTN_SIZE(3,1), GET_TEXT_F(MSG_BACK)); - #endif + .text(TITLE_POS, GET_TEXT_F(MSG_FILAMENT)) + .font(font_medium).colors(normal_btn) + .enabled(ENABLED(FILAMENT_RUNOUT_SENSOR)) + .tag(2).button(RUNOUT_SENSOR_POS, GET_TEXT_F(MSG_RUNOUT_SENSOR)) + .enabled(ENABLED(LIN_ADVANCE)) + .tag(3).button(LIN_ADVANCE_POS, GET_TEXT_F(MSG_LINEAR_ADVANCE)) + .colors(action_btn) + .tag(1).button(BACK_POS, GET_TEXT_F(MSG_BACK)); } } diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/files_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/files_screen.cpp index e304302422..f4c224dbe8 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/files_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/files_screen.cpp @@ -22,7 +22,7 @@ #include "../config.h" -#if ENABLED(TOUCH_UI_FTDI_EVE) +#if BOTH(TOUCH_UI_FTDI_EVE, SDSUPPORT) #include "screens.h" #include "screen_data.h" @@ -83,15 +83,19 @@ void FilesScreen::drawFileButton(const char* filename, uint8_t tag, bool is_dir, cmd.font(font_medium) .rectangle( 0, BTN_Y(header_h+line), display_width, BTN_H(1)); cmd.cmd(COLOR_RGB(is_highlighted ? normal_btn.rgb : bg_text_enabled)); + constexpr uint16_t dim[2] = {BTN_SIZE(6,1)}; + #define POS_AND_SHORTEN(SHORTEN) BTN_POS(1,header_h+line), dim[0] - (SHORTEN), dim[1] + #define POS_AND_SIZE POS_AND_SHORTEN(0) #if ENABLED(SCROLL_LONG_FILENAMES) if (is_highlighted) { cmd.cmd(SAVE_CONTEXT()); cmd.cmd(MACRO(0)); - } + cmd.text(POS_AND_SIZE, filename, OPT_CENTERY | OPT_NOFIT); + } else #endif - cmd.text (BTN_POS(1,header_h+line), BTN_SIZE(6,1), filename, OPT_CENTERY | TERN0(SCROLL_LONG_FILENAMES, OPT_NOFIT)); - if (is_dir) { - cmd.text(BTN_POS(1,header_h+line), BTN_SIZE(6,1), F("> "), OPT_CENTERY | OPT_RIGHTX); + draw_text_with_ellipsis(cmd, POS_AND_SHORTEN(is_dir ? 20 : 0), filename, OPT_CENTERY, font_medium); + if (is_dir && !is_highlighted) { + cmd.text(POS_AND_SIZE, F("> "), OPT_CENTERY | OPT_RIGHTX); } #if ENABLED(SCROLL_LONG_FILENAMES) if (is_highlighted) { @@ -102,7 +106,7 @@ void FilesScreen::drawFileButton(const char* filename, uint8_t tag, bool is_dir, void FilesScreen::drawFileList() { FileList files; - screen_data.FilesScreen.num_page = max(1,(ceil)(float(files.count()) / files_per_page)); + screen_data.FilesScreen.num_page = max(1,ceil(float(files.count()) / files_per_page)); screen_data.FilesScreen.cur_page = min(screen_data.FilesScreen.cur_page, screen_data.FilesScreen.num_page-1); screen_data.FilesScreen.flags.is_root = files.isAtRootDir(); @@ -111,7 +115,7 @@ void FilesScreen::drawFileList() { #define MARGIN_T 0 #define MARGIN_B 0 uint16_t fileIndex = screen_data.FilesScreen.cur_page * files_per_page; - for(uint8_t i = 0; i < files_per_page; i++, fileIndex++) { + for (uint8_t i = 0; i < files_per_page; i++, fileIndex++) { if (files.seek(fileIndex)) { drawFileButton(files.filename(), getTagForLine(i), files.isDir(), false); } @@ -134,7 +138,6 @@ void FilesScreen::drawHeader() { sprintf_P(str, PSTR("Page %d of %d"), screen_data.FilesScreen.cur_page + 1, screen_data.FilesScreen.num_page); - CommandProcessor cmd; cmd.colors(normal_btn) .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 def31e4a40..c806ef499b 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 @@ -222,7 +222,7 @@ void InterfaceSettingsScreen::saveSettings(char *buff) { eeprom.touch_transform_f = CLCD::mem_read_32(CLCD::REG::TOUCH_TRANSFORM_F); eeprom.display_h_offset_adj = CLCD::mem_read_16(CLCD::REG::HOFFSET) - FTDI::Hoffset; eeprom.display_v_offset_adj = CLCD::mem_read_16(CLCD::REG::VOFFSET) - FTDI::Voffset; - for(uint8_t i = 0; i < InterfaceSoundsScreen::NUM_EVENTS; i++) + for (uint8_t i = 0; i < InterfaceSoundsScreen::NUM_EVENTS; i++) eeprom.event_sounds[i] = InterfaceSoundsScreen::event_sounds[i]; memcpy(buff, &eeprom, sizeof(eeprom)); @@ -251,7 +251,7 @@ void InterfaceSettingsScreen::loadSettings(const char *buff) { CLCD::mem_write_32(CLCD::REG::TOUCH_TRANSFORM_F, eeprom.touch_transform_f); CLCD::mem_write_16(CLCD::REG::HOFFSET, eeprom.display_h_offset_adj + FTDI::Hoffset); CLCD::mem_write_16(CLCD::REG::VOFFSET, eeprom.display_v_offset_adj + FTDI::Voffset); - for(uint8_t i = 0; i < InterfaceSoundsScreen::NUM_EVENTS; i++) + for (uint8_t i = 0; i < InterfaceSoundsScreen::NUM_EVENTS; i++) InterfaceSoundsScreen::event_sounds[i] = eeprom.event_sounds[i]; TERN_(TOUCH_UI_DEVELOPER_MENU, StressTestScreen::startupCheck()); 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 6c05c3a887..25a44c1adb 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 @@ -43,7 +43,7 @@ void InterfaceSoundsScreen::toggleSoundSelection(event_t event) { } void InterfaceSoundsScreen::setSoundSelection(event_t event, const SoundPlayer::sound_t* sound) { - for(uint8_t i = 0; i < SoundList::n; i++) + for (uint8_t i = 0; i < SoundList::n; i++) if (SoundList::data(i) == sound) event_sounds[event] = i; } diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/leveling_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/leveling_menu.cpp new file mode 100644 index 0000000000..763403d287 --- /dev/null +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/leveling_menu.cpp @@ -0,0 +1,125 @@ +/********************* + * leveling_menu.cpp * + *********************/ + +/**************************************************************************** + * Written By Mark Pelletier 2017 - Aleph Objects, Inc. * + * Written By Marcio Teixeira 2018 - Aleph Objects, Inc. * + * * + * This program is free software: you can redistribute it and/or modify * + * it under the terms of the GNU General Public License as published by * + * the Free Software Foundation, either version 3 of the License, or * + * (at your option) any later version. * + * * + * This program is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * + * GNU General Public License for more details. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +#include "../config.h" + +#if BOTH(TOUCH_UI_FTDI_EVE,HAS_LEVELING) + +#include "screens.h" + +#if BOTH(HAS_BED_PROBE,BLTOUCH) + #include "../../../../../feature/bltouch.h" +#endif + +using namespace FTDI; +using namespace ExtUI; +using namespace Theme; + +#ifdef TOUCH_UI_PORTRAIT + #define GRID_ROWS 10 + #define GRID_COLS 2 + #define TITLE_POS BTN_POS(1,1), BTN_SIZE(2,1) + #define LEVEL_BED_POS BTN_POS(1,2), BTN_SIZE(2,1) + #define LEVEL_AXIS_POS BTN_POS(1,3), BTN_SIZE(2,1) + #define Z_AUTO_ALIGN_POS BTN_POS(1,4), BTN_SIZE(2,1) + #define SHOW_MESH_POS BTN_POS(1,5), BTN_SIZE(2,1) + #define BLTOUCH_TITLE_POS BTN_POS(1,7), BTN_SIZE(2,1) + #define BLTOUCH_RESET_POS BTN_POS(1,8), BTN_SIZE(1,1) + #define BLTOUCH_TEST_POS BTN_POS(2,8), BTN_SIZE(1,1) + #define BACK_POS BTN_POS(1,10), BTN_SIZE(2,1) +#else + #define GRID_ROWS 8 + #define GRID_COLS 2 + #define TITLE_POS BTN_POS(1,1), BTN_SIZE(2,1) + #define LEVEL_BED_POS BTN_POS(1,2), BTN_SIZE(2,1) + #define LEVEL_AXIS_POS BTN_POS(1,3), BTN_SIZE(2,1) + #define Z_AUTO_ALIGN_POS BTN_POS(1,4), BTN_SIZE(2,1) + #define SHOW_MESH_POS BTN_POS(1,5), BTN_SIZE(2,1) + #define BLTOUCH_TITLE_POS BTN_POS(1,6), BTN_SIZE(2,1) + #define BLTOUCH_RESET_POS BTN_POS(1,7), BTN_SIZE(1,1) + #define BLTOUCH_TEST_POS BTN_POS(2,7), BTN_SIZE(1,1) + #define BACK_POS BTN_POS(1,8), BTN_SIZE(2,1) +#endif + +void LevelingMenu::onRedraw(draw_mode_t what) { + if (what & BACKGROUND) { + CommandProcessor cmd; + cmd.cmd(CLEAR_COLOR_RGB(Theme::bg_color)) + .cmd(CLEAR(true,true,true)) + .tag(0); + } + + if (what & FOREGROUND) { + CommandProcessor cmd; + cmd.font(font_large) + .text(TITLE_POS, GET_TEXT_F(MSG_LEVELING)) + .font(font_medium).colors(normal_btn) + .tag(2).button(LEVEL_BED_POS, GET_TEXT_F(MSG_LEVEL_BED)) + .enabled( + #ifdef AXIS_LEVELING_COMMANDS + 1 + #endif + ) + .tag(3).button(LEVEL_AXIS_POS, GET_TEXT_F(MSG_AUTOLEVEL_X_AXIS)) + .enabled(ENABLED(Z_STEPPER_AUTO_ALIGN)) + .tag(4).button(Z_AUTO_ALIGN_POS, GET_TEXT_F(MSG_AUTO_Z_ALIGN)) + .enabled(ENABLED(HAS_MESH)) + .tag(5).button(SHOW_MESH_POS, GET_TEXT_F(MSG_SHOW_MESH)); + #if ENABLED(BLTOUCH) + cmd.text(BLTOUCH_TITLE_POS, GET_TEXT_F(MSG_BLTOUCH)) + .tag(6).button(BLTOUCH_RESET_POS, GET_TEXT_F(MSG_BLTOUCH_RESET)) + .tag(7).button(BLTOUCH_TEST_POS, GET_TEXT_F(MSG_BLTOUCH_SELFTEST)); + #endif + cmd.colors(action_btn) + .tag(1).button(BACK_POS, GET_TEXT_F(MSG_BACK)); + } +} + +bool LevelingMenu::onTouchEnd(uint8_t tag) { + switch (tag) { + case 1: GOTO_PREVIOUS(); break; + case 2: + #if HAS_MESH + BedMeshScreen::startMeshProbe(); + #else + SpinnerDialogBox::enqueueAndWait_P(F(BED_LEVELING_COMMANDS)); + #endif + break; + #ifdef AXIS_LEVELING_COMMANDS + case 3: SpinnerDialogBox::enqueueAndWait_P(F(AXIS_LEVELING_COMMANDS)); break; + #endif + #if ENABLED(Z_STEPPER_AUTO_ALIGN) + case 4: SpinnerDialogBox::enqueueAndWait_P(F("G34")); break; + #endif + #if HAS_MESH + case 5: GOTO_SCREEN(BedMeshScreen); break; + #endif + #if ENABLED(BLTOUCH) + case 6: injectCommands_P(PSTR("M280 P0 S60")); break; + case 7: SpinnerDialogBox::enqueueAndWait_P(F("M280 P0 S90\nG4 P100\nM280 P0 S120")); break; + #endif + default: return false; + } + return true; +} + +#endif // BOTH(TOUCH_UI_FTDI_EVE,HAS_LEVELING) diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/linear_advance_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/linear_advance_screen.cpp index fb90ae1133..8a5c675fac 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/linear_advance_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/linear_advance_screen.cpp @@ -34,7 +34,7 @@ void LinearAdvanceScreen::onRedraw(draw_mode_t what) { widgets_t w(what); w.precision(2, DEFAULT_LOWEST).color(e_axis); w.heading( GET_TEXT_F(MSG_LINEAR_ADVANCE)); - #if EXTRUDERS == 1 + #if !HAS_MULTI_EXTRUDER w.adjuster( 2, GET_TEXT_F(MSG_LINEAR_ADVANCE_K), getLinearAdvance_mm_mm_s(E0) ); #else w.adjuster( 2, GET_TEXT_F(MSG_LINEAR_ADVANCE_K1), getLinearAdvance_mm_mm_s(E0) ); @@ -55,7 +55,7 @@ bool LinearAdvanceScreen::onTouchHeld(uint8_t tag) { switch (tag) { case 2: UI_DECREMENT(LinearAdvance_mm_mm_s, E0); break; case 3: UI_INCREMENT(LinearAdvance_mm_mm_s, E0); break; - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER case 4: UI_DECREMENT(LinearAdvance_mm_mm_s, E1); break; case 5: UI_INCREMENT(LinearAdvance_mm_mm_s, E1); break; #if EXTRUDERS > 2 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 dfb23daa52..53e3ab00c7 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/main_menu.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/main_menu.cpp @@ -44,15 +44,14 @@ void MainMenu::onRedraw(draw_mode_t what) { #define ADVANCED_SETTINGS_POS BTN_POS(1,2), BTN_SIZE(2,1) #define FILAMENTCHANGE_POS BTN_POS(1,3), BTN_SIZE(2,1) #define TEMPERATURE_POS BTN_POS(1,4), BTN_SIZE(2,1) - #define MOVE_AXIS_POS BTN_POS(1,5), BTN_SIZE(1,1) - #define DISABLE_STEPPERS_POS BTN_POS(2,5), BTN_SIZE(1,1) - #define AUTO_HOME_POS BTN_POS(1,6), BTN_SIZE(1,1) - #define CLEAN_NOZZLE_POS BTN_POS(2,6), BTN_SIZE(1,1) - #define LEVEL_BED_POS BTN_POS(1,7), BTN_SIZE(1,1) - #define LEVEL_AXIS_POS BTN_POS(2,7), BTN_SIZE(1,1) + #define DISABLE_STEPPERS_POS BTN_POS(1,5), BTN_SIZE(2,1) + #define MOVE_AXIS_POS BTN_POS(1,6), BTN_SIZE(1,1) + #define LEVELING_POS BTN_POS(2,6), BTN_SIZE(1,1) + #define AUTO_HOME_POS BTN_POS(1,7), BTN_SIZE(1,1) + #define CLEAN_NOZZLE_POS BTN_POS(2,7), BTN_SIZE(1,1) #define BACK_POS BTN_POS(1,8), BTN_SIZE(2,1) #else - #define GRID_ROWS 6 + #define GRID_ROWS 5 #define GRID_COLS 2 #define ADVANCED_SETTINGS_POS BTN_POS(1,1), BTN_SIZE(1,1) #define ABOUT_PRINTER_POS BTN_POS(2,1), BTN_SIZE(1,1) @@ -62,9 +61,8 @@ void MainMenu::onRedraw(draw_mode_t what) { #define DISABLE_STEPPERS_POS BTN_POS(2,3), BTN_SIZE(1,1) #define TEMPERATURE_POS BTN_POS(1,4), BTN_SIZE(1,1) #define FILAMENTCHANGE_POS BTN_POS(2,4), BTN_SIZE(1,1) - #define LEVEL_BED_POS BTN_POS(1,5), BTN_SIZE(1,1) - #define LEVEL_AXIS_POS BTN_POS(2,5), BTN_SIZE(1,1) - #define BACK_POS BTN_POS(1,6), BTN_SIZE(2,1) + #define LEVELING_POS BTN_POS(1,5), BTN_SIZE(1,1) + #define BACK_POS BTN_POS(2,5), BTN_SIZE(1,1) #endif if (what & FOREGROUND) { @@ -100,24 +98,13 @@ void MainMenu::onRedraw(draw_mode_t what) { #endif )) .tag(8).button( ADVANCED_SETTINGS_POS, GET_TEXT_F(MSG_ADVANCED_SETTINGS)) - .enabled( - #ifdef PRINTCOUNTER - 1 - #endif - ) - .enabled( - #ifdef AXIS_LEVELING_COMMANDS - 1 - #endif - ) - .tag(9).button( LEVEL_AXIS_POS, GET_TEXT_F(MSG_AUTOLEVEL_X_AXIS)) .enabled( #ifdef HAS_LEVELING 1 #endif ) - .tag(10).button( LEVEL_BED_POS, GET_TEXT_F(MSG_LEVEL_BED)) - .tag(11).button( ABOUT_PRINTER_POS, GET_TEXT_F(MSG_INFO_MENU)) + .tag(9).button( LEVELING_POS, GET_TEXT_F(MSG_LEVELING)) + .tag(10).button( ABOUT_PRINTER_POS, GET_TEXT_F(MSG_INFO_MENU)) .colors(action_btn) .tag(1).button( BACK_POS, GET_TEXT_F(MSG_BACK)); } @@ -143,23 +130,10 @@ bool MainMenu::onTouchEnd(uint8_t tag) { case 7: GOTO_SCREEN(ChangeFilamentScreen); break; #endif case 8: GOTO_SCREEN(AdvancedSettingsMenu); break; - #ifdef AXIS_LEVELING_COMMANDS - case 9: SpinnerDialogBox::enqueueAndWait_P(F(AXIS_LEVELING_COMMANDS)); break; - #endif - #if HAS_LEVELING - case 10: - #ifndef BED_LEVELING_COMMANDS - #define BED_LEVELING_COMMANDS "G29" - #endif - #if HAS_MESH - GOTO_SCREEN(BedMeshScreen); - injectCommands_P(PSTR(BED_LEVELING_COMMANDS)); - #else - SpinnerDialogBox::enqueueAndWait_P(F(BED_LEVELING_COMMANDS)); - #endif - break; + #ifdef HAS_LEVELING + case 9: GOTO_SCREEN(LevelingMenu); break; #endif - case 11: GOTO_SCREEN(AboutScreen); break; + case 10: GOTO_SCREEN(AboutScreen); break; default: return false; } diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/max_velocity_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/max_velocity_screen.cpp index 95e29c197d..2316f93ee2 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/max_velocity_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/max_velocity_screen.cpp @@ -41,7 +41,7 @@ void MaxVelocityScreen::onRedraw(draw_mode_t what) { w.color(z_axis) .adjuster( 6, GET_TEXT_F(MSG_VMAX_Z), getAxisMaxFeedrate_mm_s(Z) ); #if EXTRUDERS == 1 || DISABLED(DISTINCT_E_FACTORS) w.color(e_axis) .adjuster( 8, GET_TEXT_F(MSG_VMAX_E), getAxisMaxFeedrate_mm_s(E0) ); - #elif EXTRUDERS > 1 + #elif HAS_MULTI_EXTRUDER w.heading(GET_TEXT_F(MSG_VMAX_E)); w.color(e_axis) .adjuster( 8, F(LCD_STR_E0), getAxisMaxFeedrate_mm_s(E0) ); w.color(e_axis) .adjuster( 10, F(LCD_STR_E1), getAxisMaxFeedrate_mm_s(E1) ); diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/move_axis_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/move_axis_screen.cpp index 14ca6fe297..5dd3174821 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/move_axis_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/move_axis_screen.cpp @@ -55,7 +55,7 @@ void MoveAxisScreen::onRedraw(draw_mode_t what) { w.color(Theme::e_axis); #if EXTRUDERS == 1 w.adjuster( 8, GET_TEXT_F(MSG_AXIS_E), screen_data.MoveAxisScreen.e_rel[0], canMove(E0)); - #elif EXTRUDERS > 1 + #elif HAS_MULTI_EXTRUDER w.adjuster( 8, GET_TEXT_F(MSG_AXIS_E1), screen_data.MoveAxisScreen.e_rel[0], canMove(E0)); w.adjuster( 10, GET_TEXT_F(MSG_AXIS_E2), screen_data.MoveAxisScreen.e_rel[1], canMove(E1)); #if EXTRUDERS > 2 @@ -82,7 +82,7 @@ bool MoveAxisScreen::onTouchHeld(uint8_t tag) { // For extruders, also update relative distances. case 8: UI_DECREMENT_AXIS(E0); screen_data.MoveAxisScreen.e_rel[0] -= increment; break; case 9: UI_INCREMENT_AXIS(E0); screen_data.MoveAxisScreen.e_rel[0] += increment; break; - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER case 10: UI_DECREMENT_AXIS(E1); screen_data.MoveAxisScreen.e_rel[1] -= increment; break; case 11: UI_INCREMENT_AXIS(E1); screen_data.MoveAxisScreen.e_rel[1] += increment; break; #endif diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/nudge_nozzle_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/nudge_nozzle_screen.cpp index 091ad8f124..ed3c8d999b 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/nudge_nozzle_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/nudge_nozzle_screen.cpp @@ -33,7 +33,7 @@ using namespace ExtUI; void NudgeNozzleScreen::onEntry() { screen_data.NudgeNozzleScreen.show_offsets = false; - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER screen_data.NudgeNozzleScreen.link_nozzles = true; #endif screen_data.NudgeNozzleScreen.rel.reset(); @@ -52,11 +52,11 @@ void NudgeNozzleScreen::onRedraw(draw_mode_t what) { #endif w.color(z_axis).adjuster(6, GET_TEXT_F(MSG_AXIS_Z), screen_data.NudgeNozzleScreen.rel.z / getAxisSteps_per_mm(Z)); w.increments(); - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER w.toggle(8, GET_TEXT_F(MSG_ADJUST_BOTH_NOZZLES), screen_data.NudgeNozzleScreen.link_nozzles); #endif - #if EXTRUDERS > 1 || HAS_BED_PROBE + #if HAS_MULTI_EXTRUDER || HAS_BED_PROBE w.toggle(9, GET_TEXT_F(MSG_SHOW_OFFSETS), screen_data.NudgeNozzleScreen.show_offsets); if (screen_data.NudgeNozzleScreen.show_offsets) { @@ -82,7 +82,7 @@ void NudgeNozzleScreen::onRedraw(draw_mode_t what) { bool NudgeNozzleScreen::onTouchHeld(uint8_t tag) { const float inc = getIncrement(); - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER const bool link = screen_data.NudgeNozzleScreen.link_nozzles; #else constexpr bool link = true; @@ -95,13 +95,13 @@ bool NudgeNozzleScreen::onTouchHeld(uint8_t tag) { case 5: steps = mmToWholeSteps(inc, Y); smartAdjustAxis_steps( steps, Y, link); screen_data.NudgeNozzleScreen.rel.y += steps; break; case 6: steps = mmToWholeSteps(inc, Z); smartAdjustAxis_steps(-steps, Z, link); screen_data.NudgeNozzleScreen.rel.z -= steps; break; case 7: steps = mmToWholeSteps(inc, Z); smartAdjustAxis_steps( steps, Z, link); screen_data.NudgeNozzleScreen.rel.z += steps; break; - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER case 8: screen_data.NudgeNozzleScreen.link_nozzles = !link; break; #endif case 9: screen_data.NudgeNozzleScreen.show_offsets = !screen_data.NudgeNozzleScreen.show_offsets; break; default: return false; } - #if EXTRUDERS > 1 || HAS_BED_PROBE + #if HAS_MULTI_EXTRUDER || HAS_BED_PROBE SaveSettingsDialogBox::settingsChanged(); #endif return true; 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 207277b824..dc38890a0e 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screen_data.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screen_data.h @@ -52,41 +52,46 @@ union screen_data_t { uint8_t num_page; uint8_t cur_page; #if ENABLED(SCROLL_LONG_FILENAMES) && (FTDI_API_LEVEL >= 810) - uint16_t scroll_pos; - uint16_t scroll_max; + uint16_t scroll_pos; + uint16_t scroll_max; #endif } FilesScreen; struct { struct base_numeric_adjustment_t placeholder; float e_rel[ExtUI::extruderCount]; } MoveAxisScreen; -#if HAS_MESH - struct { - uint8_t count; - uint8_t highlightedTag; - } BedMeshScreen; -#endif -#if ENABLED(TOUCH_UI_DEVELOPER_MENU) - struct { - uint32_t next_watchdog_trigger; - const char* message; - } StressTestScreen; -#endif -#if ENABLED(TOUCH_UI_COCOA_PRESS) - struct { - uint32_t start_ms; - } PreheatTimerScreen; -#endif -#if ENABLED(BABYSTEPPING) - struct { - struct base_numeric_adjustment_t placeholder; - xyz_int_t rel; - #if EXTRUDERS > 1 - bool link_nozzles; - #endif - bool show_offsets; - } NudgeNozzleScreen; -#endif + #if HAS_MESH + struct { + enum : uint8_t { + MSG_NONE, + MSG_MESH_COMPLETE, + MSG_MESH_INCOMPLETE + } message; + uint8_t count; + uint8_t highlightedTag; + } BedMeshScreen; + #endif + #if ENABLED(TOUCH_UI_DEVELOPER_MENU) + struct { + uint32_t next_watchdog_trigger; + const char* message; + } StressTestScreen; + #endif + #if ENABLED(TOUCH_UI_COCOA_PRESS) + struct { + uint32_t start_ms; + } PreheatTimerScreen; + #endif + #if ENABLED(BABYSTEPPING) + struct { + struct base_numeric_adjustment_t placeholder; + xyz_int_t rel; + #if HAS_MULTI_EXTRUDER + bool link_nozzles; + #endif + bool show_offsets; + } NudgeNozzleScreen; + #endif }; extern screen_data_t screen_data; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.cpp index 01438aeb94..16aa682168 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.cpp @@ -55,9 +55,6 @@ SCREEN_TABLE { #endif #if ENABLED(BABYSTEPPING) DECL_SCREEN(NudgeNozzleScreen), -#endif -#if HAS_MESH - DECL_SCREEN(BedMeshScreen), #endif DECL_SCREEN(MoveAxisScreen), DECL_SCREEN(StepsScreen), @@ -65,8 +62,14 @@ SCREEN_TABLE { DECL_SCREEN(StepperCurrentScreen), DECL_SCREEN(StepperBumpSensitivityScreen), #endif -#if HAS_BED_PROBE - DECL_SCREEN(ZOffsetScreen), +#if HAS_LEVELING + DECL_SCREEN(LevelingMenu), + #if HAS_BED_PROBE + DECL_SCREEN(ZOffsetScreen), + #endif + #if HAS_MESH + DECL_SCREEN(BedMeshScreen), + #endif #endif #if HAS_MULTI_HOTEND DECL_SCREEN(NozzleOffsetScreen), @@ -100,7 +103,9 @@ SCREEN_TABLE { DECL_SCREEN(InterfaceSettingsScreen), DECL_SCREEN(InterfaceSoundsScreen), DECL_SCREEN(LockScreen), +#if ENABLED(SDSUPPORT) DECL_SCREEN(FilesScreen), +#endif DECL_SCREEN(EndstopStatesScreen), #if ENABLED(TOUCH_UI_LULZBOT_BIO) DECL_SCREEN(BioPrintingDialogBox), diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h index 92e6b230f7..2108cff8df 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h @@ -27,6 +27,10 @@ #include "../theme/theme.h" #include "string_format.h" +#ifndef BED_LEVELING_COMMANDS + #define BED_LEVELING_COMMANDS "G29" +#endif + extern tiny_timer_t refresh_timer; /********************************* DL CACHE SLOTS ******************************/ @@ -39,24 +43,37 @@ enum { STATUS_SCREEN_CACHE, MENU_SCREEN_CACHE, TUNE_SCREEN_CACHE, - ADJUST_OFFSETS_SCREEN_CACHE, ALERT_BOX_CACHE, SPINNER_CACHE, ADVANCED_SETTINGS_SCREEN_CACHE, MOVE_AXIS_SCREEN_CACHE, TEMPERATURE_SCREEN_CACHE, STEPS_SCREEN_CACHE, - STEPPER_CURRENT_SCREEN_CACHE, - STEPPER_BUMP_SENSITIVITY_SCREEN_CACHE, - ZOFFSET_SCREEN_CACHE, - NOZZLE_OFFSET_SCREEN_CACHE, - BACKLASH_COMPENSATION_SCREEN_CACHE, MAX_FEEDRATE_SCREEN_CACHE, MAX_VELOCITY_SCREEN_CACHE, MAX_ACCELERATION_SCREEN_CACHE, DEFAULT_ACCELERATION_SCREEN_CACHE, -#if HAS_MESH - BED_MESH_SCREEN_CACHE, +#if HAS_LEVELING + LEVELING_SCREEN_CACHE, + #if HAS_BED_PROBE + ZOFFSET_SCREEN_CACHE, + #endif + #if HAS_MESH + BED_MESH_SCREEN_CACHE, + #endif +#endif +#if ENABLED(BABYSTEPPING) + ADJUST_OFFSETS_SCREEN_CACHE, +#endif +#if HAS_TRINAMIC_CONFIG + STEPPER_CURRENT_SCREEN_CACHE, + STEPPER_BUMP_SENSITIVITY_SCREEN_CACHE, +#endif +#if HAS_MULTI_HOTEND + NOZZLE_OFFSET_SCREEN_CACHE, +#endif +#if ENABLED(BACKLASH_GCODE) + BACKLASH_COMPENSATION_SCREEN_CACHE, #endif #if HAS_JUNCTION_DEVIATION JUNC_DEV_SCREEN_CACHE, @@ -81,12 +98,14 @@ enum { #if ENABLED(TOUCH_UI_COCOA_PRESS) PREHEAT_MENU_CACHE, PREHEAT_TIMER_SCREEN_CACHE, +#endif +#if ENABLED(SDSUPPORT) + FILES_SCREEN_CACHE, #endif CHANGE_FILAMENT_SCREEN_CACHE, INTERFACE_SETTINGS_SCREEN_CACHE, INTERFACE_SOUNDS_SCREEN_CACHE, LOCK_SCREEN_CACHE, - FILES_SCREEN_CACHE, DISPLAY_TIMINGS_SCREEN_CACHE }; @@ -96,7 +115,7 @@ enum { #define STATUS_SCREEN_DL_SIZE 2048 #define ALERT_BOX_DL_SIZE 3072 #define SPINNER_DL_SIZE 3072 -#define FILE_SCREEN_DL_SIZE 3072 +#define FILE_SCREEN_DL_SIZE 4160 #define PRINTING_SCREEN_DL_SIZE 2048 /************************* MENU SCREEN DECLARATIONS *************************/ @@ -133,33 +152,6 @@ class AboutScreen : public BaseScreen, public UncachedScreen { static bool onTouchEnd(uint8_t tag); }; -#if HAS_MESH -class BedMeshScreen : public BaseScreen, public CachedScreen { - private: - enum MeshOpts { - USE_POINTS = 0x01, - USE_COLORS = 0x02, - USE_TAGS = 0x04, - USE_HIGHLIGHT = 0x08, - USE_AUTOSCALE = 0x10 - }; - - static uint8_t pointToTag(uint8_t x, uint8_t y); - static bool tagToPoint(uint8_t tag, uint8_t &x, uint8_t &y); - static float getHightlightedValue(); - static void drawHighlightedPointValue(); - static void drawMesh(int16_t x, int16_t y, int16_t w, int16_t h, ExtUI::bed_mesh_t data, uint8_t opts, float autoscale_max = 0.1); - - public: - static void onMeshUpdate(const int8_t x, const int8_t y, const float val); - static void onMeshUpdate(const int8_t x, const int8_t y, const ExtUI::probe_state_t); - static void onEntry(); - static void onRedraw(draw_mode_t); - static bool onTouchStart(uint8_t tag); - static bool onTouchEnd(uint8_t tag); -}; -#endif - #if ENABLED(PRINTCOUNTER) class StatisticsScreen : public BaseScreen, public UncachedScreen { public: @@ -505,21 +497,59 @@ class StepsScreen : public BaseNumericAdjustmentScreen, public CachedScreen { +#if HAS_MULTI_HOTEND + class NozzleOffsetScreen : public BaseNumericAdjustmentScreen, public CachedScreen { public: + static void onEntry(); static void onRedraw(draw_mode_t); static bool onTouchHeld(uint8_t tag); }; #endif -#if HAS_MULTI_HOTEND - class NozzleOffsetScreen : public BaseNumericAdjustmentScreen, public CachedScreen { +#if HAS_LEVELING + class LevelingMenu : public BaseScreen, public CachedScreen { public: + static void onRedraw(draw_mode_t); + static bool onTouchEnd(uint8_t tag); + }; + + #if HAS_BED_PROBE + class ZOffsetScreen : public BaseNumericAdjustmentScreen, public CachedScreen { + public: + static void onRedraw(draw_mode_t); + static bool onTouchHeld(uint8_t tag); + }; + #endif + + #if HAS_MESH + class BedMeshScreen : public BaseScreen, public CachedScreen { + private: + enum MeshOpts { + USE_POINTS = 0x01, + USE_COLORS = 0x02, + USE_TAGS = 0x04, + USE_HIGHLIGHT = 0x08, + USE_AUTOSCALE = 0x10 + }; + + static uint8_t pointToTag(uint8_t x, uint8_t y); + static bool tagToPoint(uint8_t tag, uint8_t &x, uint8_t &y); + static float getHightlightedValue(); + static void drawHighlightedPointValue(); + static void drawMesh(int16_t x, int16_t y, int16_t w, int16_t h, ExtUI::bed_mesh_t data, uint8_t opts, float autoscale_max = 0.1); + static bool isMeshComplete(ExtUI::bed_mesh_t data); + + public: + static void onMeshUpdate(const int8_t x, const int8_t y, const float val); + static void onMeshUpdate(const int8_t x, const int8_t y, const ExtUI::probe_state_t); static void onEntry(); static void onRedraw(draw_mode_t); - static bool onTouchHeld(uint8_t tag); + static bool onTouchStart(uint8_t tag); + static bool onTouchEnd(uint8_t tag); + + static void startMeshProbe(); }; + #endif #endif #if ENABLED(BABYSTEPPING) @@ -707,40 +737,42 @@ class LockScreen : public BaseScreen, public CachedScreen { static bool onTouchEnd(uint8_t tag); }; -class FilesScreen : public BaseScreen, public CachedScreen { - private: - #ifdef TOUCH_UI_PORTRAIT - static constexpr uint8_t header_h = 2; - static constexpr uint8_t footer_h = 2; - static constexpr uint8_t files_per_page = 11; - #else - static constexpr uint8_t header_h = 1; - static constexpr uint8_t footer_h = 1; - static constexpr uint8_t files_per_page = 6; - #endif - - static uint8_t getTagForLine(uint8_t line) {return line + 2;} - static uint8_t getLineForTag(uint8_t tag) {return tag - 2;} - static uint16_t getFileForTag(uint8_t tag); - static uint16_t getSelectedFileIndex(); - - inline static const char *getSelectedShortFilename() {return getSelectedFilename(false);} - inline static const char *getSelectedLongFilename() {return getSelectedFilename(true);} - static const char *getSelectedFilename(bool longName); - - static void drawFileButton(const char* filename, uint8_t tag, bool is_dir, bool is_highlighted); - static void drawFileList(); - static void drawHeader(); - static void drawFooter(); - static void drawSelectedFile(); - - static void gotoPage(uint8_t); - public: - static void onEntry(); - static void onRedraw(draw_mode_t); - static bool onTouchEnd(uint8_t tag); - static void onIdle(); -}; +#if ENABLED(SDSUPPORT) + class FilesScreen : public BaseScreen, public CachedScreen { + private: + #ifdef TOUCH_UI_PORTRAIT + static constexpr uint8_t header_h = 2; + static constexpr uint8_t footer_h = 2; + static constexpr uint8_t files_per_page = 11; + #else + static constexpr uint8_t header_h = 1; + static constexpr uint8_t footer_h = 1; + static constexpr uint8_t files_per_page = 6; + #endif + + static uint8_t getTagForLine(uint8_t line) {return line + 2;} + static uint8_t getLineForTag(uint8_t tag) {return tag - 2;} + static uint16_t getFileForTag(uint8_t tag); + static uint16_t getSelectedFileIndex(); + + inline static const char *getSelectedShortFilename() {return getSelectedFilename(false);} + inline static const char *getSelectedLongFilename() {return getSelectedFilename(true);} + static const char *getSelectedFilename(bool longName); + + static void drawFileButton(const char* filename, uint8_t tag, bool is_dir, bool is_highlighted); + static void drawFileList(); + static void drawHeader(); + static void drawFooter(); + static void drawSelectedFile(); + + static void gotoPage(uint8_t); + public: + static void onEntry(); + static void onRedraw(draw_mode_t); + static bool onTouchEnd(uint8_t tag); + static void onIdle(); + }; +#endif class EndstopStatesScreen : public BaseScreen, public UncachedScreen { public: diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/status_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/status_screen.cpp index f2524c7982..fc7453fca7 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 @@ -176,11 +176,7 @@ void StatusScreen::draw_temperature(draw_mode_t what) { char bed_str[20]; char fan_str[20]; - sprintf_P( - fan_str, - PSTR("%-3d %%"), - int8_t(getActualFan_percent(FAN0)) - ); + sprintf_P(fan_str, PSTR("%-3d %%"), int8_t(getActualFan_percent(FAN0))); if (isHeaterIdle(BED)) format_temp_and_idle(bed_str, getActualTemp_celsius(BED)); @@ -193,16 +189,13 @@ void StatusScreen::draw_temperature(draw_mode_t what) { format_temp_and_temp(e0_str, getActualTemp_celsius(H0), getTargetTemp_celsius(H0)); - #if EXTRUDERS == 2 + #if HAS_MULTI_EXTRUDER if (isHeaterIdle(H1)) format_temp_and_idle(e1_str, getActualTemp_celsius(H1)); else format_temp_and_temp(e1_str, getActualTemp_celsius(H1), getTargetTemp_celsius(H1)); #else - strcpy_P( - e1_str, - PSTR("-") - ); + strcpy_P(e1_str, PSTR("-")); #endif cmd.tag(5) @@ -376,7 +369,9 @@ bool StatusScreen::onTouchEnd(uint8_t tag) { using namespace ExtUI; switch (tag) { - case 3: GOTO_SCREEN(FilesScreen); break; + #if ENABLED(SDSUPPORT) + case 3: GOTO_SCREEN(FilesScreen); break; + #endif case 4: if (isPrinting()) { GOTO_SCREEN(TuneMenu); diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/stepper_current_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/stepper_current_screen.cpp index a8e948a9c3..e89bbd2020 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/stepper_current_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/stepper_current_screen.cpp @@ -40,7 +40,7 @@ void StepperCurrentScreen::onRedraw(draw_mode_t what) { w.color(z_axis) .adjuster( 6, GET_TEXT_F(MSG_AXIS_Z), getAxisCurrent_mA(Z) ); #if EXTRUDERS == 1 w.color(e_axis).adjuster( 8, GET_TEXT_F(MSG_AXIS_E), getAxisCurrent_mA(E0) ); - #elif EXTRUDERS > 1 + #elif HAS_MULTI_EXTRUDER w.color(e_axis).adjuster( 8, GET_TEXT_F(MSG_AXIS_E1), getAxisCurrent_mA(E0) ); w.color(e_axis).adjuster(10, GET_TEXT_F(MSG_AXIS_E2), getAxisCurrent_mA(E1) ); #if EXTRUDERS > 2 @@ -64,7 +64,7 @@ bool StepperCurrentScreen::onTouchHeld(uint8_t tag) { case 7: UI_INCREMENT(AxisCurrent_mA, Z ); break; case 8: UI_DECREMENT(AxisCurrent_mA, E0); break; case 9: UI_INCREMENT(AxisCurrent_mA, E0); break; - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER case 10: UI_DECREMENT(AxisCurrent_mA, E1); break; case 11: UI_INCREMENT(AxisCurrent_mA, E1); break; #endif diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/steps_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/steps_screen.cpp index f3957c0173..92035d1b1c 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/steps_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/steps_screen.cpp @@ -40,7 +40,7 @@ void StepsScreen::onRedraw(draw_mode_t what) { w.color(z_axis) .adjuster( 6, GET_TEXT_F(MSG_AXIS_Z), getAxisSteps_per_mm(Z) ); #if EXTRUDERS == 1 || DISABLED(DISTINCT_E_FACTORS) w.color(e_axis) .adjuster( 8, GET_TEXT_F(MSG_AXIS_E), getAxisSteps_per_mm(E0) ); - #elif EXTRUDERS > 1 + #elif HAS_MULTI_EXTRUDER w.color(e_axis) .adjuster( 8, GET_TEXT_F(MSG_AXIS_E1), getAxisSteps_per_mm(E0) ); w.color(e_axis) .adjuster(10, GET_TEXT_F(MSG_AXIS_E2), getAxisSteps_per_mm(E1) ); #if EXTRUDERS > 2 @@ -64,7 +64,7 @@ bool StepsScreen::onTouchHeld(uint8_t tag) { case 7: UI_INCREMENT(AxisSteps_per_mm, Z); break; case 8: UI_DECREMENT(AxisSteps_per_mm, E0); break; case 9: UI_INCREMENT(AxisSteps_per_mm, E0); break; - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER case 10: UI_DECREMENT(AxisSteps_per_mm, E1); break; case 11: UI_INCREMENT(AxisSteps_per_mm, E1); break; #endif diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/stress_test_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/stress_test_screen.cpp index 321c608abd..44ee453f15 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/stress_test_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/stress_test_screen.cpp @@ -38,7 +38,7 @@ using namespace ExtUI; void StressTestScreen::drawDots(uint16_t x, uint16_t y, uint16_t w, uint16_t h) { CommandProcessor cmd; - for(uint8_t i = 0; i < 100; i++) { + for (uint8_t i = 0; i < 100; i++) { cmd.cmd(BEGIN(POINTS)) .cmd(POINT_SIZE(20*16)) .cmd(COLOR_RGB(random(0xFFFFFF))) @@ -111,7 +111,7 @@ void StressTestScreen::recursiveLockup() { void StressTestScreen::iterativeLockup() { screen_data.StressTestScreen.message = PSTR("Test 3: Printer will restart."); - for(;;) current_screen.onRefresh(); + for (;;) current_screen.onRefresh(); } void StressTestScreen::onIdle() { @@ -127,9 +127,7 @@ void StressTestScreen::onIdle() { injectCommands_P(PSTR( "G0 X100 Y100 Z100 F6000\n" "T0\nG4 S1" - #if EXTRUDERS > 1 - "\nT1\nG4 S1" - #endif + TERN_(HAS_MULTI_EXTRUDER, "\nT1\nG4 S1") "\nG0 X150 Y150 Z150" )); } diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/tune_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/tune_menu.cpp index 4e3fb7d17e..9fe2f1e9cb 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/tune_menu.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/tune_menu.cpp @@ -37,7 +37,7 @@ void TuneMenu::onRedraw(draw_mode_t what) { } #ifdef TOUCH_UI_PORTRAIT - #define GRID_ROWS 8 + #define GRID_ROWS 9 #define GRID_COLS 2 #define TEMPERATURE_POS BTN_POS(1,1), BTN_SIZE(2,1) #define FIL_CHANGE_POS BTN_POS(1,2), BTN_SIZE(2,1) @@ -46,9 +46,10 @@ void TuneMenu::onRedraw(draw_mode_t what) { #define SPEED_POS BTN_POS(1,5), BTN_SIZE(2,1) #define PAUSE_POS BTN_POS(1,6), BTN_SIZE(2,1) #define STOP_POS BTN_POS(1,7), BTN_SIZE(2,1) - #define BACK_POS BTN_POS(1,8), BTN_SIZE(2,1) + #define CASE_LIGHT_POS BTN_POS(1,8), BTN_SIZE(2,1) + #define BACK_POS BTN_POS(1,9), BTN_SIZE(2,1) #else - #define GRID_ROWS 4 + #define GRID_ROWS 5 #define GRID_COLS 2 #define TEMPERATURE_POS BTN_POS(1,1), BTN_SIZE(1,1) #define NUDGE_NOZ_POS BTN_POS(2,1), BTN_SIZE(1,1) @@ -57,7 +58,8 @@ void TuneMenu::onRedraw(draw_mode_t what) { #define PAUSE_POS BTN_POS(1,3), BTN_SIZE(1,1) #define STOP_POS BTN_POS(2,3), BTN_SIZE(1,1) #define FILAMENT_POS BTN_POS(1,4), BTN_SIZE(1,1) - #define BACK_POS BTN_POS(2,4), BTN_SIZE(1,1) + #define CASE_LIGHT_POS BTN_POS(2,4), BTN_SIZE(1,1) + #define BACK_POS BTN_POS(1,5), BTN_SIZE(2,1) #endif if (what & FOREGROUND) { @@ -79,6 +81,8 @@ void TuneMenu::onRedraw(draw_mode_t what) { .button( PAUSE_POS, isPrintingFromMediaPaused() ? GET_TEXT_F(MSG_RESUME_PRINT) : GET_TEXT_F(MSG_PAUSE_PRINT)) .enabled(TERN0(SDSUPPORT, isPrintingFromMedia())) .tag(8).button( STOP_POS, GET_TEXT_F(MSG_STOP_PRINT)) + .enabled(ENABLED(CASE_LIGHT_ENABLE)) + .tag(10).button( CASE_LIGHT_POS, GET_TEXT_F(MSG_CASE_LIGHT)) .tag(1).colors(action_btn) .button( BACK_POS, GET_TEXT_F(MSG_BACK)); } @@ -111,6 +115,9 @@ bool TuneMenu::onTouchEnd(uint8_t tag) { #if EITHER(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR) case 9: GOTO_SCREEN(FilamentMenu); break; #endif + #if ENABLED(CASE_LIGHT_ENABLE) + case 10: GOTO_SCREEN(CaseLightScreen); break; + #endif default: return false; } diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/bootscreen_logo_portrait.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/bootscreen_logo_portrait.h new file mode 100644 index 0000000000..6ea317dbc3 --- /dev/null +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/bootscreen_logo_portrait.h @@ -0,0 +1,42 @@ +/**************************************************************************** + * This program is free software: you can redistribute it and/or modify * + * it under the terms of the GNU General Public License as published by * + * the Free Software Foundation, either version 3 of the License, or * + * (at your option) any later version. * + * * + * This program is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * + * GNU General Public License for more details. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +/** + * This file was auto-generated using "svg2cpp.pl" + * + * The encoding consists of x,y pairs with the min and max scaled to + * 0x0000 and 0xFFFE. A single 0xFFFF in the data stream indicates the + * start of a new closed path. + */ + +#pragma once + +constexpr float x_min = 0.000000, x_max = 272.000000, + y_min = 0.000000, y_max = 480.000000; + +const PROGMEM uint16_t logo_green[] = {0x8048, 0x46D9, 0x27BC, 0x9DBA, 0xD8D3, 0x9DBA}; +const PROGMEM uint16_t logo_mark[] = {0xDB9F, 0xAC0C, 0xDA6F, 0xAC2D, 0xD970, 0xAC91, 0xD8C0, 0xAD23, 0xD885, 0xADCF, 0xD8C0, 0xAE7A, 0xD970, 0xAF0C, 0xDA6F, 0xAF6F, 0xDB9F, 0xAF8F, 0xDCCE, 0xAF6F, 0xDDD0, 0xAF0C, 0xDE7D, 0xAE7B, 0xDEB9, 0xADCF, 0xDE7D, 0xAD22, 0xDDD0, 0xAC91, 0xDCCE, 0xAC2D, 0xFFFF, 0xDB9F, 0xABC3, 0xDCFE, 0xABEA, 0xDE28, 0xAC5E, 0xDEF1, 0xAD06, 0xDF36, 0xADCF, 0xDEF1, 0xAE95, 0xDE28, 0xAF3E, 0xDCFE, 0xAFB1, 0xDB9F, 0xAFD8, 0xDA3F, 0xAFB1, 0xD916, 0xAF3E, 0xD849, 0xAE95, 0xD808, 0xADCF, 0xD849, 0xAD06, 0xD916, 0xAC5E, 0xDA3F, 0xABEA, 0xFFFF, 0xDB7D, 0xACE6, 0xDAE4, 0xACE6, 0xDAE4, 0xADA9, 0xDB7D, 0xADA9, 0xDC3B, 0xAD94, 0xDC71, 0xAD48, 0xDC3B, 0xACFD, 0xFFFF, 0xDB85, 0xAC9E, 0xDCCB, 0xACC8, 0xDD37, 0xAD47, 0xDCF6, 0xADAC, 0xDC3E, 0xADDE, 0xDC85, 0xADFF, 0xDCE8, 0xAE4E, 0xDD92, 0xAEEA, 0xDCBD, 0xAEEA, 0xDC1E, 0xAE58, 0xDBA7, 0xAE03, 0xDB36, 0xADEF, 0xDAE4, 0xADEF, 0xDAE4, 0xAEEA, 0xDA26, 0xAEEA, 0xDA26, 0xAC9E}; +const PROGMEM uint16_t logo_type[] = {0xD8D5, 0xA520, 0xD8A5, 0xA563, 0xD82E, 0xA57F, 0xD348, 0xA57F, 0xD2D1, 0xA598, 0xD2A0, 0xA5D9, 0xD2A0, 0xAF7A, 0xD274, 0xAFBE, 0xD202, 0xAFDA, 0xCD37, 0xAFDA, 0xCCBF, 0xAFBE, 0xCC8F, 0xAF7A, 0xCC8F, 0xA5D9, 0xCC63, 0xA598, 0xCBF1, 0xA57F, 0xC70B, 0xA57F, 0xC694, 0xA563, 0xC664, 0xA520, 0xC664, 0xA28C, 0xC70B, 0xA22C, 0xD82E, 0xA22C, 0xD8A5, 0xA248, 0xD8D5, 0xA28C, 0xFFFF, 0xB138, 0xAC8C, 0xB952, 0xAC8C, 0xB952, 0xA57F, 0xB138, 0xA57F, 0xFFFF, 0xBF27, 0xA421, 0xBF57, 0xA476, 0xBF6D, 0xA4D0, 0xBF6D, 0xAD36, 0xBF57, 0xAD90, 0xBF27, 0xADE6, 0xBBFA, 0xAFB2, 0xBB60, 0xAFCF, 0xBABD, 0xAFDA, 0xAFCE, 0xAFDA, 0xAF30, 0xAFCF, 0xAE9A, 0xAFB2, 0xAB6E, 0xADE6, 0xAB39, 0xAD90, 0xAB28, 0xAD36, 0xAB28, 0xA4D0, 0xAB39, 0xA476, 0xAB6E, 0xA421, 0xAE9A, 0xA255, 0xAF30, 0xA239, 0xAFCE, 0xA22C, 0xBABD, 0xA22C, 0xBB60, 0xA239, 0xBBFA, 0xA255, 0xFFFF, 0x93A4, 0xACDC, 0x9CEA, 0xACDC, 0x9CEA, 0xAA34, 0x93A4, 0xAA34, 0x93A4, 0xACDC, 0xFFFF, 0x93A4, 0xA796, 0x9CEA, 0xA796, 0x9CEA, 0xA525, 0x93A4, 0xA525, 0xFFFF, 0xA227, 0xA421, 0xA258, 0xA478, 0xA26E, 0xA4D5, 0xA26E, 0xA700, 0xA24F, 0xA757, 0xA204, 0xA7A5, 0xA089, 0xA8B8, 0xA061, 0xA903, 0xA092, 0xA949, 0xA1FC, 0xAA43, 0xA24B, 0xAA91, 0xA26E, 0xAAE8, 0xA26E, 0xAD36, 0xA258, 0xAD90, 0xA227, 0xADE6, 0x9EFC, 0xAFB2, 0x9E61, 0xAFCF, 0x9DBE, 0xAFDA, 0x8ED0, 0xAFDA, 0x8E28, 0xAF7A, 0x8E28, 0xA28C, 0x8E59, 0xA248, 0x8ED0, 0xA22C, 0x9DBE, 0xA22C, 0x9E61, 0xA239, 0x9EFC, 0xA255, 0xFFFF, 0x853C, 0xA502, 0x8517, 0xA557, 0x84C9, 0xA5A2, 0x7994, 0xACC8, 0x8494, 0xACC8, 0x850A, 0xACE4, 0x853C, 0xAD27, 0x853C, 0xAF7A, 0x850A, 0xAFBE, 0x8494, 0xAFDA, 0x7371, 0xAFDA, 0x72C9, 0xAF7A, 0x72C9, 0xAD09, 0x72E8, 0xACB2, 0x7333, 0xAC64, 0x7EA5, 0xA53E, 0x73A6, 0xA53E, 0x732F, 0xA522, 0x72FE, 0xA4DF, 0x72FE, 0xA28C, 0x732F, 0xA248, 0x73A6, 0xA22C, 0x8494, 0xA22C, 0x850A, 0xA248, 0x853C, 0xA28C, 0xFFFF, 0x6B68, 0xAC87, 0x6BDB, 0xACA3, 0x6C07, 0xACE6, 0x6C07, 0xAF7A, 0x6BDB, 0xAFBE, 0x6B68, 0xAFDA, 0x5C84, 0xAFDA, 0x5BDC, 0xAF7A, 0x5BDC, 0xA28C, 0x5C84, 0xA22C, 0x6146, 0xA22C, 0x61EE, 0xA28C, 0x61EE, 0xAC2D, 0x621E, 0xAC6E, 0x6295, 0xAC87, 0xFFFF, 0x52C6, 0xA248, 0x52F7, 0xA28C, 0x52F7, 0xAD45, 0x52EE, 0xAD45, 0x52DC, 0xAD9B, 0x52B1, 0xADE6, 0x4F85, 0xAFB2, 0x4EEA, 0xAFCF, 0x4E47, 0xAFDA, 0x4359, 0xAFDA, 0x42BA, 0xAFCF, 0x4224, 0xAFB2, 0x3EF8, 0xADE6, 0x3EC3, 0xAD90, 0x3EB2, 0xAD36, 0x3EB2, 0xA28C, 0x3EE2, 0xA248, 0x3F5A, 0xA22C, 0x441B, 0xA22C, 0x4493, 0xA248, 0x44C3, 0xA28C, 0x44C3, 0xAC2D, 0x44F4, 0xAC71, 0x456B, 0xAC8C, 0x4C3E, 0xAC8C, 0x4CB1, 0xAC71, 0x4CDD, 0xAC2D, 0x4CDD, 0xA28C, 0x4D0D, 0xA248, 0x4D85, 0xA22C, 0x524F, 0xA22C, 0xFFFF, 0x3748, 0xAC87, 0x37BB, 0xACA3, 0x37E7, 0xACE6, 0x37E7, 0xAF7A, 0x37BB, 0xAFBE, 0x3748, 0xAFDA, 0x2864, 0xAFDA, 0x27BC, 0xAF7A, 0x27BC, 0xA28C, 0x2864, 0xA22C, 0x2D26, 0xA22C, 0x2DCD, 0xA28C, 0x2DCD, 0xAC2D, 0x2DFE, 0xAC6E, 0x2E75, 0xAC87}; +const PROGMEM uint16_t logo_black[] = {0x8048, 0x527A, 0x8ADE, 0x5CDE, 0x75B2, 0x5CDE, 0xFFFF, 0x8048, 0x4FF6, 0x71D9, 0x5E20, 0x8EB8, 0x5E20, 0x8048, 0x4FF6, 0xFFFF, 0x4436, 0x8D8E, 0x4ECC, 0x97F2, 0x39A0, 0x97F2, 0xFFFF, 0x4436, 0x8B0A, 0x35C8, 0x9934, 0x52A5, 0x9934, 0xFFFF, 0xBC3D, 0x8D8E, 0xC6D4, 0x97F2, 0xB1A7, 0x97F2, 0xFFFF, 0xBC3D, 0x8B0A, 0xADCE, 0x9934, 0xCAAC, 0x9934, 0xFFFF, 0x8045, 0x6778, 0x7F6D, 0x67A7, 0x7E9D, 0x689F, 0x7D49, 0x69EA, 0x7B41, 0x6A81, 0x7908, 0x6A3A, 0x7726, 0x692C, 0x75EA, 0x685A, 0x7505, 0x684C, 0x744A, 0x6899, 0x73F5, 0x69A8, 0x7345, 0x6B1A, 0x7193, 0x6BF8, 0x6F4D, 0x6C08, 0x6CFA, 0x6B45, 0x6B61, 0x6AA3, 0x6A7D, 0x6AB7, 0x69EB, 0x6B1D, 0x6A1D, 0x6C34, 0x6A22, 0x6DB8, 0x68E5, 0x6ECD, 0x66B9, 0x6F33, 0x6417, 0x6EC5, 0x6239, 0x6E5C, 0x6165, 0x6E91, 0x6108, 0x6F09, 0x61C1, 0x7018, 0x6282, 0x7196, 0x61CF, 0x72D1, 0x5FE5, 0x7384, 0x5D38, 0x7380, 0x5B4B, 0x7365, 0x5A97, 0x73B7, 0x5A74, 0x7438, 0x5B90, 0x7520, 0x5CE8, 0x7671, 0x5CCB, 0x77BB, 0x5B43, 0x78B0, 0x58B6, 0x7914, 0x56D7, 0x7944, 0x564F, 0x79AD, 0x5667, 0x7A2F, 0x57DA, 0x7AE3, 0x59B7, 0x7BF3, 0x5A31, 0x7D37, 0x5927, 0x7E5D, 0x56E0, 0x7F1E, 0x5529, 0x7F93, 0x54D7, 0x800D, 0x5529, 0x8087, 0x56E0, 0x80FD, 0x5926, 0x81BE, 0x5A30, 0x82E5, 0x59B5, 0x8428, 0x57D8, 0x8538, 0x5664, 0x85EB, 0x564C, 0x866D, 0x56D4, 0x86D7, 0x58B2, 0x8708, 0x5B3F, 0x876B, 0x5CC6, 0x8860, 0x5CE3, 0x89AA, 0x5B8B, 0x8AFC, 0x5A6D, 0x8BE3, 0x5A91, 0x8C65, 0x5B44, 0x8CB7, 0x5D32, 0x8C9C, 0x5FDE, 0x8C98, 0x61C7, 0x8D4B, 0x627A, 0x8E87, 0x61B9, 0x9005, 0x60FF, 0x9114, 0x615C, 0x918B, 0x622F, 0x91C0, 0x640E, 0x9158, 0x66B0, 0x90EA, 0x68DC, 0x9150, 0x6A18, 0x9266, 0x6A12, 0x93E9, 0x69E0, 0x9501, 0x6A72, 0x9567, 0x6B56, 0x957B, 0x6CEE, 0x94D9, 0x6F43, 0x9417, 0x7188, 0x9428, 0x7339, 0x9506, 0x73E9, 0x9678, 0x743E, 0x9787, 0x74F8, 0x97D4, 0x75DD, 0x97C6, 0x771A, 0x96F4, 0x78FB, 0x95E6, 0x7B35, 0x95A1, 0x7D3D, 0x9637, 0x7E91, 0x9782, 0x7F60, 0x987A, 0x8038, 0x98AA, 0x810F, 0x987B, 0x81DF, 0x9782, 0x8333, 0x9638, 0x853B, 0x95A1, 0x8775, 0x95E7, 0x8956, 0x96F5, 0x8A92, 0x97C8, 0x8B78, 0x97D6, 0x8C32, 0x9789, 0x8C88, 0x967A, 0x8D37, 0x9508, 0x8EE9, 0x942A, 0x912F, 0x941A, 0x9383, 0x94DD, 0x951B, 0x957F, 0x95FF, 0x956B, 0x9690, 0x9505, 0x9660, 0x93ED, 0x9659, 0x926A, 0x9797, 0x9154, 0x99C3, 0x90EF, 0x9C65, 0x915D, 0x9E43, 0x91C6, 0x9F17, 0x9191, 0x9F74, 0x9119, 0x9EBB, 0x900A, 0x9DFA, 0x8E8C, 0x9EAE, 0x8D51, 0xA098, 0x8C9E, 0xA345, 0x8CA2, 0xA531, 0x8CBE, 0xA5E5, 0x8C6B, 0xA609, 0x8BEA, 0xA4EC, 0x8B02, 0xA394, 0x89B1, 0xA3B2, 0x8867, 0xA53A, 0x8772, 0xA7C6, 0x870E, 0xA9A5, 0x86DE, 0xAA2D, 0x8675, 0xAA14, 0x85F2, 0xA8A2, 0x853F, 0xA6C5, 0x842E, 0xA64B, 0x82EB, 0xA755, 0x81C5, 0xA99C, 0x8104, 0xAB52, 0x808F, 0xABA6, 0x8015, 0xAB52, 0x7F9B, 0xA99C, 0x7F25, 0xA755, 0x7E64, 0xA64C, 0x7D3E, 0xA6C7, 0x7BFA, 0xA8A5, 0x7AEA, 0xAA18, 0x7A37, 0xAA31, 0x79B5, 0xA9A9, 0x794B, 0xA7CA, 0x791B, 0xA53C, 0x78B7, 0xA3B6, 0x77C1, 0xA39A, 0x7677, 0xA4F1, 0x7526, 0xA60E, 0x743F, 0xA5EB, 0x73BD, 0xA538, 0x736B, 0xA34B, 0x7387, 0xA09E, 0x738A, 0x9EB4, 0x72D6, 0x9E02, 0x719B, 0x9EC4, 0x701D, 0x9F7E, 0x6F0E, 0x9F20, 0x6E96, 0x9E4E, 0x6E61, 0x9C6E, 0x6ECA, 0x99CB, 0x6F37, 0x97A0, 0x6ED2, 0x9664, 0x6DBC, 0x966B, 0x6C38, 0x969B, 0x6B21, 0x960B, 0x6ABB, 0x9526, 0x6AA6, 0x938E, 0x6B48, 0x913B, 0x6C0B, 0x8EF4, 0x6BFA, 0x8D43, 0x6B1D, 0x8C94, 0x69AA, 0x8C3F, 0x689B, 0x8B85, 0x684D, 0x8A9E, 0x685C, 0x8962, 0x692E, 0x8781, 0x6A3C, 0x8546, 0x6A82, 0x833F, 0x69EA, 0x81EC, 0x68A0, 0x811C, 0x67A8, 0x8045, 0x6778, 0x8045, 0x6778, 0xFFFF, 0x8047, 0x6AA0, 0x81C8, 0x6AFA, 0x8268, 0x6BD5, 0x81C8, 0x6CAF, 0x8047, 0x6D09, 0x7EC6, 0x6CAF, 0x7E27, 0x6BD5, 0x7EC6, 0x6AFA, 0x8047, 0x6AA0, 0x8047, 0x6AA0, 0xFFFF, 0x803E, 0x6E19, 0x867C, 0x6E71, 0x8C65, 0x6F75, 0x91D7, 0x711B, 0x96AD, 0x735B, 0x9ABC, 0x762C, 0x9DA2, 0x794C, 0x9F5F, 0x7CA2, 0x9FF3, 0x8011, 0x9F5E, 0x8380, 0x9DA1, 0x86D5, 0x9ABA, 0x89F6, 0x96AB, 0x8CC7, 0x91D6, 0x8F08, 0x8C65, 0x90AD, 0x867C, 0x91B1, 0x803D, 0x9209, 0x7A00, 0x91B1, 0x7416, 0x90AD, 0x6EA6, 0x8F08, 0x69D0, 0x8CC7, 0x65D6, 0x8A0A, 0x62EE, 0x86F4, 0x6125, 0x839B, 0x6089, 0x8011, 0x6124, 0x7C88, 0x62ED, 0x792E, 0x65D6, 0x7619, 0x69CF, 0x735B, 0x6EA5, 0x711B, 0x7416, 0x6F75, 0x7A00, 0x6E71, 0x803E, 0x6E19, 0x803E, 0x6E19, 0xFFFF, 0x803E, 0x6EB2, 0x7A5A, 0x6F04, 0x74B2, 0x6FF8, 0x6F4B, 0x7194, 0x6A8F, 0x73C7, 0x66A2, 0x7681, 0x63D5, 0x7986, 0x6226, 0x7CBF, 0x6197, 0x8011, 0x6226, 0x8363, 0x63D5, 0x869C, 0x66A2, 0x89A2, 0x6A8F, 0x8C5B, 0x6F4B, 0x8E8E, 0x74B2, 0x902B, 0x7A5A, 0x911E, 0x803D, 0x9170, 0x803E, 0x9170, 0x8621, 0x911E, 0x8BCA, 0x902B, 0x9130, 0x8E8E, 0x95ED, 0x8C5B, 0x99CF, 0x89AB, 0x9CA7, 0x869C, 0x9E55, 0x8367, 0x9EE5, 0x8011, 0x9E55, 0x7CBB, 0x9CA7, 0x7986, 0x99CF, 0x7677, 0x95ED, 0x73C7, 0x9130, 0x7194, 0x8BCA, 0x6FF8, 0x8621, 0x6F04, 0x803E, 0x6EB2, 0x803E, 0x6EB2, 0xFFFF, 0x80BC, 0x6FD7, 0x80AF, 0x71D8, 0x7FC8, 0x71D9, 0x7FB7, 0x6FD8, 0x80BC, 0x6FD7, 0x80BC, 0x6FD7, 0xFFFF, 0x83CB, 0x6FF6, 0x84CD, 0x700B, 0x843E, 0x7206, 0x835B, 0x71F4, 0xFFFF, 0x7CA9, 0x6FF8, 0x7D1A, 0x71F5, 0x7C37, 0x7207, 0x7BA7, 0x700D, 0x7CA9, 0x6FF8, 0x7CA9, 0x6FF8, 0xFFFF, 0x87CD, 0x7068, 0x88C7, 0x7092, 0x87BA, 0x727C, 0x86DF, 0x7258, 0xFFFF, 0x78A8, 0x706B, 0x7997, 0x725A, 0x78BA, 0x727E, 0x77AD, 0x7095, 0x78A8, 0x706B, 0x78A8, 0x706B, 0xFFFF, 0x6700, 0x708A, 0x6880, 0x70E5, 0x6920, 0x71BF, 0x6880, 0x7299, 0x66FF, 0x72F4, 0x657F, 0x7299, 0x64E0, 0x71BF, 0x657F, 0x70E4, 0x6700, 0x708A, 0x6700, 0x708A, 0xFFFF, 0x998D, 0x708C, 0x9B0E, 0x70E6, 0x9BAE, 0x71C0, 0x9B0E, 0x729B, 0x998D, 0x72F6, 0x980D, 0x729B, 0x976E, 0x71C1, 0x980D, 0x70E7, 0x998D, 0x708C, 0x998D, 0x708C, 0xFFFF, 0x8BA7, 0x712C, 0x8C95, 0x716A, 0x8B10, 0x7339, 0x8A3F, 0x7303, 0x8BA7, 0x712C, 0xFFFF, 0x74CE, 0x712F, 0x7635, 0x7307, 0x7564, 0x733C, 0x73DE, 0x716D, 0x74CE, 0x712F, 0x74CE, 0x712F, 0xFFFF, 0x8F47, 0x723F, 0x9023, 0x728E, 0x8E2D, 0x743A, 0x8D6B, 0x73F4, 0x8F47, 0x723F, 0xFFFF, 0x712D, 0x7242, 0x7308, 0x73F7, 0x7248, 0x743D, 0x7050, 0x7292, 0x712D, 0x7242, 0x712D, 0x7242, 0xFFFF, 0x803E, 0x72F6, 0x891B, 0x73F4, 0x909A, 0x76CC, 0x959F, 0x7B0B, 0x975E, 0x8011, 0x959F, 0x8517, 0x909A, 0x8957, 0x891B, 0x8C2E, 0x803E, 0x8D2B, 0x7761, 0x8C2E, 0x6FE2, 0x8957, 0x6ADD, 0x8517, 0x691E, 0x8011, 0x6ADD, 0x7B0B, 0x6FE2, 0x76CC, 0x7761, 0x73F4, 0x803E, 0x72F6, 0x803E, 0x72F6, 0xFFFF, 0x803E, 0x738F, 0x77C8, 0x7481, 0x70A0, 0x7738, 0x6BD7, 0x7B46, 0x6A2C, 0x8011, 0x6BD7, 0x84DC, 0x70A1, 0x88EA, 0x77C9, 0x8BA1, 0x803E, 0x8C93, 0x88B4, 0x8BA1, 0x8FDB, 0x88EA, 0x94A5, 0x84DD, 0x9650, 0x8011, 0x94A5, 0x7B46, 0x8FDB, 0x7738, 0x88B4, 0x7481, 0x803E, 0x738F, 0x803E, 0x738F, 0xFFFF, 0x929B, 0x739A, 0x935C, 0x73FA, 0x9100, 0x7578, 0x905A, 0x7527, 0x9175, 0x745E, 0xFFFF, 0x6DDC, 0x739D, 0x7022, 0x7527, 0x6F74, 0x757C, 0x6D16, 0x73FF, 0x6DDC, 0x739D, 0x6DDC, 0x739D, 0xFFFF, 0x9589, 0x7533, 0x9634, 0x75A4, 0x937E, 0x76ED, 0x92E8, 0x768B, 0xFFFF, 0x6AEB, 0x7539, 0x6D8D, 0x7690, 0x6CFB, 0x76F0, 0x6CEC, 0x76FA, 0x6BED, 0x7674, 0x6A40, 0x75A9, 0x6A45, 0x75A7, 0x6AEB, 0x7539, 0x6AEB, 0x7539, 0xFFFF, 0x980B, 0x7707, 0x989A, 0x7784, 0x9597, 0x7892, 0x951A, 0x7825, 0xFFFF, 0x686A, 0x770C, 0x6B5B, 0x782A, 0x6ADF, 0x7897, 0x67DD, 0x7788, 0x686A, 0x770C, 0x686A, 0x770C, 0xFFFF, 0x9A12, 0x790A, 0x9A7E, 0x7991, 0x9740, 0x7A5E, 0x96E1, 0x79E8, 0x9A12, 0x790A, 0xFFFF, 0x6664, 0x790F, 0x6996, 0x79ED, 0x6937, 0x7A63, 0x65F9, 0x7996, 0x6664, 0x790F, 0x6664, 0x790F, 0xFFFF, 0x9B91, 0x7B32, 0x9BDB, 0x7BC1, 0x9870, 0x7C48, 0x9831, 0x7BCB, 0xFFFF, 0x64E6, 0x7B37, 0x6847, 0x7BD0, 0x6807, 0x7C4C, 0x649D, 0x7BC5, 0x64E6, 0x7B37, 0x64E6, 0x7B37, 0xFFFF, 0x9C82, 0x7D72, 0x9CA7, 0x7E06, 0x9925, 0x7E46, 0x9903, 0x7DC5, 0xFFFF, 0x63F7, 0x7D78, 0x6776, 0x7DC9, 0x6756, 0x7E49, 0x63D3, 0x7E0A, 0x63F7, 0x7D78, 0x63F7, 0x7D78, 0xFFFF, 0x5C87, 0x7EDB, 0x5E08, 0x7F35, 0x5EA8, 0x800F, 0x5E08, 0x80E9, 0x5C87, 0x8144, 0x5C85, 0x8144, 0x5B06, 0x80E9, 0x5A67, 0x800F, 0x5B06, 0x7F35, 0x5C87, 0x7EDB, 0x5C87, 0x7EDB, 0xFFFF, 0xA402, 0x7EDE, 0xA583, 0x7F38, 0xA623, 0x8011, 0xA623, 0x8013, 0xA583, 0x80EC, 0xA402, 0x8147, 0xA281, 0x80ED, 0xA1E2, 0x8013, 0xA281, 0x7F38, 0xA402, 0x7EDE, 0xA402, 0x7EDE, 0xFFFF, 0x9CE0, 0x7FC0, 0x9CE0, 0x8055, 0x9957, 0x804D, 0x9957, 0x7FCB, 0xFFFF, 0x639D, 0x7FC5, 0x6726, 0x7FCE, 0x6726, 0x8051, 0x639D, 0x805A, 0x639D, 0x7FC5, 0x639D, 0x7FC5, 0xFFFF, 0x9927, 0x81D1, 0x9CAA, 0x8210, 0x9C87, 0x82A2, 0x9907, 0x8252, 0x9927, 0x81D1, 0x9927, 0x81D1, 0xFFFF, 0x6757, 0x81D5, 0x6777, 0x8255, 0x63F9, 0x82A7, 0x63D4, 0x8214, 0xFFFF, 0x9877, 0x83CF, 0x9BE2, 0x8455, 0x9B99, 0x84E3, 0x9838, 0x844C, 0x9877, 0x83CF, 0x9877, 0x83CF, 0xFFFF, 0x6808, 0x83D3, 0x6848, 0x8450, 0x64E7, 0x84E8, 0x649E, 0x845A, 0xFFFF, 0x9749, 0x85B9, 0x9A88, 0x8684, 0x9A1D, 0x870C, 0x96EB, 0x862E, 0x9749, 0x85B9, 0x9749, 0x85B9, 0xFFFF, 0x6938, 0x85BD, 0x6997, 0x8634, 0x6665, 0x8710, 0x65F9, 0x8689, 0xFFFF, 0x95A2, 0x8785, 0x98A5, 0x8892, 0x9818, 0x890F, 0x9527, 0x87F2, 0x95A2, 0x8785, 0x95A2, 0x8785, 0xFFFF, 0x6ADF, 0x878A, 0x6B5B, 0x87F8, 0x686A, 0x8914, 0x67DC, 0x8897, 0x6ADF, 0x878A, 0xFFFF, 0x6CF7, 0x892F, 0x6D8D, 0x8991, 0x6AEB, 0x8AE9, 0x6A40, 0x8A79, 0xFFFF, 0x9380, 0x8932, 0x9645, 0x8A72, 0x963E, 0x8A77, 0x9599, 0x8AE3, 0x92F5, 0x898D, 0x9380, 0x8932, 0x9380, 0x8932, 0xFFFF, 0x9110, 0x8AA1, 0x936F, 0x8C1F, 0x92AA, 0x8C80, 0x9064, 0x8AF7, 0x9110, 0x8AA1, 0x9110, 0x8AA1, 0xFFFF, 0x6F73, 0x8AA5, 0x7021, 0x8AFB, 0x7035, 0x8B04, 0x6DED, 0x8C8B, 0x6DE1, 0x8C87, 0x6D17, 0x8C23, 0xFFFF, 0x8E3E, 0x8BE1, 0x9037, 0x8D8B, 0x8F59, 0x8DDC, 0x8D7C, 0x8C27, 0x8E3E, 0x8BE1, 0x8E3E, 0x8BE1, 0xFFFF, 0x7259, 0x8BEB, 0x731B, 0x8C31, 0x7140, 0x8DE7, 0x7064, 0x8D97, 0xFFFF, 0x8B21, 0x8CE3, 0x8CA9, 0x8EB2, 0x8BBA, 0x8EEF, 0x8A51, 0x8D18, 0x8B21, 0x8CE3, 0x8B21, 0x8CE3, 0xFFFF, 0x7576, 0x8CEB, 0x7648, 0x8D20, 0x74E0, 0x8EF8, 0x73F2, 0x8EBB, 0xFFFF, 0x66F3, 0x8D2F, 0x6874, 0x8D8A, 0x687D, 0x8D8F, 0x6886, 0x8D94, 0x6926, 0x8E6E, 0x6887, 0x8F48, 0x6705, 0x8FA2, 0x6584, 0x8F49, 0x657F, 0x8F45, 0x6570, 0x8F3E, 0x6573, 0x8F3E, 0x64D3, 0x8E63, 0x6573, 0x8D89, 0x66F3, 0x8D2F, 0x66F3, 0x8D2F, 0xFFFF, 0x9993, 0x8D31, 0x9B13, 0x8D8C, 0x9BB4, 0x8E66, 0x9B16, 0x8F40, 0x9993, 0x8F9A, 0x9814, 0x8F40, 0x9774, 0x8E66, 0x9812, 0x8D8C, 0x9993, 0x8D31, 0x9993, 0x8D31, 0xFFFF, 0x87CD, 0x8DA1, 0x88DC, 0x8F8B, 0x87E0, 0x8FB5, 0x86F0, 0x8DC6, 0x87CD, 0x8DA1, 0x87CD, 0x8DA1, 0xFFFF, 0x78CD, 0x8DA8, 0x79A8, 0x8DCB, 0x78BC, 0x8FBB, 0x77C1, 0x8F92, 0xFFFF, 0x8450, 0x8E19, 0x84E2, 0x9014, 0x83E0, 0x9029, 0x836C, 0x8E2C, 0x8450, 0x8E19, 0x8450, 0x8E19, 0xFFFF, 0x7C48, 0x8E1C, 0x7D2B, 0x8E2E, 0x7CBD, 0x902C, 0x7BBB, 0x9017, 0x7C48, 0x8E1C, 0xFFFF, 0x80BF, 0x8E49, 0x80D2, 0x904A, 0x7FCC, 0x904A, 0x7FD9, 0x8E49, 0x80BF, 0x8E49, 0x80BF, 0x8E49, 0xFFFF, 0x804F, 0x9321, 0x81D0, 0x937A, 0x8271, 0x9455, 0x81D1, 0x952F, 0x8051, 0x958A, 0x7ECF, 0x9530, 0x7E2F, 0x9456, 0x7ECE, 0x937B, 0x804F, 0x9321, 0x804F, 0x9321, 0xFFFF, 0x8048, 0x46D9, 0x27BC, 0x9DBA, 0xD8D3, 0x9DBA, 0xFFFF, 0x8048, 0x4BC9, 0x952E, 0x604A, 0x6B62, 0x604A, 0xFFFF, 0x68D2, 0x62CE, 0x97BF, 0x62CE, 0xB9BA, 0x8427, 0xA239, 0x9B36, 0x5E16, 0x9B36, 0x46B6, 0x8446, 0x68D2, 0x62CE, 0xFFFF, 0xBC3E, 0x869F, 0xD13B, 0x9B36, 0xA742, 0x9B36, 0xFFFF, 0x4431, 0x86BE, 0x590E, 0x9B36, 0x2F54, 0x9B36, 0x4431, 0x86BE}; +const PROGMEM uint16_t logo_white[] = {0x80BC, 0x6FD7, 0x80AF, 0x71D8, 0x7FC8, 0x71D9, 0x7FB7, 0x6FD8, 0x80BC, 0x6FD7, 0xFFFF, 0x83CB, 0x6FF6, 0x84CD, 0x700B, 0x843E, 0x7206, 0x835B, 0x71F4, 0xFFFF, 0x7CA9, 0x6FF8, 0x7D1A, 0x71F5, 0x7C37, 0x7207, 0x7BA7, 0x700D, 0x7CA9, 0x6FF8, 0x7CA9, 0x6FF8, 0xFFFF, 0x87CD, 0x7068, 0x88C7, 0x7092, 0x87BA, 0x727C, 0x86DF, 0x7258, 0xFFFF, 0x78A8, 0x706B, 0x7997, 0x725A, 0x78BA, 0x727E, 0x77AD, 0x7095, 0x78A8, 0x706B, 0x78A8, 0x706B, 0xFFFF, 0x8BA7, 0x712C, 0x8C95, 0x716A, 0x8B10, 0x7339, 0x8A3F, 0x7303, 0xFFFF, 0x74CE, 0x712F, 0x7635, 0x7307, 0x7564, 0x733C, 0x73DE, 0x716D, 0x74CE, 0x712F, 0x74CE, 0x712F, 0xFFFF, 0x8F47, 0x723F, 0x9023, 0x728E, 0x8E2D, 0x743A, 0x8D6B, 0x73F4, 0xFFFF, 0x712D, 0x7242, 0x7309, 0x73F7, 0x7248, 0x743D, 0x7050, 0x7292, 0x712D, 0x7242, 0x712D, 0x7242, 0xFFFF, 0x929B, 0x739A, 0x935C, 0x73FA, 0x9100, 0x7578, 0x905A, 0x7527, 0xFFFF, 0x6DDC, 0x739D, 0x7022, 0x7527, 0x6F74, 0x757C, 0x6D16, 0x73FF, 0x6DDC, 0x739D, 0x6DDC, 0x739D, 0xFFFF, 0x9589, 0x7533, 0x9634, 0x75A4, 0x937E, 0x76ED, 0x92E8, 0x768B, 0xFFFF, 0x6AEB, 0x7539, 0x6D8D, 0x7690, 0x6CFB, 0x76F0, 0x6A40, 0x75A9, 0x6AEB, 0x7539, 0xFFFF, 0x980B, 0x7707, 0x989A, 0x7784, 0x9597, 0x7892, 0x951A, 0x7825, 0xFFFF, 0x686A, 0x770C, 0x6B5B, 0x782A, 0x6ADF, 0x7897, 0x67DD, 0x7788, 0x686A, 0x770C, 0x686A, 0x770C, 0xFFFF, 0x9A12, 0x790A, 0x9A7E, 0x7991, 0x9740, 0x7A5E, 0x96E1, 0x79E8, 0xFFFF, 0x6664, 0x790F, 0x6996, 0x79ED, 0x6937, 0x7A63, 0x65F9, 0x7996, 0x6664, 0x790F, 0x6664, 0x790F, 0xFFFF, 0x9B91, 0x7B32, 0x9BDB, 0x7BC1, 0x9870, 0x7C48, 0x9831, 0x7BCC, 0xFFFF, 0x64E6, 0x7B37, 0x6847, 0x7BD0, 0x6807, 0x7C4C, 0x649D, 0x7BC5, 0x64E6, 0x7B37, 0x64E6, 0x7B37, 0xFFFF, 0x9C82, 0x7D72, 0x9CA7, 0x7E06, 0x9925, 0x7E46, 0x9903, 0x7DC5, 0xFFFF, 0x63F7, 0x7D78, 0x6776, 0x7DC9, 0x6756, 0x7E49, 0x63D3, 0x7E0A, 0x63F7, 0x7D78, 0x63F7, 0x7D78, 0xFFFF, 0x9CE0, 0x7FC0, 0x9CE0, 0x8055, 0x9957, 0x804D, 0x9957, 0x7FCB, 0xFFFF, 0x639D, 0x7FC5, 0x6726, 0x7FCE, 0x6726, 0x8051, 0x639D, 0x805A, 0x639D, 0x7FC5, 0xFFFF, 0x9927, 0x81D1, 0x9CAA, 0x8210, 0x9C87, 0x82A2, 0x9907, 0x8252, 0x9927, 0x81D1, 0x9927, 0x81D1, 0xFFFF, 0x6757, 0x81D5, 0x6777, 0x8256, 0x63F9, 0x82A7, 0x63D4, 0x8214, 0xFFFF, 0x9877, 0x83CF, 0x9BE2, 0x8455, 0x9B99, 0x84E3, 0x9838, 0x844C, 0x9877, 0x83CF, 0xFFFF, 0x6808, 0x83D3, 0x6848, 0x8450, 0x64E7, 0x84E8, 0x649E, 0x845A, 0xFFFF, 0x9749, 0x85B9, 0x9A88, 0x8684, 0x9A1D, 0x870C, 0x96EB, 0x862E, 0x9749, 0x85B9, 0x9749, 0x85B9, 0xFFFF, 0x6938, 0x85BD, 0x6997, 0x8634, 0x6665, 0x8710, 0x65F9, 0x8689, 0xFFFF, 0x95A2, 0x8785, 0x98A5, 0x8892, 0x9818, 0x890F, 0x9527, 0x87F2, 0x95A2, 0x8785, 0x95A2, 0x8785, 0xFFFF, 0x6ADF, 0x878A, 0x6B5B, 0x87F8, 0x686A, 0x8915, 0x67DC, 0x8897, 0xFFFF, 0x6CF7, 0x8930, 0x6D8D, 0x8991, 0x6AEB, 0x8AE9, 0x6A40, 0x8A79, 0xFFFF, 0x9380, 0x8932, 0x9645, 0x8A72, 0x9599, 0x8AE3, 0x92F5, 0x898D, 0x9380, 0x8932, 0xFFFF, 0x9110, 0x8AA1, 0x936F, 0x8C1F, 0x92AA, 0x8C80, 0x9064, 0x8AF7, 0x9110, 0x8AA1, 0x9110, 0x8AA1, 0xFFFF, 0x6F73, 0x8AA5, 0x7021, 0x8AFB, 0x6DED, 0x8C8C, 0x6D17, 0x8C23, 0xFFFF, 0x8E3E, 0x8BE1, 0x9037, 0x8D8B, 0x8F59, 0x8DDC, 0x8D7C, 0x8C27, 0x8E3E, 0x8BE1, 0x8E3E, 0x8BE1, 0xFFFF, 0x7259, 0x8BEB, 0x731B, 0x8C31, 0x7140, 0x8DE7, 0x7064, 0x8D97, 0xFFFF, 0x8B21, 0x8CE3, 0x8CA9, 0x8EB2, 0x8BBA, 0x8EEF, 0x8A51, 0x8D18, 0x8B21, 0x8CE3, 0x8B21, 0x8CE3, 0xFFFF, 0x7576, 0x8CEB, 0x7648, 0x8D20, 0x74E0, 0x8EF8, 0x73F2, 0x8EBB, 0xFFFF, 0x87CD, 0x8DA1, 0x88DC, 0x8F8B, 0x87E0, 0x8FB5, 0x86F0, 0x8DC6, 0x87CD, 0x8DA1, 0x87CD, 0x8DA1, 0xFFFF, 0x78CC, 0x8DA8, 0x79A8, 0x8DCB, 0x78BC, 0x8FBB, 0x77C0, 0x8F92, 0xFFFF, 0x8450, 0x8E19, 0x84E2, 0x9014, 0x83E0, 0x9029, 0x836C, 0x8E2C, 0x8450, 0x8E19, 0x8450, 0x8E19, 0xFFFF, 0x7C48, 0x8E1C, 0x7D2B, 0x8E2E, 0x7CBD, 0x902C, 0x7BBB, 0x9017, 0xFFFF, 0x80BE, 0x8E49, 0x80D1, 0x904A, 0x7FCC, 0x904A, 0x7FD9, 0x8E49, 0x80BE, 0x8E49, 0xFFFF, 0x8276, 0x75D6, 0x83AF, 0x75FE, 0x8436, 0x7628, 0x84AE, 0x7661, 0x8542, 0x7706, 0x8512, 0x77BA, 0x8457, 0x7845, 0x8335, 0x788B, 0x8318, 0x7882, 0x82D8, 0x7860, 0x831E, 0x7830, 0x8353, 0x7823, 0x83E6, 0x77F9, 0x8464, 0x7790, 0x847A, 0x771A, 0x8415, 0x76B7, 0x83B6, 0x7691, 0x8351, 0x7676, 0x827F, 0x7662, 0x81BB, 0x7687, 0x8161, 0x76AF, 0x8123, 0x76DA, 0x80E5, 0x771A, 0x80C5, 0x774D, 0x80B8, 0x77C1, 0x80D1, 0x77EE, 0x8107, 0x7814, 0x81CC, 0x786B, 0x837F, 0x7918, 0x8464, 0x7983, 0x84C0, 0x79B2, 0x852D, 0x79FD, 0x859D, 0x7ABC, 0x858E, 0x7B79, 0x8545, 0x7C25, 0x84D9, 0x7CC5, 0x8469, 0x7D4D, 0x843B, 0x7DCD, 0x8555, 0x7DA8, 0x85D3, 0x7D67, 0x870D, 0x7CA0, 0x87E0, 0x7BC0, 0x880D, 0x7B5B, 0x886D, 0x7A46, 0x88B3, 0x799B, 0x88CC, 0x7970, 0x893A, 0x78EA, 0x8995, 0x78A8, 0x8A01, 0x786F, 0x8AF8, 0x781F, 0x8BA6, 0x77FD, 0x8C0C, 0x77EF, 0x8C96, 0x77FB, 0x8D1D, 0x7815, 0x8D59, 0x7826, 0x8E40, 0x7889, 0x8EDB, 0x7925, 0x8EFC, 0x797B, 0x8EFF, 0x79D4, 0x8E71, 0x7A7B, 0x8D58, 0x7AD2, 0x8C23, 0x7ADE, 0x8AFF, 0x7A97, 0x8AF5, 0x7A81, 0x8AEF, 0x7A4E, 0x8B68, 0x7A52, 0x8B96, 0x7A5F, 0x8C39, 0x7A87, 0x8D33, 0x7A7F, 0x8E07, 0x7A3F, 0x8E66, 0x79CB, 0x8E63, 0x7985, 0x8E43, 0x793F, 0x8DC6, 0x78C6, 0x8CFA, 0x7876, 0x8C7E, 0x785F, 0x8C18, 0x7857, 0x8B84, 0x7874, 0x8B22, 0x788F, 0x8A7D, 0x78CA, 0x8A2E, 0x78F9, 0x89F0, 0x7930, 0x89A3, 0x79A5, 0x8979, 0x7AC0, 0x897C, 0x7B9C, 0x8972, 0x7BF2, 0x88CC, 0x7D32, 0x87B7, 0x7E4C, 0x8665, 0x7F52, 0x8660, 0x7F5A, 0x878F, 0x7F01, 0x88AE, 0x7EC2, 0x89FD, 0x7E9E, 0x8B8D, 0x7EC6, 0x8C40, 0x7F0E, 0x8CB6, 0x7F68, 0x8D1D, 0x7FD7, 0x8DFA, 0x80BD, 0x8EA8, 0x816E, 0x8F34, 0x81D4, 0x8F8A, 0x81F9, 0x8FDA, 0x820A, 0x90AB, 0x820F, 0x9120, 0x81FF, 0x91A5, 0x81DC, 0x91F4, 0x81B8, 0x922C, 0x8198, 0x9288, 0x812B, 0x927D, 0x80AB, 0x9252, 0x8068, 0x921C, 0x8033, 0x9174, 0x7FEB, 0x9099, 0x7FEB, 0x8FCF, 0x8029, 0x8F5D, 0x808D, 0x8F47, 0x80A4, 0x8ED4, 0x80A4, 0x8EC5, 0x8070, 0x8F65, 0x7FE6, 0x906D, 0x7F92, 0x91A4, 0x7F90, 0x92A8, 0x7FF7, 0x92FC, 0x8043, 0x9331, 0x8090, 0x9349, 0x813D, 0x92D1, 0x81E3, 0x9264, 0x8227, 0x91E5, 0x825B, 0x915D, 0x8280, 0x90D3, 0x8296, 0x8FA0, 0x829A, 0x8F2C, 0x8286, 0x8EE7, 0x8273, 0x8E78, 0x824A, 0x8DA9, 0x81D4, 0x8CB9, 0x8127, 0x8B68, 0x802C, 0x8B22, 0x8001, 0x8AC3, 0x7FE7, 0x8A50, 0x7FF4, 0x88FD, 0x8068, 0x87A4, 0x811D, 0x879E, 0x812D, 0x8904, 0x81F1, 0x89D4, 0x8285, 0x8A7C, 0x8343, 0x8A94, 0x8431, 0x8A4E, 0x84A1, 0x89E8, 0x850E, 0x892F, 0x85E5, 0x88B0, 0x86E5, 0x88C0, 0x8757, 0x88F2, 0x878D, 0x8927, 0x87AD, 0x8ABF, 0x8821, 0x8B0E, 0x881E, 0x8B70, 0x8811, 0x8C1B, 0x87D6, 0x8C9B, 0x8776, 0x8CC4, 0x873D, 0x8CD3, 0x8705, 0x8CA2, 0x86A3, 0x8C06, 0x8662, 0x8B39, 0x864F, 0x8A77, 0x8662, 0x89F9, 0x864D, 0x8A10, 0x8606, 0x8A66, 0x85F7, 0x8B35, 0x85DC, 0x8C50, 0x85FD, 0x8D3C, 0x8663, 0x8D94, 0x870A, 0x8D7D, 0x875F, 0x8D3A, 0x87B8, 0x8CB1, 0x882D, 0x8BC1, 0x888C, 0x8B30, 0x88A7, 0x8A8D, 0x88AE, 0x89EE, 0x8898, 0x896E, 0x887E, 0x8869, 0x882D, 0x87EE, 0x87EA, 0x87A4, 0x87A8, 0x878E, 0x8785, 0x874D, 0x86E3, 0x875D, 0x8637, 0x87FD, 0x8466, 0x8705, 0x835A, 0x86B8, 0x8359, 0x84A4, 0x8358, 0x7F20, 0x851B, 0x7F13, 0x864D, 0x8016, 0x86F9, 0x818E, 0x87D8, 0x823B, 0x8869, 0x8272, 0x88C9, 0x8276, 0x8915, 0x8266, 0x893D, 0x81FB, 0x89D8, 0x8197, 0x8A21, 0x8119, 0x8A62, 0x80A7, 0x8A8A, 0x8016, 0x8AAA, 0x7EDC, 0x8AAE, 0x7DC5, 0x8A63, 0x7D55, 0x8A29, 0x7CFA, 0x89E5, 0x7CAD, 0x8939, 0x7D1B, 0x8895, 0x7E00, 0x8825, 0x7F27, 0x8800, 0x7F66, 0x880F, 0x7F69, 0x8850, 0x7E49, 0x8873, 0x7D9A, 0x88C9, 0x7D4F, 0x893E, 0x7D8B, 0x89B2, 0x7DD8, 0x89E6, 0x7E36, 0x8A10, 0x7F02, 0x8A40, 0x7FDB, 0x8A34, 0x8046, 0x8A16, 0x8091, 0x89F5, 0x80A5, 0x89EB, 0x80FE, 0x89AB, 0x8126, 0x8981, 0x8159, 0x8918, 0x814F, 0x88E6, 0x8128, 0x88B8, 0x8094, 0x8856, 0x7EFC, 0x8796, 0x7D74, 0x86E7, 0x7D3D, 0x86C5, 0x7CD8, 0x8674, 0x7C98, 0x8605, 0x7CA0, 0x8536, 0x7D7C, 0x83E6, 0x7E07, 0x8357, 0x7DED, 0x835B, 0x79CC, 0x843E, 0x7962, 0x8448, 0x77CB, 0x8450, 0x76F3, 0x8438, 0x763E, 0x841E, 0x7502, 0x83FE, 0x746C, 0x83FD, 0x73E4, 0x840A, 0x72CE, 0x8444, 0x729B, 0x8457, 0x71E6, 0x84B7, 0x71B5, 0x84EB, 0x719B, 0x853B, 0x719B, 0x8558, 0x71D4, 0x85E0, 0x72B0, 0x8642, 0x73D4, 0x8661, 0x74B3, 0x8616, 0x74AD, 0x84D7, 0x74B2, 0x84B3, 0x74B5, 0x849B, 0x751E, 0x8496, 0x753B, 0x84B8, 0x75C5, 0x856E, 0x756D, 0x865A, 0x74D0, 0x86B8, 0x73FA, 0x86EA, 0x7250, 0x86CF, 0x70E7, 0x863F, 0x707E, 0x85C8, 0x705F, 0x8549, 0x7075, 0x84CC, 0x70AC, 0x8475, 0x70CD, 0x8452, 0x71FF, 0x839C, 0x7287, 0x8376, 0x736A, 0x833A, 0x7443, 0x8319, 0x751E, 0x8311, 0x76AC, 0x8327, 0x77C4, 0x8341, 0x7810, 0x8340, 0x799F, 0x8313, 0x7A2A, 0x82EA, 0x7B24, 0x8281, 0x7BE4, 0x820C, 0x7BEC, 0x81B1, 0x7A5E, 0x81C8, 0x7809, 0x81ED, 0x7751, 0x81F8, 0x7664, 0x81EF, 0x7571, 0x81B4, 0x74BB, 0x8141, 0x7483, 0x80F9, 0x7408, 0x802F, 0x73D9, 0x7FEB, 0x7359, 0x7F50, 0x72A0, 0x7EC4, 0x719E, 0x7E89, 0x7074, 0x7EA8, 0x7015, 0x7ECC, 0x6FD0, 0x7EF8, 0x6FA3, 0x7F19, 0x6F6B, 0x7FBB, 0x6F93, 0x8017, 0x6FA7, 0x8032, 0x6FD7, 0x805A, 0x70DF, 0x8092, 0x7205, 0x805A, 0x729E, 0x7FCB, 0x72B3, 0x7FBC, 0x7309, 0x7FA6, 0x733B, 0x7FDE, 0x72F9, 0x804B, 0x726D, 0x80A7, 0x70E6, 0x80FB, 0x700D, 0x80EC, 0x6F48, 0x80A8, 0x6EFC, 0x8073, 0x6EC1, 0x8026, 0x6E93, 0x7FCC, 0x6ED4, 0x7ED8, 0x6F54, 0x7E72, 0x6FCB, 0x7E3A, 0x700B, 0x7E25, 0x71AB, 0x7DED, 0x7356, 0x7E3E, 0x7472, 0x7EF4, 0x7536, 0x7FBD, 0x75DA, 0x8075, 0x7628, 0x80B6, 0x767B, 0x80D8, 0x76D9, 0x80EF, 0x7755, 0x80FC, 0x7881, 0x80D5, 0x7931, 0x8093, 0x7A00, 0x801E, 0x799B, 0x7D9B, 0x789A, 0x7CD8, 0x77C0, 0x7BE5, 0x7783, 0x7B55, 0x7787, 0x7AB9, 0x77AE, 0x7A67, 0x77E6, 0x7A1D, 0x781E, 0x79CD, 0x785E, 0x7909, 0x7853, 0x78C0, 0x7823, 0x788B, 0x7808, 0x7875, 0x7649, 0x77E8, 0x74B6, 0x7869, 0x7488, 0x78B3, 0x7472, 0x7901, 0x74D2, 0x796F, 0x75D8, 0x799A, 0x76EE, 0x7971, 0x774A, 0x797A, 0x7751, 0x79B4, 0x76A0, 0x79F0, 0x75E4, 0x7A0A, 0x7454, 0x79E1, 0x73AF, 0x7986, 0x7369, 0x7909, 0x7374, 0x7891, 0x739D, 0x783C, 0x73B6, 0x781E, 0x74B7, 0x7768, 0x765D, 0x772C, 0x77ED, 0x7769, 0x7932, 0x77FC, 0x7979, 0x7836, 0x79B8, 0x787B, 0x79DF, 0x7912, 0x7998, 0x7A14, 0x7967, 0x7AB4, 0x796A, 0x7AD8, 0x79C5, 0x7B60, 0x7A9D, 0x7BE9, 0x7B72, 0x7C47, 0x7EBA, 0x7BD6, 0x8206, 0x7CA8, 0x82FA, 0x7C2E, 0x8391, 0x7BB4, 0x83F6, 0x7B40, 0x8413, 0x7AD0, 0x83DD, 0x7A71, 0x838A, 0x7A39, 0x8296, 0x79B7, 0x80F3, 0x78FA, 0x8016, 0x788A, 0x7FB4, 0x7833, 0x7F8D, 0x77DF, 0x7F92, 0x77A9, 0x7FB3, 0x7718, 0x7FF6, 0x76C2, 0x8036, 0x768A, 0x8097, 0x764A, 0x80DF, 0x762A, 0x813C, 0x7605, 0x8275, 0x75D5}; + +#define LOGO_BACKGROUND 0xDEEA5C + +#define LOGO_PAINT_PATHS \ + LOGO_PAINT_PATH(0xC1D82F, logo_green) \ + LOGO_PAINT_PATH(0x000000, logo_black) \ + LOGO_PAINT_PATH(0x000000, logo_type) \ + LOGO_PAINT_PATH(0x000000, logo_mark) \ + LOGO_PAINT_PATH(0xFFFFFF, logo_white) 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 f99c0fd3eb..4e2fde6ab3 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/colors.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/colors.h @@ -124,7 +124,13 @@ namespace Theme { constexpr uint32_t shadow_rgb = gray_color_6; constexpr uint32_t stroke_rgb = accent_color_1; constexpr uint32_t fill_rgb = accent_color_3; - constexpr uint32_t syringe_rgb = accent_color_5; + #if ENABLED(TOUCH_UI_COCOA_PRESS) + constexpr uint32_t syringe_rgb = 0xFFFFFF; + constexpr uint32_t fluid_rgb = accent_color_5; + #else + constexpr uint32_t syringe_rgb = accent_color_5; + constexpr uint32_t fluid_rgb = accent_color_3; + #endif #if ENABLED(TOUCH_UI_ROYAL_THEME) constexpr uint32_t x_axis = hsl_to_rgb(0, 1.00, 0.26); diff --git a/Marlin/src/lcd/extui/lib/mks_ui/SPIFlashStorage.cpp b/Marlin/src/lcd/extui/lib/mks_ui/SPIFlashStorage.cpp index 979c916e5c..3f57124451 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/SPIFlashStorage.cpp +++ b/Marlin/src/lcd/extui/lib/mks_ui/SPIFlashStorage.cpp @@ -223,7 +223,7 @@ void SPIFlashStorage::flushPage() { #if HAS_SPI_FLASH_COMPRESSION // Restart the compressed buffer, keep the pointers of the uncompressed buffer m_compressedDataUsed = 0; - #elif + #else m_pageDataUsed = 0; #endif m_currentPage++; diff --git a/Marlin/src/lcd/extui/lib/mks_ui/SPI_TFT.cpp b/Marlin/src/lcd/extui/lib/mks_ui/SPI_TFT.cpp index ea94d6c1a5..351d033d01 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/SPI_TFT.cpp +++ b/Marlin/src/lcd/extui/lib/mks_ui/SPI_TFT.cpp @@ -26,6 +26,7 @@ #include "SPI_TFT.h" #include "pic_manager.h" +#include "tft_lvgl_configuration.h" #include "../../../../inc/MarlinConfig.h" @@ -74,6 +75,7 @@ void TFT::SetWindows(uint16_t x, uint16_t y, uint16_t with, uint16_t height) { } void TFT::LCD_init() { + TFT_BLK_L; TFT_RST_H; delay(150); TFT_RST_L; @@ -92,8 +94,7 @@ void TFT::LCD_init() { LCD_WR_DATA(0x96); LCD_WR_REG(0x36); - LCD_WR_DATA(0x28); - + LCD_WR_DATA(0x28 + TERN0(GRAPHICAL_TFT_ROTATE_180, 0x80)); LCD_WR_REG(0x3A); LCD_WR_DATA(0x55); diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_about.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_about.cpp index 94a865d045..34b7427860 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_about.cpp +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_about.cpp @@ -33,8 +33,9 @@ #include "../../../../MarlinCore.h" #include "../../../../module/temperature.h" +extern lv_group_t * g; static lv_obj_t * scr; -static lv_obj_t * fw_type, *board, *fw_version; +static lv_obj_t * fw_type, *board; //*fw_version; #define ID_A_RETURN 1 @@ -73,23 +74,24 @@ void lv_draw_about(void) { lv_refr_now(lv_refr_get_disp_refreshing()); - LV_IMG_DECLARE(bmp_pic); - - /*Create an Image button*/ + // Create an Image button buttonBack = lv_imgbtn_create(scr, NULL); #if 1 - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_A_RETURN, "bmp_return.bin", 0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_A_RETURN, NULL, 0); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_return.bin"); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_return.bin"); lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonBack); + #endif #endif lv_obj_set_pos(buttonBack, BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight); lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); - /*Create a label on the Image button*/ + // Create a label on the image button label_Back = lv_label_create(buttonBack, NULL); if (gCfgItems.multiple_language != 0) { @@ -97,30 +99,27 @@ void lv_draw_about(void) { lv_obj_align(label_Back, buttonBack, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); } - fw_version = lv_label_create(scr, NULL); - lv_obj_set_style(fw_version, &tft_style_label_rel); - lv_label_set_text(fw_version, SHORT_BUILD_VERSION); - lv_obj_align(fw_version, NULL, LV_ALIGN_CENTER, 0, -60); + //fw_version = lv_label_create(scr, NULL); + //lv_obj_set_style(fw_version, &tft_style_label_rel); + //lv_label_set_text(fw_version, SHORT_BUILD_VERSION); + //lv_obj_align(fw_version, NULL, LV_ALIGN_CENTER, 0, -60); fw_type = lv_label_create(scr, NULL); lv_obj_set_style(fw_type, &tft_style_label_rel); - lv_label_set_text(fw_type, - #if MB(MKS_ROBIN_PRO) - "Firmware: Robin_Pro35" - #elif MB(MKS_ROBIN_NANO, MKS_ROBIN_NANO_V2) - "Firmware: Robin_Nano35" - #else - CUSTOM_MACHINE_NAME - #endif - ); + lv_label_set_text(fw_type, "Firmware: Marlin " SHORT_BUILD_VERSION); lv_obj_align(fw_type, NULL, LV_ALIGN_CENTER, 0, -20); board = lv_label_create(scr, NULL); lv_obj_set_style(board, &tft_style_label_rel); lv_label_set_text(board, "Board: " BOARD_INFO_NAME); - lv_obj_align(board, NULL, LV_ALIGN_CENTER, 0, 20); + lv_obj_align(board, NULL, LV_ALIGN_CENTER, 0, -60); } -void lv_clear_about() { lv_obj_del(scr); } +void lv_clear_about() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} #endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_about.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_about.h index 4c6c288d08..2ee7ec04c6 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_about.h +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_about.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus -extern "C" { /* C-declarations for C++ */ + extern "C" { /* C-declarations for C++ */ #endif extern void lv_draw_about(void); @@ -30,5 +30,5 @@ extern void lv_clear_about(); //extern void disp_temp_ready_print(); #ifdef __cplusplus -} /* C-declarations for C++ */ + } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_acceleration_settings.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_acceleration_settings.cpp index b6906a6dfe..a30c99dba0 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_acceleration_settings.cpp +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_acceleration_settings.cpp @@ -29,6 +29,7 @@ #include "../../../../MarlinCore.h" #include "../../../../module/planner.h" +extern lv_group_t * g; static lv_obj_t * scr; #define ID_ACCE_RETURN 1 @@ -160,14 +161,14 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { void lv_draw_acceleration_settings(void) { lv_obj_t *buttonBack = NULL, *label_Back = NULL, *buttonTurnPage = NULL, *labelTurnPage = NULL; - lv_obj_t *buttonPrintText = NULL, *labelPrintText = NULL, *buttonPrintValue = NULL, *labelPrintValue = NULL; - lv_obj_t *buttonRetraText = NULL, *labelRetraText = NULL, *buttonRetraValue = NULL, *labelRetraValue = NULL; - lv_obj_t *buttonTravelText = NULL, *labelTravelText = NULL, *buttonTravelValue = NULL, *labelTravelValue = NULL; - lv_obj_t *buttonXText = NULL, *labelXText = NULL, *buttonXValue = NULL, *labelXValue = NULL; - lv_obj_t *buttonYText = NULL, *labelYText = NULL, *buttonYValue = NULL, *labelYValue = NULL; - lv_obj_t *buttonZText = NULL, *labelZText = NULL, *buttonZValue = NULL, *labelZValue = NULL; - lv_obj_t *buttonE0Text = NULL, *labelE0Text = NULL, *buttonE0Value = NULL, *labelE0Value = NULL; - lv_obj_t *buttonE1Text = NULL, *labelE1Text = NULL, *buttonE1Value = NULL, *labelE1Value = NULL; + lv_obj_t *labelPrintText = NULL, *buttonPrintValue = NULL, *labelPrintValue = NULL; + lv_obj_t *labelRetraText = NULL, *buttonRetraValue = NULL, *labelRetraValue = NULL; + lv_obj_t *labelTravelText = NULL, *buttonTravelValue = NULL, *labelTravelValue = NULL; + lv_obj_t *labelXText = NULL, *buttonXValue = NULL, *labelXValue = NULL; + lv_obj_t *labelYText = NULL, *buttonYValue = NULL, *labelYValue = NULL; + lv_obj_t *labelZText = NULL, *buttonZValue = NULL, *labelZValue = NULL; + lv_obj_t *labelE0Text = NULL, *buttonE0Value = NULL, *labelE0Value = NULL; + lv_obj_t *labelE1Text = NULL, *buttonE1Value = NULL, *labelE1Value = NULL; lv_obj_t * line1 = NULL, * line2 = NULL, * line3 = NULL, * line4 = NULL; if (disp_state_stack._disp_state[disp_state_stack._disp_index] != ACCELERATION_UI) { disp_state_stack._disp_index++; @@ -188,231 +189,202 @@ void lv_draw_acceleration_settings(void) { lv_refr_now(lv_refr_get_disp_refreshing()); - LV_IMG_DECLARE(bmp_para_back); - // LV_IMG_DECLARE(bmp_para_arrow); - LV_IMG_DECLARE(bmp_para_bank); - if (uiCfg.para_ui_page != 1) { - buttonPrintText = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonPrintText, PARA_UI_POS_X, PARA_UI_POS_Y); /*Set its position*/ - lv_obj_set_size(buttonPrintText, PARA_UI_VALUE_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - lv_obj_set_event_cb(buttonPrintText, event_handler); - lv_btn_set_style(buttonPrintText, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonPrintText, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonPrintText, LV_LAYOUT_OFF); - labelPrintText = lv_label_create(buttonPrintText, NULL); /*Add a label to the button*/ - - buttonPrintValue = lv_imgbtn_create(scr, NULL); + + labelPrintText = lv_label_create(scr, NULL); + lv_obj_set_style(labelPrintText, &tft_style_label_rel); + lv_obj_set_pos(labelPrintText, PARA_UI_POS_X, PARA_UI_POS_Y + 10); + lv_label_set_text(labelPrintText, machine_menu.PrintAcceleration); + + buttonPrintValue = lv_btn_create(scr, NULL); lv_obj_set_pos(buttonPrintValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y + PARA_UI_VALUE_V); - lv_obj_set_event_cb_mks(buttonPrintValue, event_handler, ID_ACCE_PRINT, "bmp_value_blank.bin", 0); - lv_imgbtn_set_src(buttonPrintValue, LV_BTN_STATE_REL, &bmp_para_bank); - lv_imgbtn_set_src(buttonPrintValue, LV_BTN_STATE_PR, &bmp_para_bank); - lv_imgbtn_set_style(buttonPrintValue, LV_BTN_STATE_PR, &style_para_value_pre); - lv_imgbtn_set_style(buttonPrintValue, LV_BTN_STATE_REL, &style_para_value_rel); - lv_btn_set_layout(buttonPrintValue, LV_LAYOUT_OFF); + lv_obj_set_size(buttonPrintValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonPrintValue, event_handler, ID_ACCE_PRINT, NULL, 0); + lv_btn_set_style(buttonPrintValue, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonPrintValue, LV_BTN_STYLE_PR, &style_para_value); labelPrintValue = lv_label_create(buttonPrintValue, NULL); line1 = lv_line_create(scr, NULL); lv_ex_line(line1, line_points[0]); - buttonRetraText = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonRetraText, PARA_UI_POS_X, PARA_UI_POS_Y * 2); /*Set its position*/ - lv_obj_set_size(buttonRetraText, PARA_UI_VALUE_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - lv_obj_set_event_cb(buttonRetraText, event_handler); - lv_btn_set_style(buttonRetraText, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonRetraText, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonRetraText, LV_LAYOUT_OFF); - labelRetraText = lv_label_create(buttonRetraText, NULL); /*Add a label to the button*/ + labelRetraText = lv_label_create(scr, NULL); + lv_obj_set_style(labelRetraText, &tft_style_label_rel); + lv_obj_set_pos(labelRetraText, PARA_UI_POS_X, PARA_UI_POS_Y * 2 + 10); + lv_label_set_text(labelRetraText, machine_menu.RetractAcceleration); - buttonRetraValue = lv_imgbtn_create(scr, NULL); + buttonRetraValue = lv_btn_create(scr, NULL); lv_obj_set_pos(buttonRetraValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 2 + PARA_UI_VALUE_V); - lv_obj_set_event_cb_mks(buttonRetraValue, event_handler, ID_ACCE_RETRA, "bmp_value_blank.bin", 0); - lv_imgbtn_set_src(buttonRetraValue, LV_BTN_STATE_REL, &bmp_para_bank); - lv_imgbtn_set_src(buttonRetraValue, LV_BTN_STATE_PR, &bmp_para_bank); - lv_imgbtn_set_style(buttonRetraValue, LV_BTN_STATE_PR, &style_para_value_pre); - lv_imgbtn_set_style(buttonRetraValue, LV_BTN_STATE_REL, &style_para_value_rel); - lv_btn_set_layout(buttonRetraValue, LV_LAYOUT_OFF); + lv_obj_set_size(buttonRetraValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonRetraValue, event_handler, ID_ACCE_RETRA, NULL, 0); + lv_btn_set_style(buttonRetraValue, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonRetraValue, LV_BTN_STYLE_PR, &style_para_value); labelRetraValue = lv_label_create(buttonRetraValue, NULL); line2 = lv_line_create(scr, NULL); lv_ex_line(line2, line_points[1]); - buttonTravelText = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonTravelText, PARA_UI_POS_X, PARA_UI_POS_Y * 3); /*Set its position*/ - lv_obj_set_size(buttonTravelText, PARA_UI_VALUE_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - lv_obj_set_event_cb(buttonTravelText, event_handler); - lv_btn_set_style(buttonTravelText, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonTravelText, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonTravelText, LV_LAYOUT_OFF); - labelTravelText = lv_label_create(buttonTravelText, NULL); /*Add a label to the button*/ + labelTravelText = lv_label_create(scr, NULL); + lv_obj_set_style(labelTravelText, &tft_style_label_rel); + lv_obj_set_pos(labelTravelText, PARA_UI_POS_X, PARA_UI_POS_Y * 3 + 10); + lv_label_set_text(labelTravelText, machine_menu.TravelAcceleration); - buttonTravelValue = lv_imgbtn_create(scr, NULL); + buttonTravelValue = lv_btn_create(scr, NULL); lv_obj_set_pos(buttonTravelValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 3 + PARA_UI_VALUE_V); - lv_obj_set_event_cb_mks(buttonTravelValue, event_handler, ID_ACCE_TRAVEL, "bmp_value_blank.bin", 0); - lv_imgbtn_set_src(buttonTravelValue, LV_BTN_STATE_REL, &bmp_para_bank); - lv_imgbtn_set_src(buttonTravelValue, LV_BTN_STATE_PR, &bmp_para_bank); - lv_imgbtn_set_style(buttonTravelValue, LV_BTN_STATE_PR, &style_para_value_pre); - lv_imgbtn_set_style(buttonTravelValue, LV_BTN_STATE_REL, &style_para_value_rel); - lv_btn_set_layout(buttonTravelValue, LV_LAYOUT_OFF); + lv_obj_set_size(buttonTravelValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonTravelValue, event_handler, ID_ACCE_TRAVEL, NULL, 0); + lv_btn_set_style(buttonTravelValue, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonTravelValue, LV_BTN_STYLE_PR, &style_para_value); labelTravelValue = lv_label_create(buttonTravelValue, NULL); line3 = lv_line_create(scr, NULL); lv_ex_line(line3, line_points[2]); - buttonXText = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonXText, PARA_UI_POS_X, PARA_UI_POS_Y * 4); /*Set its position*/ - lv_obj_set_size(buttonXText, PARA_UI_VALUE_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - lv_obj_set_event_cb(buttonXText, event_handler); - lv_btn_set_style(buttonXText, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonXText, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonXText, LV_LAYOUT_OFF); - labelXText = lv_label_create(buttonXText, NULL); /*Add a label to the button*/ + labelXText = lv_label_create(scr, NULL); + lv_obj_set_style(labelXText, &tft_style_label_rel); + lv_obj_set_pos(labelXText, PARA_UI_POS_X, PARA_UI_POS_Y * 4 + 10); + lv_label_set_text(labelXText, machine_menu.X_Acceleration); - buttonXValue = lv_imgbtn_create(scr, NULL); + buttonXValue = lv_btn_create(scr, NULL); lv_obj_set_pos(buttonXValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 4 + PARA_UI_VALUE_V); - lv_obj_set_event_cb_mks(buttonXValue, event_handler, ID_ACCE_X, "bmp_value_blank.bin", 0); - lv_imgbtn_set_src(buttonXValue, LV_BTN_STATE_REL, &bmp_para_bank); - lv_imgbtn_set_src(buttonXValue, LV_BTN_STATE_PR, &bmp_para_bank); - lv_imgbtn_set_style(buttonXValue, LV_BTN_STATE_PR, &style_para_value_pre); - lv_imgbtn_set_style(buttonXValue, LV_BTN_STATE_REL, &style_para_value_rel); - lv_btn_set_layout(buttonXValue, LV_LAYOUT_OFF); + lv_obj_set_size(buttonXValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonXValue, event_handler, ID_ACCE_X, NULL, 0); + lv_btn_set_style(buttonXValue, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonXValue, LV_BTN_STYLE_PR, &style_para_value); labelXValue = lv_label_create(buttonXValue, NULL); line4 = lv_line_create(scr, NULL); lv_ex_line(line4, line_points[3]); - buttonTurnPage = lv_imgbtn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonTurnPage, event_handler, ID_ACCE_DOWN, "bmp_back70x40.bin", 0); - lv_imgbtn_set_src(buttonTurnPage, LV_BTN_STATE_REL, &bmp_para_back); - lv_imgbtn_set_src(buttonTurnPage, LV_BTN_STATE_PR, &bmp_para_back); - lv_imgbtn_set_style(buttonTurnPage, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonTurnPage, LV_BTN_STATE_REL, &tft_style_label_rel); + buttonTurnPage = lv_btn_create(scr, NULL); + lv_obj_set_event_cb_mks(buttonTurnPage, event_handler, ID_ACCE_DOWN, NULL, 0); + lv_btn_set_style(buttonTurnPage, LV_BTN_STYLE_REL, &style_para_back); + lv_btn_set_style(buttonTurnPage, LV_BTN_STYLE_PR, &style_para_back); + + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonPrintValue); + lv_group_add_obj(g, buttonRetraValue); + lv_group_add_obj(g, buttonTravelValue); + lv_group_add_obj(g, buttonXValue); + lv_group_add_obj(g, buttonTurnPage); + } + #endif } else { - buttonYText = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonYText, PARA_UI_POS_X, PARA_UI_POS_Y); /*Set its position*/ - lv_obj_set_size(buttonYText, PARA_UI_VALUE_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - lv_obj_set_event_cb(buttonYText, event_handler); - lv_btn_set_style(buttonYText, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonYText, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonYText, LV_LAYOUT_OFF); - labelYText = lv_label_create(buttonYText, NULL); /*Add a label to the button*/ - - buttonYValue = lv_imgbtn_create(scr, NULL); + labelYText = lv_label_create(scr, NULL); + lv_obj_set_style(labelYText, &tft_style_label_rel); + lv_obj_set_pos(labelYText, PARA_UI_POS_X, PARA_UI_POS_Y + 10); + lv_label_set_text(labelYText, machine_menu.Y_Acceleration); + + buttonYValue = lv_btn_create(scr, NULL); lv_obj_set_pos(buttonYValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y + PARA_UI_VALUE_V); - lv_obj_set_event_cb_mks(buttonYValue, event_handler, ID_ACCE_Y, "bmp_value_blank.bin", 0); - lv_imgbtn_set_src(buttonYValue, LV_BTN_STATE_REL, &bmp_para_bank); - lv_imgbtn_set_src(buttonYValue, LV_BTN_STATE_PR, &bmp_para_bank); - lv_imgbtn_set_style(buttonYValue, LV_BTN_STATE_PR, &style_para_value_pre); - lv_imgbtn_set_style(buttonYValue, LV_BTN_STATE_REL, &style_para_value_rel); - lv_btn_set_layout(buttonYValue, LV_LAYOUT_OFF); + lv_obj_set_size(buttonYValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonYValue, event_handler, ID_ACCE_Y, NULL, 0); + lv_btn_set_style(buttonYValue, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonYValue, LV_BTN_STYLE_PR, &style_para_value); labelYValue = lv_label_create(buttonYValue, NULL); line1 = lv_line_create(scr, NULL); lv_ex_line(line1, line_points[0]); - buttonZText = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonZText, PARA_UI_POS_X, PARA_UI_POS_Y * 2); /*Set its position*/ - lv_obj_set_size(buttonZText, PARA_UI_VALUE_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - lv_obj_set_event_cb(buttonZText, event_handler); - lv_btn_set_style(buttonZText, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonZText, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonZText, LV_LAYOUT_OFF); - labelZText = lv_label_create(buttonZText, NULL); /*Add a label to the button*/ + labelZText = lv_label_create(scr, NULL); + lv_obj_set_style(labelZText, &tft_style_label_rel); + lv_obj_set_pos(labelZText, PARA_UI_POS_X, PARA_UI_POS_Y * 2 + 10); + lv_label_set_text(labelZText, machine_menu.Z_Acceleration); - buttonZValue = lv_imgbtn_create(scr, NULL); + buttonZValue = lv_btn_create(scr, NULL); lv_obj_set_pos(buttonZValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 2 + PARA_UI_VALUE_V); - lv_obj_set_event_cb_mks(buttonZValue, event_handler, ID_ACCE_Z, "bmp_value_blank.bin", 0); - lv_imgbtn_set_src(buttonZValue, LV_BTN_STATE_REL, &bmp_para_bank); - lv_imgbtn_set_src(buttonZValue, LV_BTN_STATE_PR, &bmp_para_bank); - lv_imgbtn_set_style(buttonZValue, LV_BTN_STATE_PR, &style_para_value_pre); - lv_imgbtn_set_style(buttonZValue, LV_BTN_STATE_REL, &style_para_value_rel); - lv_btn_set_layout(buttonZValue, LV_LAYOUT_OFF); + lv_obj_set_size(buttonZValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); lv_obj_set_event_cb_mks(buttonYValue, event_handler, ID_ACCE_Y, NULL, 0); + lv_obj_set_event_cb_mks(buttonZValue, event_handler, ID_ACCE_Z, NULL, 0); + lv_btn_set_style(buttonZValue, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonZValue, LV_BTN_STYLE_PR, &style_para_value); labelZValue = lv_label_create(buttonZValue, NULL); + line2 = lv_line_create(scr, NULL); lv_ex_line(line2, line_points[1]); - buttonE0Text = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonE0Text, PARA_UI_POS_X, PARA_UI_POS_Y * 3); /*Set its position*/ - lv_obj_set_size(buttonE0Text, PARA_UI_VALUE_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - lv_obj_set_event_cb(buttonE0Text, event_handler); - lv_btn_set_style(buttonE0Text, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonE0Text, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonE0Text, LV_LAYOUT_OFF); - labelE0Text = lv_label_create(buttonE0Text, NULL); /*Add a label to the button*/ + labelE0Text = lv_label_create(scr, NULL); + lv_obj_set_style(labelE0Text, &tft_style_label_rel); + lv_obj_set_pos(labelE0Text, PARA_UI_POS_X, PARA_UI_POS_Y * 3 + 10); + lv_label_set_text(labelE0Text, machine_menu.E0_Acceleration); - buttonE0Value = lv_imgbtn_create(scr, NULL); + buttonE0Value = lv_btn_create(scr, NULL); lv_obj_set_pos(buttonE0Value, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 3 + PARA_UI_VALUE_V); - lv_obj_set_event_cb_mks(buttonE0Value, event_handler, ID_ACCE_E0, "bmp_value_blank.bin", 0); - lv_imgbtn_set_src(buttonE0Value, LV_BTN_STATE_REL, &bmp_para_bank); - lv_imgbtn_set_src(buttonE0Value, LV_BTN_STATE_PR, &bmp_para_bank); - lv_imgbtn_set_style(buttonE0Value, LV_BTN_STATE_PR, &style_para_value_pre); - lv_imgbtn_set_style(buttonE0Value, LV_BTN_STATE_REL, &style_para_value_rel); - lv_btn_set_layout(buttonE0Value, LV_LAYOUT_OFF); + lv_obj_set_size(buttonE0Value, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); lv_obj_set_event_cb_mks(buttonYValue, event_handler, ID_ACCE_Y, NULL, 0); + lv_obj_set_event_cb_mks(buttonE0Value, event_handler, ID_ACCE_E0, NULL, 0); + lv_btn_set_style(buttonE0Value, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonE0Value, LV_BTN_STYLE_PR, &style_para_value); labelE0Value = lv_label_create(buttonE0Value, NULL); + line3 = lv_line_create(scr, NULL); lv_ex_line(line3, line_points[2]); - buttonE1Text = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonE1Text, PARA_UI_POS_X, PARA_UI_POS_Y * 4); /*Set its position*/ - lv_obj_set_size(buttonE1Text, PARA_UI_VALUE_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - lv_obj_set_event_cb(buttonE1Text, event_handler); - lv_btn_set_style(buttonE1Text, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonE1Text, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonE1Text, LV_LAYOUT_OFF); - labelE1Text = lv_label_create(buttonE1Text, NULL); /*Add a label to the button*/ + labelE1Text = lv_label_create(scr, NULL); + lv_obj_set_style(labelE1Text, &tft_style_label_rel); + lv_obj_set_pos(labelE1Text, PARA_UI_POS_X, PARA_UI_POS_Y * 4 + 10); + lv_label_set_text(labelE1Text, machine_menu.E1_Acceleration); - buttonE1Value = lv_imgbtn_create(scr, NULL); + buttonE1Value = lv_btn_create(scr, NULL); lv_obj_set_pos(buttonE1Value, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 4 + PARA_UI_VALUE_V); - lv_obj_set_event_cb_mks(buttonE1Value, event_handler, ID_ACCE_E1, "bmp_value_blank.bin", 0); - lv_imgbtn_set_src(buttonE1Value, LV_BTN_STATE_REL, &bmp_para_bank); - lv_imgbtn_set_src(buttonE1Value, LV_BTN_STATE_PR, &bmp_para_bank); - lv_imgbtn_set_style(buttonE1Value, LV_BTN_STATE_PR, &style_para_value_pre); - lv_imgbtn_set_style(buttonE1Value, LV_BTN_STATE_REL, &style_para_value_rel); - lv_btn_set_layout(buttonE1Value, LV_LAYOUT_OFF); + lv_obj_set_size(buttonE1Value, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); lv_obj_set_event_cb_mks(buttonYValue, event_handler, ID_ACCE_Y, NULL, 0); + lv_obj_set_event_cb_mks(buttonE1Value, event_handler, ID_ACCE_E1, NULL, 0); + lv_btn_set_style(buttonE1Value, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonE1Value, LV_BTN_STYLE_PR, &style_para_value); labelE1Value = lv_label_create(buttonE1Value, NULL); + line4 = lv_line_create(scr, NULL); lv_ex_line(line4, line_points[3]); - buttonTurnPage = lv_imgbtn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonTurnPage, event_handler, ID_ACCE_UP, "bmp_back70x40.bin", 0); - lv_imgbtn_set_src(buttonTurnPage, LV_BTN_STATE_REL, &bmp_para_back); - lv_imgbtn_set_src(buttonTurnPage, LV_BTN_STATE_PR, &bmp_para_back); - lv_imgbtn_set_style(buttonTurnPage, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonTurnPage, LV_BTN_STATE_REL, &tft_style_label_rel); + buttonTurnPage = lv_btn_create(scr, NULL); + lv_obj_set_event_cb_mks(buttonTurnPage, event_handler, ID_ACCE_UP, NULL, 0); + //lv_imgbtn_set_src(buttonTurnPage, LV_BTN_STATE_REL, "F:/bmp_back70x40.bin"); + //lv_imgbtn_set_src(buttonTurnPage, LV_BTN_STATE_PR, "F:/bmp_back70x40.bin"); + //lv_imgbtn_set_style(buttonTurnPage, LV_BTN_STATE_PR, &tft_style_label_pre); + //lv_imgbtn_set_style(buttonTurnPage, LV_BTN_STATE_REL, &tft_style_label_rel); + lv_btn_set_style(buttonTurnPage, LV_BTN_STYLE_REL, &style_para_back); + lv_btn_set_style(buttonTurnPage, LV_BTN_STYLE_PR, &style_para_back); + + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonYValue); + lv_group_add_obj(g, buttonZValue); + lv_group_add_obj(g, buttonE0Value); + lv_group_add_obj(g, buttonE1Value); + lv_group_add_obj(g, buttonTurnPage); + } + #endif } + //lv_obj_set_pos(buttonTurnPage, PARA_UI_TURN_PAGE_POS_X, PARA_UI_TURN_PAGE_POS_Y); + //lv_btn_set_layout(buttonTurnPage, LV_LAYOUT_OFF); + //labelTurnPage = lv_label_create(buttonTurnPage, NULL); lv_obj_set_pos(buttonTurnPage, PARA_UI_TURN_PAGE_POS_X, PARA_UI_TURN_PAGE_POS_Y); - lv_btn_set_layout(buttonTurnPage, LV_LAYOUT_OFF); + lv_obj_set_size(buttonTurnPage, PARA_UI_BACK_BTN_X_SIZE, PARA_UI_BACK_BTN_Y_SIZE); labelTurnPage = lv_label_create(buttonTurnPage, NULL); - buttonBack = lv_imgbtn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_ACCE_RETURN, "bmp_back70x40.bin", 0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, &bmp_para_back); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, &bmp_para_back); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); - + buttonBack = lv_btn_create(scr, NULL); + lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_ACCE_RETURN, NULL, 0); + //lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_back70x40.bin"); + //lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_back70x40.bin"); + //lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); + //lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); + lv_btn_set_style(buttonBack, LV_BTN_STYLE_REL, &style_para_back); + lv_btn_set_style(buttonBack, LV_BTN_STYLE_PR, &style_para_back); lv_obj_set_pos(buttonBack, PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y); - lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); + lv_obj_set_size(buttonBack, PARA_UI_BACK_BTN_X_SIZE, PARA_UI_BACK_BTN_Y_SIZE); label_Back = lv_label_create(buttonBack, NULL); + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonBack); + #endif + + //lv_obj_set_pos(buttonBack, PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y); + //lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); if (gCfgItems.multiple_language != 0) { if (uiCfg.para_ui_page != 1) { - lv_label_set_text(labelPrintText, machine_menu.PrintAcceleration); - lv_obj_align(labelPrintText, buttonPrintText, LV_ALIGN_IN_LEFT_MID, 0, 0); - - lv_label_set_text(labelRetraText, machine_menu.RetractAcceleration); - lv_obj_align(labelRetraText, buttonRetraText, LV_ALIGN_IN_LEFT_MID, 0, 0); - - lv_label_set_text(labelTravelText, machine_menu.TravelAcceleration); - lv_obj_align(labelTravelText, buttonTravelText, LV_ALIGN_IN_LEFT_MID, 0, 0); - - lv_label_set_text(labelXText, machine_menu.X_Acceleration); - lv_obj_align(labelXText, buttonXText, LV_ALIGN_IN_LEFT_MID, 0, 0); lv_label_set_text(labelTurnPage, machine_menu.next); lv_obj_align(labelTurnPage, buttonTurnPage, LV_ALIGN_CENTER, 0, 0); @@ -438,17 +410,6 @@ void lv_draw_acceleration_settings(void) { lv_obj_align(labelXValue, buttonXValue, LV_ALIGN_CENTER, 0, 0); } else { - lv_label_set_text(labelYText, machine_menu.Y_Acceleration); - lv_obj_align(labelYText, buttonYText, LV_ALIGN_IN_LEFT_MID, 0, 0); - - lv_label_set_text(labelZText, machine_menu.Z_Acceleration); - lv_obj_align(labelZText, buttonZText, LV_ALIGN_IN_LEFT_MID, 0, 0); - - lv_label_set_text(labelE0Text, machine_menu.E0_Acceleration); - lv_obj_align(labelE0Text, buttonE0Text, LV_ALIGN_IN_LEFT_MID, 0, 0); - - lv_label_set_text(labelE1Text, machine_menu.E1_Acceleration); - lv_obj_align(labelE1Text, buttonE1Text, LV_ALIGN_IN_LEFT_MID, 0, 0); lv_label_set_text(labelTurnPage, machine_menu.previous); lv_obj_align(labelTurnPage, buttonTurnPage, LV_ALIGN_CENTER, 0, 0); @@ -478,6 +439,11 @@ void lv_draw_acceleration_settings(void) { } } -void lv_clear_acceleration_settings() { lv_obj_del(scr); } +void lv_clear_acceleration_settings() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} #endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_acceleration_settings.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_acceleration_settings.h index b5b62fdc4c..6ab49713c9 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_acceleration_settings.h +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_acceleration_settings.h @@ -22,12 +22,12 @@ #pragma once #ifdef __cplusplus -extern "C" { /* C-declarations for C++ */ + extern "C" { /* C-declarations for C++ */ #endif extern void lv_draw_acceleration_settings(void); extern void lv_clear_acceleration_settings(); #ifdef __cplusplus -} /* C-declarations for C++ */ + } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_advance_settings.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_advance_settings.cpp index 7d3eab436b..5b1b241716 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_advance_settings.cpp +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_advance_settings.cpp @@ -28,11 +28,18 @@ #include "../../../../MarlinCore.h" +extern lv_group_t * g; static lv_obj_t * scr; -#define ID_ADVANCE_RETURN 1 -#define ID_PAUSE_POS 2 -#define ID_PAUSE_POS_ARROW 3 +#define ID_ADVANCE_RETURN 1 +#define ID_PAUSE_POS 2 +#define ID_PAUSE_POS_ARROW 3 +#define ID_WIFI_PARA 4 +#define ID_WIFI_PARA_ARROW 5 +#define ID_FILAMENT_SETTINGS 6 +#define ID_FILAMENT_SETTINGS_ARROW 7 +#define ID_ENCODER_SETTINGS 8 +#define ID_ENCODER_SETTINGS_ARROW 9 static void event_handler(lv_obj_t * obj, lv_event_t event) { switch (obj->mks_obj_id) { @@ -63,13 +70,79 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { lv_draw_pause_position(); } break; + case ID_FILAMENT_SETTINGS: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + lv_clear_advance_settings(); + lv_draw_filament_settings(); + } + break; + case ID_FILAMENT_SETTINGS_ARROW: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + lv_clear_advance_settings(); + lv_draw_filament_settings(); + } + break; + #if ENABLED(USE_WIFI_FUNCTION) + case ID_WIFI_PARA: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + lv_clear_advance_settings(); + lv_draw_wifi_settings(); + } + break; + case ID_WIFI_PARA_ARROW: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + lv_clear_advance_settings(); + lv_draw_wifi_settings(); + } + break; + #endif + #if HAS_ROTARY_ENCODER + case ID_ENCODER_SETTINGS: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + lv_clear_advance_settings(); + lv_draw_encoder_settings(); + } + break; + case ID_ENCODER_SETTINGS_ARROW: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + lv_clear_advance_settings(); + lv_draw_encoder_settings(); + } + break; + #endif } } void lv_draw_advance_settings(void) { lv_obj_t *buttonBack, *label_Back; lv_obj_t *buttonPausePos, *labelPausePos, *buttonPausePosNarrow; - lv_obj_t * line1; + lv_obj_t *buttonFilamentSettings, *labelFilamentSettings, *buttonFilamentSettingsNarrow; + lv_obj_t * line1,* line2; + #if ENABLED(USE_WIFI_FUNCTION) + lv_obj_t *buttonWifiSet,*labelWifiSet,*buttonWifiSetNarrow; + #endif + #if HAS_ROTARY_ENCODER + lv_obj_t *buttonEcoder,*labelEcoder,*buttonEcoderNarrow; + #endif + if (disp_state_stack._disp_state[disp_state_stack._disp_index] != ADVANCED_UI) { disp_state_stack._disp_index++; disp_state_stack._disp_state[disp_state_stack._disp_index] = ADVANCED_UI; @@ -89,24 +162,24 @@ void lv_draw_advance_settings(void) { lv_refr_now(lv_refr_get_disp_refreshing()); - LV_IMG_DECLARE(bmp_para_back); - LV_IMG_DECLARE(bmp_para_arrow); - - buttonPausePos = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonPausePos, PARA_UI_POS_X, PARA_UI_POS_Y); /*Set its position*/ - lv_obj_set_size(buttonPausePos, PARA_UI_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ + buttonPausePos = lv_btn_create(scr, NULL); + lv_obj_set_pos(buttonPausePos, PARA_UI_POS_X, PARA_UI_POS_Y); + lv_obj_set_size(buttonPausePos, PARA_UI_SIZE_X, PARA_UI_SIZE_Y); //lv_obj_set_event_cb(buttonMachine, event_handler); lv_obj_set_event_cb_mks(buttonPausePos, event_handler, ID_PAUSE_POS, NULL, 0); - lv_btn_set_style(buttonPausePos, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonPausePos, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ + lv_btn_set_style(buttonPausePos, LV_BTN_STYLE_REL, &tft_style_label_rel); + lv_btn_set_style(buttonPausePos, LV_BTN_STYLE_PR, &tft_style_label_pre); lv_btn_set_layout(buttonPausePos, LV_LAYOUT_OFF); - labelPausePos = lv_label_create(buttonPausePos, NULL); /*Add a label to the button*/ + labelPausePos = lv_label_create(buttonPausePos, NULL); + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonPausePos); + #endif buttonPausePosNarrow = lv_imgbtn_create(scr, NULL); lv_obj_set_pos(buttonPausePosNarrow, PARA_UI_POS_X + PARA_UI_SIZE_X, PARA_UI_POS_Y + PARA_UI_ARROW_V); - lv_obj_set_event_cb_mks(buttonPausePosNarrow, event_handler, ID_PAUSE_POS_ARROW, "bmp_arrow.bin", 0); - lv_imgbtn_set_src(buttonPausePosNarrow, LV_BTN_STATE_REL, &bmp_para_arrow); - lv_imgbtn_set_src(buttonPausePosNarrow, LV_BTN_STATE_PR, &bmp_para_arrow); + lv_obj_set_event_cb_mks(buttonPausePosNarrow, event_handler, ID_PAUSE_POS_ARROW, NULL, 0); + lv_imgbtn_set_src(buttonPausePosNarrow, LV_BTN_STATE_REL, "F:/bmp_arrow.bin"); + lv_imgbtn_set_src(buttonPausePosNarrow, LV_BTN_STATE_PR, "F:/bmp_arrow.bin"); lv_imgbtn_set_style(buttonPausePosNarrow, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonPausePosNarrow, LV_BTN_STATE_REL, &tft_style_label_rel); lv_btn_set_layout(buttonPausePosNarrow, LV_LAYOUT_OFF); @@ -114,13 +187,117 @@ void lv_draw_advance_settings(void) { line1 = lv_line_create(lv_scr_act(), NULL); lv_ex_line(line1, line_points[0]); + buttonFilamentSettings = lv_btn_create(scr, NULL); + lv_obj_set_pos(buttonFilamentSettings, PARA_UI_POS_X, PARA_UI_POS_Y*2); + lv_obj_set_size(buttonFilamentSettings, PARA_UI_SIZE_X, PARA_UI_SIZE_Y); + lv_obj_set_event_cb_mks(buttonFilamentSettings, event_handler, ID_FILAMENT_SETTINGS, NULL, 0); + lv_btn_set_style(buttonFilamentSettings, LV_BTN_STYLE_REL, &tft_style_label_rel); + lv_btn_set_style(buttonFilamentSettings, LV_BTN_STYLE_PR, &tft_style_label_pre); + lv_btn_set_layout(buttonFilamentSettings, LV_LAYOUT_OFF); + labelFilamentSettings = lv_label_create(buttonFilamentSettings, NULL); + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonFilamentSettings); + #endif + + buttonFilamentSettingsNarrow = lv_imgbtn_create(scr, NULL); + lv_obj_set_pos(buttonFilamentSettingsNarrow, PARA_UI_POS_X + PARA_UI_SIZE_X, PARA_UI_POS_Y*2 + PARA_UI_ARROW_V); + lv_obj_set_event_cb_mks(buttonFilamentSettingsNarrow, event_handler, ID_FILAMENT_SETTINGS_ARROW, NULL, 0); + lv_imgbtn_set_src(buttonFilamentSettingsNarrow, LV_BTN_STATE_REL, "F:/bmp_arrow.bin"); + lv_imgbtn_set_src(buttonFilamentSettingsNarrow, LV_BTN_STATE_PR, "F:/bmp_arrow.bin"); + lv_imgbtn_set_style(buttonFilamentSettingsNarrow, LV_BTN_STATE_PR, &tft_style_label_pre); + lv_imgbtn_set_style(buttonFilamentSettingsNarrow, LV_BTN_STATE_REL, &tft_style_label_rel); + lv_btn_set_layout(buttonFilamentSettingsNarrow, LV_LAYOUT_OFF); + + line2 = lv_line_create(lv_scr_act(), NULL); + lv_ex_line(line2, line_points[1]); + + #if ENABLED(USE_WIFI_FUNCTION) + + buttonWifiSet = lv_btn_create(scr, NULL); /*Add a button the current screen*/ + lv_obj_set_pos(buttonWifiSet, PARA_UI_POS_X,PARA_UI_POS_Y*3); + lv_obj_set_size(buttonWifiSet, PARA_UI_SIZE_X,PARA_UI_SIZE_Y); + lv_obj_set_event_cb_mks(buttonWifiSet, event_handler,ID_WIFI_PARA,NULL,0); + lv_btn_set_style(buttonWifiSet, LV_BTN_STYLE_REL, &tft_style_label_rel); + lv_btn_set_style(buttonWifiSet, LV_BTN_STYLE_PR, &tft_style_label_pre); + lv_btn_set_layout(buttonWifiSet, LV_LAYOUT_OFF); + labelWifiSet = lv_label_create(buttonWifiSet, NULL); + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonWifiSet); + #endif + + buttonWifiSetNarrow = lv_imgbtn_create(scr, NULL); + lv_obj_set_pos(buttonWifiSetNarrow,PARA_UI_POS_X+PARA_UI_SIZE_X,PARA_UI_POS_Y*3+PARA_UI_ARROW_V); + lv_obj_set_event_cb_mks(buttonWifiSetNarrow, event_handler,ID_WIFI_PARA_ARROW, NULL,0); + lv_imgbtn_set_src(buttonWifiSetNarrow, LV_BTN_STATE_REL, "F:/bmp_arrow.bin"); + lv_imgbtn_set_src(buttonWifiSetNarrow, LV_BTN_STATE_PR, "F:/bmp_arrow.bin"); + lv_imgbtn_set_style(buttonWifiSetNarrow, LV_BTN_STATE_PR, &tft_style_label_pre); + lv_imgbtn_set_style(buttonWifiSetNarrow, LV_BTN_STATE_REL, &tft_style_label_rel); + lv_btn_set_layout(buttonWifiSetNarrow, LV_LAYOUT_OFF); + + lv_obj_t * line3 = lv_line_create(scr, NULL); + lv_ex_line(line3,line_points[2]); + + #if HAS_ROTARY_ENCODER + buttonEcoder = lv_btn_create(scr, NULL); /*Add a button the current screen*/ + lv_obj_set_pos(buttonEcoder, PARA_UI_POS_X,PARA_UI_POS_Y*4); + lv_obj_set_size(buttonEcoder, PARA_UI_SIZE_X,PARA_UI_SIZE_Y); + lv_obj_set_event_cb_mks(buttonEcoder, event_handler,ID_ENCODER_SETTINGS,NULL,0); + lv_btn_set_style(buttonEcoder, LV_BTN_STYLE_REL, &tft_style_label_rel); + lv_btn_set_style(buttonEcoder, LV_BTN_STYLE_PR, &tft_style_label_pre); + lv_btn_set_layout(buttonEcoder, LV_LAYOUT_OFF); + labelEcoder = lv_label_create(buttonEcoder, NULL); + + if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonEcoder); + + buttonEcoderNarrow = lv_imgbtn_create(scr, NULL); + lv_obj_set_pos(buttonEcoderNarrow,PARA_UI_POS_X+PARA_UI_SIZE_X,PARA_UI_POS_Y*4+PARA_UI_ARROW_V); + lv_obj_set_event_cb_mks(buttonEcoderNarrow, event_handler,ID_ENCODER_SETTINGS_ARROW, NULL,0); + lv_imgbtn_set_src(buttonEcoderNarrow, LV_BTN_STATE_REL, "F:/bmp_arrow.bin"); + lv_imgbtn_set_src(buttonEcoderNarrow, LV_BTN_STATE_PR, "F:/bmp_arrow.bin"); + lv_imgbtn_set_style(buttonEcoderNarrow, LV_BTN_STATE_PR, &tft_style_label_pre); + lv_imgbtn_set_style(buttonEcoderNarrow, LV_BTN_STATE_REL, &tft_style_label_rel); + lv_btn_set_layout(buttonEcoderNarrow, LV_LAYOUT_OFF); + + lv_obj_t * line4 = lv_line_create(scr, NULL); + lv_ex_line(line4,line_points[3]); + #endif + + #elif HAS_ROTARY_ENCODER + buttonEcoder = lv_btn_create(scr, NULL); /*Add a button the current screen*/ + lv_obj_set_pos(buttonEcoder, PARA_UI_POS_X,PARA_UI_POS_Y*3); + lv_obj_set_size(buttonEcoder, PARA_UI_SIZE_X,PARA_UI_SIZE_Y); + lv_obj_set_event_cb_mks(buttonEcoder, event_handler,ID_ENCODER_SETTINGS,NULL,0); + lv_btn_set_style(buttonEcoder, LV_BTN_STYLE_REL, &tft_style_label_rel); + lv_btn_set_style(buttonEcoder, LV_BTN_STYLE_PR, &tft_style_label_pre); + lv_btn_set_layout(buttonEcoder, LV_LAYOUT_OFF); + labelEcoder = lv_label_create(buttonEcoder, NULL); + + if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonEcoder); + + buttonEcoderNarrow = lv_imgbtn_create(scr, NULL); + lv_obj_set_pos(buttonEcoderNarrow,PARA_UI_POS_X+PARA_UI_SIZE_X,PARA_UI_POS_Y*3+PARA_UI_ARROW_V); + lv_obj_set_event_cb_mks(buttonEcoderNarrow, event_handler,ID_ENCODER_SETTINGS_ARROW, NULL,0); + lv_imgbtn_set_src(buttonEcoderNarrow, LV_BTN_STATE_REL, "F:/bmp_arrow.bin"); + lv_imgbtn_set_src(buttonEcoderNarrow, LV_BTN_STATE_PR, "F:/bmp_arrow.bin"); + lv_imgbtn_set_style(buttonEcoderNarrow, LV_BTN_STATE_PR, &tft_style_label_pre); + lv_imgbtn_set_style(buttonEcoderNarrow, LV_BTN_STATE_REL, &tft_style_label_rel); + lv_btn_set_layout(buttonEcoderNarrow, LV_LAYOUT_OFF); + + lv_obj_t * line3 = lv_line_create(scr, NULL); + lv_ex_line(line3,line_points[2]); + #endif + buttonBack = lv_imgbtn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_ADVANCE_RETURN, "bmp_back70x40.bin", 0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, &bmp_para_back); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, &bmp_para_back); + lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_ADVANCE_RETURN, NULL, 0); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_back70x40.bin"); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_back70x40.bin"); lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonBack); + #endif + lv_obj_set_pos(buttonBack, PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y); lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); label_Back = lv_label_create(buttonBack, NULL); @@ -131,10 +308,27 @@ void lv_draw_advance_settings(void) { lv_label_set_text(labelPausePos, machine_menu.PausePosition); lv_obj_align(labelPausePos, buttonPausePos, LV_ALIGN_IN_LEFT_MID, 0, 0); + + lv_label_set_text(labelFilamentSettings, machine_menu.FilamentConf); + lv_obj_align(labelFilamentSettings, buttonFilamentSettings, LV_ALIGN_IN_LEFT_MID, 0, 0); + + #if ENABLED(USE_WIFI_FUNCTION) + lv_label_set_text(labelWifiSet, machine_menu.WifiSettings); + lv_obj_align(labelWifiSet, buttonWifiSet, LV_ALIGN_IN_LEFT_MID,0, 0); + #endif + #if HAS_ROTARY_ENCODER + lv_label_set_text(labelEcoder, machine_menu.EncoderSettings); + lv_obj_align(labelEcoder, buttonEcoder, LV_ALIGN_IN_LEFT_MID,0, 0); + #endif } } -void lv_clear_advance_settings() { lv_obj_del(scr); } +void lv_clear_advance_settings() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} #endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_advance_settings.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_advance_settings.h index bfd76125bb..84e4a4d4cf 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_advance_settings.h +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_advance_settings.h @@ -22,12 +22,12 @@ #pragma once #ifdef __cplusplus -extern "C" { /* C-declarations for C++ */ + extern "C" { /* C-declarations for C++ */ #endif extern void lv_draw_advance_settings(void); extern void lv_clear_advance_settings(); #ifdef __cplusplus -} /* C-declarations for C++ */ + } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_auto_level_offset_settings.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_auto_level_offset_settings.cpp new file mode 100644 index 0000000000..bb6b45aebe --- /dev/null +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_auto_level_offset_settings.cpp @@ -0,0 +1,203 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../../inc/MarlinConfigPre.h" + +#if BOTH(HAS_TFT_LVGL_UI, HAS_BED_PROBE) + +#include "lv_conf.h" +#include "draw_ui.h" + +#include "../../../../MarlinCore.h" +#include "../../../../module/planner.h" +#include "../../../../module/probe.h" + +extern lv_group_t * g; +static lv_obj_t * scr; + +#define ID_OFFSET_RETURN 1 +#define ID_OFFSET_X 2 +#define ID_OFFSET_Y 3 +#define ID_OFFSET_Z 4 + +static void event_handler(lv_obj_t * obj, lv_event_t event) { + switch (obj->mks_obj_id) { + case ID_OFFSET_RETURN: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + lv_clear_auto_level_offset_settings(); + draw_return_ui(); + } + break; + case ID_OFFSET_X: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + value = x_offset; + lv_clear_auto_level_offset_settings(); + lv_draw_number_key(); + } + break; + case ID_OFFSET_Y: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + value = y_offset; + lv_clear_auto_level_offset_settings(); + lv_draw_number_key(); + } + break; + case ID_OFFSET_Z: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + value = z_offset; + lv_clear_auto_level_offset_settings(); + lv_draw_number_key(); + } + break; + } +} + +void lv_draw_auto_level_offset_settings(void) { + lv_obj_t *buttonBack = NULL, *label_Back = NULL; + lv_obj_t *labelXText = NULL, *buttonXValue = NULL, *labelXValue = NULL; + lv_obj_t *labelYText = NULL, *buttonYValue = NULL, *labelYValue = NULL; + lv_obj_t *labelZText = NULL, *buttonZValue = NULL, *labelZValue = NULL; + lv_obj_t * line1 = NULL, * line2 = NULL, * line3 = NULL; + if (disp_state_stack._disp_state[disp_state_stack._disp_index] != NOZZLE_PROBE_OFFSET_UI) { + disp_state_stack._disp_index++; + disp_state_stack._disp_state[disp_state_stack._disp_index] = NOZZLE_PROBE_OFFSET_UI; + } + disp_state = NOZZLE_PROBE_OFFSET_UI; + + scr = lv_obj_create(NULL, NULL); + + lv_obj_set_style(scr, &tft_style_scr); + lv_scr_load(scr); + lv_obj_clean(scr); + + lv_obj_t * title = lv_label_create(scr, NULL); + lv_obj_set_style(title, &tft_style_label_rel); + lv_obj_set_pos(title, TITLE_XPOS, TITLE_YPOS); + lv_label_set_text(title, machine_menu.OffsetConfTitle); + + lv_refr_now(lv_refr_get_disp_refreshing()); + + labelXText = lv_label_create(scr, NULL); + lv_obj_set_style(labelXText, &tft_style_label_rel); + lv_obj_set_pos(labelXText, PARA_UI_POS_X, PARA_UI_POS_Y + 10); + lv_label_set_text(labelXText, machine_menu.Xoffset); + + buttonXValue = lv_btn_create(scr, NULL); + lv_obj_set_pos(buttonXValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y + PARA_UI_VALUE_V_2); + lv_obj_set_size(buttonXValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonXValue, event_handler, ID_OFFSET_X, NULL, 0); + lv_btn_set_style(buttonXValue, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonXValue, LV_BTN_STYLE_PR, &style_para_value); + labelXValue = lv_label_create(buttonXValue, NULL); + + line1 = lv_line_create(scr, NULL); + lv_ex_line(line1, line_points[0]); + + labelYText = lv_label_create(scr, NULL); + lv_obj_set_style(labelYText, &tft_style_label_rel); + lv_obj_set_pos(labelYText, PARA_UI_POS_X, PARA_UI_POS_Y * 2 + 10); + lv_label_set_text(labelYText, machine_menu.Yoffset); + + buttonYValue = lv_btn_create(scr, NULL); + lv_obj_set_pos(buttonYValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 2 + PARA_UI_VALUE_V_2); + lv_obj_set_size(buttonYValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonYValue, event_handler, ID_OFFSET_Y, NULL, 0); + lv_btn_set_style(buttonYValue, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonYValue, LV_BTN_STYLE_PR, &style_para_value); + labelYValue = lv_label_create(buttonYValue, NULL); + + line2 = lv_line_create(scr, NULL); + lv_ex_line(line2, line_points[1]); + + labelZText = lv_label_create(scr, NULL); + lv_obj_set_style(labelZText, &tft_style_label_rel); + lv_obj_set_pos(labelZText, PARA_UI_POS_X, PARA_UI_POS_Y * 3 + 10); + lv_label_set_text(labelZText, machine_menu.Zoffset); + + buttonZValue = lv_btn_create(scr, NULL); + lv_obj_set_pos(buttonZValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 3 + PARA_UI_VALUE_V_2); + lv_obj_set_size(buttonZValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonZValue, event_handler, ID_OFFSET_Z, NULL, 0); + lv_btn_set_style(buttonZValue, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonZValue, LV_BTN_STYLE_PR, &style_para_value); + labelZValue = lv_label_create(buttonZValue, NULL); + + line3 = lv_line_create(scr, NULL); + lv_ex_line(line3, line_points[2]); + + buttonBack = lv_btn_create(scr, NULL); + lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_OFFSET_RETURN, NULL, 0); + lv_btn_set_style(buttonBack, LV_BTN_STYLE_REL, &style_para_back); + lv_btn_set_style(buttonBack, LV_BTN_STYLE_PR, &style_para_back); + lv_obj_set_pos(buttonBack, PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y); + lv_obj_set_size(buttonBack, PARA_UI_BACK_BTN_X_SIZE, PARA_UI_BACK_BTN_Y_SIZE); + label_Back = lv_label_create(buttonBack, NULL); + + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonXValue); + lv_group_add_obj(g, buttonYValue); + lv_group_add_obj(g, buttonZValue); + lv_group_add_obj(g, buttonBack); + } + #endif + + if (gCfgItems.multiple_language != 0) { + ZERO(public_buf_l); + sprintf_P(public_buf_l, PSTR("%.1f"), TERN(HAS_PROBE_XY_OFFSET, probe.offset.x, 0)); + lv_label_set_text(labelXValue, public_buf_l); + lv_obj_align(labelXValue, buttonXValue, LV_ALIGN_CENTER, 0, 0); + + ZERO(public_buf_l); + sprintf_P(public_buf_l, PSTR("%.1f"), TERN(HAS_PROBE_XY_OFFSET, probe.offset.y, 0)); + lv_label_set_text(labelYValue, public_buf_l); + lv_obj_align(labelYValue, buttonYValue, LV_ALIGN_CENTER, 0, 0); + + ZERO(public_buf_l); + sprintf_P(public_buf_l, PSTR("%.1f"), probe.offset.z); + lv_label_set_text(labelZValue, public_buf_l); + lv_obj_align(labelZValue, buttonZValue, LV_ALIGN_CENTER, 0, 0); + + lv_label_set_text(label_Back, common_menu.text_back); + lv_obj_align(label_Back, buttonBack, LV_ALIGN_CENTER, 0, 0); + } +} + +void lv_clear_auto_level_offset_settings() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // HAS_TFT_LVGL_UI && HAS_BED_PROBE diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_auto_level_offset_settings.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_auto_level_offset_settings.h new file mode 100644 index 0000000000..688cd205d0 --- /dev/null +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_auto_level_offset_settings.h @@ -0,0 +1,33 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#ifdef __cplusplus + extern "C" { /* C-declarations for C++ */ +#endif + +extern void lv_draw_auto_level_offset_settings(void); +extern void lv_clear_auto_level_offset_settings(); + +#ifdef __cplusplus + } /* C-declarations for C++ */ +#endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_baby_stepping.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_baby_stepping.cpp new file mode 100644 index 0000000000..70564c036c --- /dev/null +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_baby_stepping.cpp @@ -0,0 +1,352 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "lv_conf.h" +#include "draw_ui.h" + +#include "../../../../MarlinCore.h" +#include "../../../../gcode/queue.h" +#include "../../../../gcode/gcode.h" + +#if HAS_BED_PROBE + #include "../../../../module/probe.h" +#endif + +extern lv_group_t * g; +static lv_obj_t * scr; + +static lv_obj_t *labelV, *buttonV, * zOffsetText; + +#define ID_BABY_STEP_X_P 1 +#define ID_BABY_STEP_X_N 2 +#define ID_BABY_STEP_Y_P 3 +#define ID_BABY_STEP_Y_N 4 +#define ID_BABY_STEP_Z_P 5 +#define ID_BABY_STEP_Z_N 6 +#define ID_BABY_STEP_DIST 7 +#define ID_BABY_STEP_RETURN 8 + +static float babystep_dist=0.01; +static uint8_t has_adjust_z = 0; + +static void event_handler(lv_obj_t * obj, lv_event_t event) { + char baby_buf[30]={0}; + switch (obj->mks_obj_id) { + case ID_BABY_STEP_X_P: + if (event == LV_EVENT_CLICKED) { + // nothing to do + } + else if (event == LV_EVENT_RELEASED) { + ZERO(baby_buf); + sprintf_P(baby_buf, PSTR("M290 X%.3f"),babystep_dist); + gcode.process_subcommands_now_P(PSTR(baby_buf)); + has_adjust_z = 1; + } + break; + case ID_BABY_STEP_X_N: + if (event == LV_EVENT_CLICKED) { + // nothing to do + } + else if (event == LV_EVENT_RELEASED) { + ZERO(baby_buf); + sprintf_P(baby_buf, PSTR("M290 X%.3f"),((float)0 - babystep_dist)); + gcode.process_subcommands_now_P(PSTR(baby_buf)); + has_adjust_z = 1; + } + break; + case ID_BABY_STEP_Y_P: + if (event == LV_EVENT_CLICKED) { + // nothing to do + } + else if (event == LV_EVENT_RELEASED) { + ZERO(baby_buf); + sprintf_P(baby_buf, PSTR("M290 Y%.3f"), babystep_dist); + gcode.process_subcommands_now_P(PSTR(baby_buf)); + has_adjust_z = 1; + } + break; + case ID_BABY_STEP_Y_N: + if (event == LV_EVENT_CLICKED) { + // nothing to do + } + else if (event == LV_EVENT_RELEASED) { + ZERO(baby_buf); + sprintf_P(baby_buf, PSTR("M290 Y%.3f"),((float)0 - babystep_dist)); + gcode.process_subcommands_now_P(PSTR(baby_buf)); + has_adjust_z = 1; + } + break; + case ID_BABY_STEP_Z_P: + if (event == LV_EVENT_CLICKED) { + // nothing to do + } + else if (event == LV_EVENT_RELEASED) { + ZERO(baby_buf); + sprintf_P(baby_buf, PSTR("M290 Z%.3f"), babystep_dist); + gcode.process_subcommands_now_P(PSTR(baby_buf)); + has_adjust_z = 1; + } + break; + case ID_BABY_STEP_Z_N: + if (event == LV_EVENT_CLICKED) { + // nothing to do + } + else if (event == LV_EVENT_RELEASED) { + ZERO(baby_buf); + sprintf_P(baby_buf, PSTR("M290 Z%.3f"),((float)0 - babystep_dist)); + gcode.process_subcommands_now_P(PSTR(baby_buf)); + has_adjust_z = 1; + } + break; + case ID_BABY_STEP_DIST: + if (event == LV_EVENT_CLICKED) { + // nothing to do + } + else if (event == LV_EVENT_RELEASED) { + if (abs((int)(100 * babystep_dist)) == 1) + babystep_dist = 0.05; + else if (abs((int)(100 * babystep_dist)) == 5) + babystep_dist = 0.1; + else + babystep_dist = 0.01; + disp_baby_step_dist(); + } + + break; + case ID_BABY_STEP_RETURN: + if (event == LV_EVENT_CLICKED) { + // nothing to do + } + else if (event == LV_EVENT_RELEASED) { + if (has_adjust_z == 1) { + gcode.process_subcommands_now_P(PSTR("M500")); + has_adjust_z = 0; + } + clear_cur_ui(); + draw_return_ui(); + } + break; + } +} + +void lv_draw_baby_stepping(void) { + lv_obj_t *buttonXI, *buttonXD, *buttonYI, *buttonYD, *buttonZI, *buttonZD, *buttonBack; + + if (disp_state_stack._disp_state[disp_state_stack._disp_index] != BABY_STEP_UI) { + disp_state_stack._disp_index++; + disp_state_stack._disp_state[disp_state_stack._disp_index] = BABY_STEP_UI; + } + disp_state = BABY_STEP_UI; + + scr = lv_obj_create(NULL, NULL); + + lv_obj_set_style(scr, &tft_style_scr); + lv_scr_load(scr); + lv_obj_clean(scr); + + lv_obj_t * title = lv_label_create(scr, NULL); + lv_obj_set_style(title, &tft_style_label_rel); + lv_obj_set_pos(title, TITLE_XPOS, TITLE_YPOS); + lv_label_set_text(title, creat_title_text()); + + lv_refr_now(lv_refr_get_disp_refreshing()); + + // Create an Image button + buttonXI = lv_imgbtn_create(scr, NULL); + buttonXD = lv_imgbtn_create(scr, NULL); + buttonYI = lv_imgbtn_create(scr, NULL); + buttonYD = lv_imgbtn_create(scr, NULL); + buttonZI = lv_imgbtn_create(scr, NULL); + buttonZD = lv_imgbtn_create(scr, NULL); + buttonV = lv_imgbtn_create(scr, NULL); + buttonBack = lv_imgbtn_create(scr, NULL); + + lv_obj_set_event_cb_mks(buttonXI, event_handler, ID_BABY_STEP_X_P, NULL, 0); + lv_imgbtn_set_src(buttonXI, LV_BTN_STATE_REL, "F:/bmp_xAdd.bin"); + lv_imgbtn_set_src(buttonXI, LV_BTN_STATE_PR, "F:/bmp_xAdd.bin"); + lv_imgbtn_set_style(buttonXI, LV_BTN_STATE_PR, &tft_style_label_pre); + lv_imgbtn_set_style(buttonXI, LV_BTN_STATE_REL, &tft_style_label_rel); + + #if 1 + lv_obj_set_event_cb_mks(buttonXD, event_handler, ID_BABY_STEP_X_N, NULL, 0); + lv_imgbtn_set_src(buttonXD, LV_BTN_STATE_REL, "F:/bmp_xDec.bin"); + lv_imgbtn_set_src(buttonXD, LV_BTN_STATE_PR, "F:/bmp_xDec.bin"); + lv_imgbtn_set_style(buttonXD, LV_BTN_STATE_PR, &tft_style_label_pre); + lv_imgbtn_set_style(buttonXD, LV_BTN_STATE_REL, &tft_style_label_rel); + + lv_obj_set_event_cb_mks(buttonYI, event_handler, ID_BABY_STEP_Y_P, NULL, 0); + lv_imgbtn_set_src(buttonYI, LV_BTN_STATE_REL, "F:/bmp_yAdd.bin"); + lv_imgbtn_set_src(buttonYI, LV_BTN_STATE_PR, "F:/bmp_yAdd.bin"); + lv_imgbtn_set_style(buttonYI, LV_BTN_STATE_PR, &tft_style_label_pre); + lv_imgbtn_set_style(buttonYI, LV_BTN_STATE_REL, &tft_style_label_rel); + + lv_obj_set_event_cb_mks(buttonYD, event_handler, ID_BABY_STEP_Y_N, NULL, 0); + lv_imgbtn_set_src(buttonYD, LV_BTN_STATE_REL, "F:/bmp_yDec.bin"); + lv_imgbtn_set_src(buttonYD, LV_BTN_STATE_PR, "F:/bmp_yDec.bin"); + lv_imgbtn_set_style(buttonYD, LV_BTN_STATE_PR, &tft_style_label_pre); + lv_imgbtn_set_style(buttonYD, LV_BTN_STATE_REL, &tft_style_label_rel); + + lv_obj_set_event_cb_mks(buttonZI, event_handler, ID_BABY_STEP_Z_P, NULL, 0); + lv_imgbtn_set_src(buttonZI, LV_BTN_STATE_REL, "F:/bmp_zAdd.bin"); + lv_imgbtn_set_src(buttonZI, LV_BTN_STATE_PR, "F:/bmp_zAdd.bin"); + lv_imgbtn_set_style(buttonZI, LV_BTN_STATE_PR, &tft_style_label_pre); + lv_imgbtn_set_style(buttonZI, LV_BTN_STATE_REL, &tft_style_label_rel); + + lv_obj_set_event_cb_mks(buttonZD, event_handler, ID_BABY_STEP_Z_N, NULL, 0); + lv_imgbtn_set_src(buttonZD, LV_BTN_STATE_REL, "F:/bmp_zDec.bin"); + lv_imgbtn_set_src(buttonZD, LV_BTN_STATE_PR, "F:/bmp_zDec.bin"); + lv_imgbtn_set_style(buttonZD, LV_BTN_STATE_PR, &tft_style_label_pre); + lv_imgbtn_set_style(buttonZD, LV_BTN_STATE_REL, &tft_style_label_rel); + + lv_obj_set_event_cb_mks(buttonV, event_handler, ID_BABY_STEP_DIST, NULL, 0); + lv_imgbtn_set_style(buttonV, LV_BTN_STATE_PR, &tft_style_label_pre); + lv_imgbtn_set_style(buttonV, LV_BTN_STATE_REL, &tft_style_label_rel); + + lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_BABY_STEP_RETURN, NULL, 0); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_return.bin"); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_return.bin"); + lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); + lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); + + #endif // if 1 + lv_obj_set_pos(buttonXI, INTERVAL_V, titleHeight); + lv_obj_set_pos(buttonYI, BTN_X_PIXEL + INTERVAL_V * 2, titleHeight); + lv_obj_set_pos(buttonZI, BTN_X_PIXEL * 2 + INTERVAL_V * 3, titleHeight); + lv_obj_set_pos(buttonV, BTN_X_PIXEL * 3 + INTERVAL_V * 4, titleHeight); + lv_obj_set_pos(buttonXD, INTERVAL_V, BTN_Y_PIXEL + INTERVAL_H + titleHeight); + lv_obj_set_pos(buttonYD, BTN_X_PIXEL + INTERVAL_V * 2, BTN_Y_PIXEL + INTERVAL_H + titleHeight); + lv_obj_set_pos(buttonZD, BTN_X_PIXEL * 2 + INTERVAL_V * 3, BTN_Y_PIXEL + INTERVAL_H + titleHeight); + lv_obj_set_pos(buttonBack, BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight); + + // Create labels on the image buttons + lv_btn_set_layout(buttonXI, LV_LAYOUT_OFF); + lv_btn_set_layout(buttonXD, LV_LAYOUT_OFF); + lv_btn_set_layout(buttonYI, LV_LAYOUT_OFF); + lv_btn_set_layout(buttonYD, LV_LAYOUT_OFF); + lv_btn_set_layout(buttonZI, LV_LAYOUT_OFF); + lv_btn_set_layout(buttonZD, LV_LAYOUT_OFF); + lv_btn_set_layout(buttonV, LV_LAYOUT_OFF); + lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); + + lv_obj_t *labelXI = lv_label_create(buttonXI, NULL); + lv_obj_t *labelXD = lv_label_create(buttonXD, NULL); + lv_obj_t *labelYI = lv_label_create(buttonYI, NULL); + lv_obj_t *labelYD = lv_label_create(buttonYD, NULL); + lv_obj_t *labelZI = lv_label_create(buttonZI, NULL); + lv_obj_t *labelZD = lv_label_create(buttonZD, NULL); + labelV = lv_label_create(buttonV, NULL); + lv_obj_t *label_Back = lv_label_create(buttonBack, NULL); + + if (gCfgItems.multiple_language != 0) { + lv_label_set_text(labelXI, move_menu.x_add); + lv_obj_align(labelXI, buttonXI, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + + lv_label_set_text(labelXD, move_menu.x_dec); + lv_obj_align(labelXD, buttonXD, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + + lv_label_set_text(labelYI, move_menu.y_add); + lv_obj_align(labelYI, buttonYI, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + + lv_label_set_text(labelYD, move_menu.y_dec); + lv_obj_align(labelYD, buttonYD, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + + lv_label_set_text(labelZI, move_menu.z_add); + lv_obj_align(labelZI, buttonZI, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + + lv_label_set_text(labelZD, move_menu.z_dec); + lv_obj_align(labelZD, buttonZD, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + + lv_label_set_text(label_Back, common_menu.text_back); + lv_obj_align(label_Back, buttonBack, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + } + + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonXI); + lv_group_add_obj(g, buttonXD); + lv_group_add_obj(g, buttonYI); + lv_group_add_obj(g, buttonYD); + lv_group_add_obj(g, buttonZI); + lv_group_add_obj(g, buttonZD); + lv_group_add_obj(g, buttonV); + lv_group_add_obj(g, buttonBack); + } + #endif + + disp_baby_step_dist(); + + zOffsetText = lv_label_create(scr, NULL); + lv_obj_set_style(zOffsetText, &tft_style_label_rel); + lv_obj_set_pos(zOffsetText, 290, TITLE_YPOS); + disp_z_offset_value(); +} + +void disp_baby_step_dist() { + // char buf[30] = {0}; + + if ((int)(100 * babystep_dist) == 1) { + lv_imgbtn_set_src(buttonV, LV_BTN_STATE_REL, "F:/bmp_baby_move0_01.bin"); + lv_imgbtn_set_src(buttonV, LV_BTN_STATE_PR, "F:/bmp_baby_move0_01.bin"); + } + else if ((int)(100 * babystep_dist) == 5) { + lv_imgbtn_set_src(buttonV, LV_BTN_STATE_REL, "F:/bmp_baby_move0_05.bin"); + lv_imgbtn_set_src(buttonV, LV_BTN_STATE_PR, "F:/bmp_baby_move0_05.bin"); + } + else if ((int)(100 * babystep_dist) == 10) { + lv_imgbtn_set_src(buttonV, LV_BTN_STATE_REL, "F:/bmp_baby_move0_1.bin"); + lv_imgbtn_set_src(buttonV, LV_BTN_STATE_PR, "F:/bmp_baby_move0_1.bin"); + } + if (gCfgItems.multiple_language != 0) { + if ((int)(100 * babystep_dist) == 1) { + lv_label_set_text(labelV, move_menu.step_001mm); + lv_obj_align(labelV, buttonV, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + } + else if ((int)(100 * babystep_dist) == 5) { + lv_label_set_text(labelV, move_menu.step_005mm); + lv_obj_align(labelV, buttonV, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + } + else if ((int)(100 * babystep_dist) == 10) { + lv_label_set_text(labelV, move_menu.step_01mm); + lv_obj_align(labelV, buttonV, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + } + } +} + +void disp_z_offset_value() { + char buf[20]; + + ZERO(buf); + sprintf_P(buf, PSTR("offset Z: %.3f"), (double)TERN(HAS_BED_PROBE, probe.offset.z, 0)); + lv_label_set_text(zOffsetText, buf); +} + +void lv_clear_baby_stepping() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_baby_stepping.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_baby_stepping.h new file mode 100644 index 0000000000..333ba2d597 --- /dev/null +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_baby_stepping.h @@ -0,0 +1,36 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#ifdef __cplusplus + extern "C" { /* C-declarations for C++ */ +#endif + +extern void lv_draw_baby_stepping(void); +extern void lv_clear_baby_stepping(); +extern void disp_baby_step_dist(); +extern void disp_z_offset_value(); + +//extern void disp_temp_ready_print(); +#ifdef __cplusplus + } /* C-declarations for C++ */ +#endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_change_speed.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_change_speed.cpp index 264d528c03..c60000afae 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_change_speed.cpp +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_change_speed.cpp @@ -34,9 +34,10 @@ #include "../../../../module/temperature.h" #include "../../../../module/planner.h" +extern lv_group_t * g; static lv_obj_t * scr; -static lv_obj_t * labelStep, *buttonStep, *buttonMov, *buttonExt; -static lv_obj_t * labelMov, *labelExt; +static lv_obj_t *labelStep, *buttonStep, *buttonMov, *buttonExt; +static lv_obj_t *labelMov, *labelExt; static lv_obj_t * printSpeedText; #define ID_C_ADD 1 @@ -70,10 +71,10 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { //planner.flow_percentage[1] = planner.flow_percentage[0]; //planner.e_factor[1]= planner.flow_percentage[1]*0.01; planner.refresh_e_factor(0); - if (EXTRUDERS == 2) { + #if HAS_MULTI_EXTRUDER planner.flow_percentage[1] = planner.flow_percentage[0]; planner.refresh_e_factor(1); - } + #endif } disp_print_speed(); } @@ -98,10 +99,10 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { //planner.flow_percentage[1] = planner.flow_percentage[0]; //planner.e_factor[1]= planner.flow_percentage[1] * 0.01; planner.refresh_e_factor(0); - if (EXTRUDERS == 2) { + #if HAS_MULTI_EXTRUDER planner.flow_percentage[1] = planner.flow_percentage[0]; planner.refresh_e_factor(1); - } + #endif } disp_print_speed(); } @@ -175,9 +176,8 @@ void lv_draw_change_speed(void) { lv_refr_now(lv_refr_get_disp_refreshing()); - LV_IMG_DECLARE(bmp_pic); - /*Create an Image button*/ + // Create an Image button buttonAdd = lv_imgbtn_create(scr, NULL); buttonDec = lv_imgbtn_create(scr, NULL); buttonMov = lv_imgbtn_create(scr, NULL); @@ -185,38 +185,34 @@ void lv_draw_change_speed(void) { buttonStep = lv_imgbtn_create(scr, NULL); buttonBack = lv_imgbtn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonAdd, event_handler, ID_C_ADD, "bmp_Add.bin", 0); - lv_imgbtn_set_src(buttonAdd, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonAdd, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonAdd, event_handler, ID_C_ADD, NULL, 0); + lv_imgbtn_set_src(buttonAdd, LV_BTN_STATE_REL, "F:/bmp_Add.bin"); + lv_imgbtn_set_src(buttonAdd, LV_BTN_STATE_PR, "F:/bmp_Add.bin"); lv_imgbtn_set_style(buttonAdd, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonAdd, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_clear_protect(buttonAdd, LV_PROTECT_FOLLOW); #if 1 - lv_obj_set_event_cb_mks(buttonDec, event_handler, ID_C_DEC, "bmp_Dec.bin", 0); - lv_imgbtn_set_src(buttonDec, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonDec, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonDec, event_handler, ID_C_DEC, NULL, 0); + lv_imgbtn_set_src(buttonDec, LV_BTN_STATE_REL, "F:/bmp_Dec.bin"); + lv_imgbtn_set_src(buttonDec, LV_BTN_STATE_PR, "F:/bmp_Dec.bin"); lv_imgbtn_set_style(buttonDec, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonDec, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_imgbtn_set_src(buttonMov, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonMov, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonMov, event_handler, ID_C_MOVE, NULL, 0); lv_imgbtn_set_style(buttonMov, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonMov, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_imgbtn_set_src(buttonExt, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonExt, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonExt, event_handler, ID_C_EXT, NULL, 0); lv_imgbtn_set_style(buttonExt, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonExt, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_imgbtn_set_src(buttonStep, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonStep, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonStep, event_handler, ID_C_STEP, NULL, 0); lv_imgbtn_set_style(buttonStep, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonStep, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_C_RETURN, "bmp_return.bin", 0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_C_RETURN, NULL, 0); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_return.bin"); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_return.bin"); lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); #endif @@ -228,7 +224,7 @@ void lv_draw_change_speed(void) { lv_obj_set_pos(buttonStep, BTN_X_PIXEL * 2 + INTERVAL_V * 3, BTN_Y_PIXEL + INTERVAL_H + titleHeight); lv_obj_set_pos(buttonBack, BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - /*Create a label on the Image button*/ + // Create labels on the image buttons lv_btn_set_layout(buttonAdd, LV_LAYOUT_OFF); lv_btn_set_layout(buttonDec, LV_LAYOUT_OFF); lv_btn_set_layout(buttonMov, LV_LAYOUT_OFF); @@ -236,12 +232,12 @@ void lv_draw_change_speed(void) { lv_btn_set_layout(buttonStep, LV_LAYOUT_OFF); lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); - lv_obj_t * labelAdd = lv_label_create(buttonAdd, NULL); - lv_obj_t * labelDec = lv_label_create(buttonDec, NULL); - labelMov = lv_label_create(buttonMov, NULL); - labelExt = lv_label_create(buttonExt, NULL); - labelStep = lv_label_create(buttonStep, NULL); - lv_obj_t * label_Back = lv_label_create(buttonBack, NULL); + lv_obj_t *labelAdd = lv_label_create(buttonAdd, NULL); + lv_obj_t *labelDec = lv_label_create(buttonDec, NULL); + labelMov = lv_label_create(buttonMov, NULL); + labelExt = lv_label_create(buttonExt, NULL); + labelStep = lv_label_create(buttonStep, NULL); + lv_obj_t *label_Back = lv_label_create(buttonBack, NULL); if (gCfgItems.multiple_language != 0) { lv_label_set_text(labelAdd, speed_menu.add); @@ -253,6 +249,17 @@ void lv_draw_change_speed(void) { lv_label_set_text(label_Back, common_menu.text_back); lv_obj_align(label_Back, buttonBack, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); } + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonAdd); + lv_group_add_obj(g, buttonDec); + lv_group_add_obj(g, buttonMov); + lv_group_add_obj(g, buttonExt); + lv_group_add_obj(g, buttonStep); + lv_group_add_obj(g, buttonBack); + } + #endif + disp_speed_type(); disp_speed_step(); @@ -262,13 +269,18 @@ void lv_draw_change_speed(void) { } void disp_speed_step() { - if (uiCfg.stepPrintSpeed == 1) - lv_obj_set_event_cb_mks(buttonStep, event_handler, ID_C_STEP, "bmp_step1_percent.bin", 0); - else if (uiCfg.stepPrintSpeed == 5) - lv_obj_set_event_cb_mks(buttonStep, event_handler, ID_C_STEP, "bmp_step5_percent.bin", 0); - else if (uiCfg.stepPrintSpeed == 10) - lv_obj_set_event_cb_mks(buttonStep, event_handler, ID_C_STEP, "bmp_step10_percent.bin", 0); - + if (uiCfg.stepPrintSpeed == 1) { + lv_imgbtn_set_src(buttonStep, LV_BTN_STATE_REL, "F:/bmp_step1_percent.bin"); + lv_imgbtn_set_src(buttonStep, LV_BTN_STATE_PR, "F:/bmp_step1_percent.bin"); + } + else if (uiCfg.stepPrintSpeed == 5) { + lv_imgbtn_set_src(buttonStep, LV_BTN_STATE_REL, "F:/bmp_step5_percent.bin"); + lv_imgbtn_set_src(buttonStep, LV_BTN_STATE_PR, "F:/bmp_step5_percent.bin"); + } + else if (uiCfg.stepPrintSpeed == 10) { + lv_imgbtn_set_src(buttonStep, LV_BTN_STATE_REL, "F:/bmp_step10_percent.bin"); + lv_imgbtn_set_src(buttonStep, LV_BTN_STATE_PR, "F:/bmp_step10_percent.bin"); + } if (gCfgItems.multiple_language != 0) { if (uiCfg.stepPrintSpeed == 1) { lv_label_set_text(labelStep, speed_menu.step_1percent); @@ -286,7 +298,7 @@ void disp_speed_step() { } void disp_print_speed() { - char buf[30] = {0}; + char buf[30] = { 0 }; public_buf_l[0] = '\0'; @@ -309,13 +321,17 @@ void disp_print_speed() { void disp_speed_type() { switch (speedType) { case 1: - lv_obj_set_event_cb_mks(buttonExt, event_handler, ID_C_EXT, "bmp_extruct_sel.bin", 0); - lv_obj_set_event_cb_mks(buttonMov, event_handler, ID_C_MOVE, "bmp_mov_changeSpeed.bin", 0); + lv_imgbtn_set_src(buttonMov, LV_BTN_STATE_REL, "F:/bmp_mov_changeSpeed.bin"); + lv_imgbtn_set_src(buttonMov, LV_BTN_STATE_PR, "F:/bmp_mov_changeSpeed.bin"); + lv_imgbtn_set_src(buttonExt, LV_BTN_STATE_REL, "F:/bmp_extruct_sel.bin"); + lv_imgbtn_set_src(buttonExt, LV_BTN_STATE_PR, "F:/bmp_extruct_sel.bin"); break; default: - lv_obj_set_event_cb_mks(buttonExt, event_handler, ID_C_EXT, "bmp_speed_extruct.bin", 0); - lv_obj_set_event_cb_mks(buttonMov, event_handler, ID_C_MOVE, "bmp_mov_sel.bin", 0); + lv_imgbtn_set_src(buttonMov, LV_BTN_STATE_REL, "F:/bmp_mov_sel.bin"); + lv_imgbtn_set_src(buttonMov, LV_BTN_STATE_PR, "F:/bmp_mov_sel.bin"); + lv_imgbtn_set_src(buttonExt, LV_BTN_STATE_REL, "F:/bmp_speed_extruct.bin"); + lv_imgbtn_set_src(buttonExt, LV_BTN_STATE_PR, "F:/bmp_speed_extruct.bin"); break; } lv_obj_refresh_ext_draw_pad(buttonExt); @@ -330,6 +346,11 @@ void disp_speed_type() { } } -void lv_clear_change_speed() { lv_obj_del(scr); } +void lv_clear_change_speed() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} #endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_change_speed.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_change_speed.h index d071da20bb..c4996a3ef7 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_change_speed.h +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_change_speed.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus -extern "C" { /* C-declarations for C++ */ + extern "C" { /* C-declarations for C++ */ #endif #define MIN_EXT_SPEED_PERCENT 10 @@ -36,5 +36,5 @@ extern void disp_speed_type(); //extern void disp_temp_ready_print(); #ifdef __cplusplus -} /* C-declarations for C++ */ + } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_dialog.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_dialog.cpp index aad5e4362e..c848323010 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_dialog.cpp +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_dialog.cpp @@ -41,6 +41,7 @@ #include "../../../../gcode/queue.h" #include "../../../../module/temperature.h" #include "../../../../module/planner.h" +#include "../../../../gcode/gcode.h" #if ENABLED(POWER_LOSS_RECOVERY) #include "../../../../feature/powerloss.h" @@ -51,20 +52,25 @@ #endif #include "../../../../gcode/gcode.h" -#include "pic_manager.h" - +extern lv_group_t * g; static lv_obj_t * scr; +static lv_obj_t * tempText1; +static lv_obj_t * filament_bar; + extern uint8_t sel_id; extern uint8_t once_flag; extern uint8_t gcode_preview_over; -uint8_t DialogType; +extern int upload_result ; +extern uint32_t upload_time; +extern uint32_t upload_size; +extern uint8_t temperature_change_frequency; static void btn_ok_event_cb(lv_obj_t * btn, lv_event_t event) { if (event == LV_EVENT_CLICKED) { // nothing to do } else if (event == LV_EVENT_RELEASED) { - if (DialogType == DIALOG_TYPE_PRINT_FILE) { + if (uiCfg.dialogType == DIALOG_TYPE_PRINT_FILE) { #if HAS_GCODE_PREVIEW preview_gcode_prehandle(list_file.file_name[sel_id]); #endif @@ -95,7 +101,7 @@ static void btn_ok_event_cb(lv_obj_t * btn, lv_event_t event) { //saved_feedrate_percentage = feedrate_percentage; planner.flow_percentage[0] = 100; planner.e_factor[0] = planner.flow_percentage[0] * 0.01f; - #if EXTRUDERS == 2 + #if HAS_MULTI_EXTRUDER planner.flow_percentage[1] = 100; planner.e_factor[1] = planner.flow_percentage[1] * 0.01f; #endif @@ -108,7 +114,8 @@ static void btn_ok_event_cb(lv_obj_t * btn, lv_event_t event) { } #endif } - else if (DialogType == DIALOG_TYPE_STOP) { + else if (uiCfg.dialogType == DIALOG_TYPE_STOP) { + wait_for_heatup = false; stop_print_time(); lv_clear_dialog(); lv_draw_ready_print(); @@ -130,40 +137,57 @@ static void btn_ok_event_cb(lv_obj_t * btn, lv_event_t event) { //queue.inject_P(PSTR("G91\nG1 Z10\nG90\nG28 X0 Y0\nM84\nM107")); #endif } - else if (DialogType == DIALOG_TYPE_FINISH_PRINT) { + else if (uiCfg.dialogType == DIALOG_TYPE_FINISH_PRINT) { clear_cur_ui(); lv_draw_ready_print(); } #if ENABLED(ADVANCED_PAUSE_FEATURE) - else if (DialogType == DIALOG_PAUSE_MESSAGE_WAITING - || DialogType == DIALOG_PAUSE_MESSAGE_INSERT - || DialogType == DIALOG_PAUSE_MESSAGE_HEAT + else if (uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_WAITING + || uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_INSERT + || uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_HEAT ) { wait_for_user = false; } - else if (DialogType == DIALOG_PAUSE_MESSAGE_OPTION) { + else if (uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_OPTION) { pause_menu_response = PAUSE_RESPONSE_EXTRUDE_MORE; } - else if (DialogType == DIALOG_PAUSE_MESSAGE_RESUME) { + else if (uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_RESUME) { clear_cur_ui(); draw_return_ui(); } #endif - else if (DialogType == DIALOG_STORE_EEPROM_TIPS) { + else if (uiCfg.dialogType == DIALOG_STORE_EEPROM_TIPS) { gcode.process_subcommands_now_P(PSTR("M500")); clear_cur_ui(); draw_return_ui(); } - else if (DialogType == DIALOG_READ_EEPROM_TIPS) { + else if (uiCfg.dialogType == DIALOG_READ_EEPROM_TIPS) { gcode.process_subcommands_now_P(PSTR("M501")); clear_cur_ui(); draw_return_ui(); } - else if (DialogType == DIALOG_REVERT_EEPROM_TIPS) { + else if (uiCfg.dialogType == DIALOG_REVERT_EEPROM_TIPS) { gcode.process_subcommands_now_P(PSTR("M502")); clear_cur_ui(); draw_return_ui(); } + else if (uiCfg.dialogType == DIALOG_WIFI_CONFIG_TIPS) { + uiCfg.configWifi = 1; + clear_cur_ui(); + draw_return_ui(); + } + else if (uiCfg.dialogType == DIALOG_TYPE_FILAMENT_HEAT_LOAD_COMPLETED) { + uiCfg.filament_heat_completed_load = 1; + } + else if (uiCfg.dialogType == DIALOG_TYPE_FILAMENT_HEAT_UNLOAD_COMPLETED) { + uiCfg.filament_heat_completed_unload = 1; + } + else if (uiCfg.dialogType == DIALOG_TYPE_FILAMENT_LOAD_COMPLETED + || uiCfg.dialogType == DIALOG_TYPE_FILAMENT_UNLOAD_COMPLETED + ) { + clear_cur_ui(); + draw_return_ui(); + } } } @@ -172,11 +196,35 @@ static void btn_cancel_event_cb(lv_obj_t * btn, lv_event_t event) { // nothing to do } else if (event == LV_EVENT_RELEASED) { - if (DialogType == DIALOG_PAUSE_MESSAGE_OPTION) { + if (uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_OPTION) { #if ENABLED(ADVANCED_PAUSE_FEATURE) pause_menu_response = PAUSE_RESPONSE_RESUME_PRINT; #endif } + else if ((uiCfg.dialogType == DIALOG_TYPE_FILAMENT_LOAD_HEAT) + || (uiCfg.dialogType == DIALOG_TYPE_FILAMENT_UNLOAD_HEAT) + || (uiCfg.dialogType == DIALOG_TYPE_FILAMENT_HEAT_LOAD_COMPLETED) + || (uiCfg.dialogType == DIALOG_TYPE_FILAMENT_HEAT_UNLOAD_COMPLETED) + ) { + thermalManager.temp_hotend[uiCfg.curSprayerChoose].target= uiCfg.desireSprayerTempBak; + clear_cur_ui(); + draw_return_ui(); + } + else if ((uiCfg.dialogType == DIALOG_TYPE_FILAMENT_LOADING) + || (uiCfg.dialogType == DIALOG_TYPE_FILAMENT_UNLOADING) + ) { + queue.enqueue_one_P(PSTR("M410")); + uiCfg.filament_rate = 0; + uiCfg.filament_loading_completed = 0; + uiCfg.filament_unloading_completed = 0; + uiCfg.filament_loading_time_flg = 0; + uiCfg.filament_loading_time_cnt = 0; + uiCfg.filament_unloading_time_flg = 0; + uiCfg.filament_unloading_time_cnt = 0; + thermalManager.temp_hotend[uiCfg.curSprayerChoose].target = uiCfg.desireSprayerTempBak; + clear_cur_ui(); + draw_return_ui(); + } else { clear_cur_ui(); draw_return_ui(); @@ -186,13 +234,15 @@ static void btn_cancel_event_cb(lv_obj_t * btn, lv_event_t event) { void lv_draw_dialog(uint8_t type) { + lv_obj_t * btnOk = NULL; + lv_obj_t * btnCancel = NULL; if (disp_state_stack._disp_state[disp_state_stack._disp_index] != DIALOG_UI) { disp_state_stack._disp_index++; disp_state_stack._disp_state[disp_state_stack._disp_index] = DIALOG_UI; } disp_state = DIALOG_UI; - DialogType = type; + uiCfg.dialogType = type; scr = lv_obj_create(NULL, NULL); @@ -208,7 +258,6 @@ void lv_draw_dialog(uint8_t type) { lv_refr_now(lv_refr_get_disp_refreshing()); - //LV_IMG_DECLARE(bmp_pic); static lv_style_t style_btn_rel; // A variable to store the released style lv_style_copy(&style_btn_rel, &lv_style_plain); // Initialize from a built-in style @@ -231,60 +280,151 @@ void lv_draw_dialog(uint8_t type) { style_btn_pr.text.color = lv_color_hex3(0xBCD); style_btn_pr.text.font = &TERN(HAS_SPI_FLASH_FONT, gb2312_puhui32, lv_font_roboto_22); - lv_obj_t * labelDialog = lv_label_create(scr, NULL); + lv_obj_t *labelDialog = lv_label_create(scr, NULL); lv_obj_set_style(labelDialog, &tft_style_label_rel); - if (DialogType == DIALOG_TYPE_FINISH_PRINT || DialogType == DIALOG_PAUSE_MESSAGE_RESUME) { - lv_obj_t * btnOk = lv_btn_create(scr, NULL); // Add a button the current screen - lv_obj_set_pos(btnOk, BTN_OK_X + 90, BTN_OK_Y); // Set its position - lv_obj_set_size(btnOk, 100, 50); // Set its size - lv_obj_set_event_cb(btnOk, btn_ok_event_cb); - lv_btn_set_style(btnOk, LV_BTN_STYLE_REL, &style_btn_rel); // Set the button's released style - lv_btn_set_style(btnOk, LV_BTN_STYLE_PR, &style_btn_pr); // Set the button's pressed style - lv_obj_t * labelOk = lv_label_create(btnOk, NULL); // Add a label to the button - lv_label_set_text(labelOk, print_file_dialog_menu.confirm); // Set the labels text + if (uiCfg.dialogType == DIALOG_TYPE_FINISH_PRINT || uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_RESUME) { + btnOk = lv_btn_create(scr, NULL); // Add a button the current screen + lv_obj_set_pos(btnOk, BTN_OK_X + 90, BTN_OK_Y); // Set its position + lv_obj_set_size(btnOk, 100, 50); // Set its size + lv_obj_set_event_cb(btnOk, btn_ok_event_cb); + lv_btn_set_style(btnOk, LV_BTN_STYLE_REL, &style_btn_rel); // Set the button's released style + lv_btn_set_style(btnOk, LV_BTN_STYLE_PR, &style_btn_pr); // Set the button's pressed style + lv_obj_t *labelOk = lv_label_create(btnOk, NULL); // Add a label to the button + lv_label_set_text(labelOk, print_file_dialog_menu.confirm); // Set the labels text } - else if (DialogType == DIALOG_PAUSE_MESSAGE_WAITING - || DialogType == DIALOG_PAUSE_MESSAGE_INSERT - || DialogType == DIALOG_PAUSE_MESSAGE_HEAT + else if (uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_WAITING + || uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_INSERT + || uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_HEAT ) { - lv_obj_t * btnOk = lv_btn_create(scr, NULL); // Add a button the current screen + btnOk = lv_btn_create(scr, NULL); // Add a button the current screen lv_obj_set_pos(btnOk, BTN_OK_X + 90, BTN_OK_Y); // Set its position lv_obj_set_size(btnOk, 100, 50); // Set its size lv_obj_set_event_cb(btnOk, btn_ok_event_cb); lv_btn_set_style(btnOk, LV_BTN_STYLE_REL, &style_btn_rel); // Set the button's released style lv_btn_set_style(btnOk, LV_BTN_STYLE_PR, &style_btn_pr); // Set the button's pressed style - lv_obj_t * labelOk = lv_label_create(btnOk, NULL); // Add a label to the button + lv_obj_t *labelOk = lv_label_create(btnOk, NULL); // Add a label to the button lv_label_set_text(labelOk, print_file_dialog_menu.confirm); // Set the labels text } - else if (DialogType == DIALOG_PAUSE_MESSAGE_PAUSING - || DialogType == DIALOG_PAUSE_MESSAGE_CHANGING - || DialogType == DIALOG_PAUSE_MESSAGE_UNLOAD - || DialogType == DIALOG_PAUSE_MESSAGE_LOAD - || DialogType == DIALOG_PAUSE_MESSAGE_PURGE - || DialogType == DIALOG_PAUSE_MESSAGE_RESUME - || DialogType == DIALOG_PAUSE_MESSAGE_HEATING + else if (uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_PAUSING + || uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_CHANGING + || uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_UNLOAD + || uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_LOAD + || uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_PURGE + || uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_RESUME + || uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_HEATING ) { // nothing to do } + else if (uiCfg.dialogType == WIFI_ENABLE_TIPS) { + btnCancel = lv_btn_create(scr, NULL); + lv_obj_set_pos(btnCancel, BTN_OK_X+90, BTN_OK_Y); + lv_obj_set_size(btnCancel, 100, 50); + lv_obj_set_event_cb(btnCancel, btn_cancel_event_cb); + lv_btn_set_style(btnCancel, LV_BTN_STYLE_REL, &style_btn_rel); + lv_btn_set_style(btnCancel, LV_BTN_STYLE_PR, &style_btn_pr); + lv_obj_t *labelCancel = lv_label_create(btnCancel, NULL); + lv_label_set_text(labelCancel, print_file_dialog_menu.cancle); + } + else if (uiCfg.dialogType == DIALOG_TRANSFER_NO_DEVICE) { + btnCancel = lv_btn_create(scr, NULL); + lv_obj_set_pos(btnCancel, BTN_OK_X+90, BTN_OK_Y); + lv_obj_set_size(btnCancel, 100, 50); + lv_obj_set_event_cb(btnCancel, btn_cancel_event_cb); + lv_btn_set_style(btnCancel, LV_BTN_STYLE_REL, &style_btn_rel); + lv_btn_set_style(btnCancel, LV_BTN_STYLE_PR, &style_btn_pr); + lv_obj_t *labelCancel = lv_label_create(btnCancel, NULL); + lv_label_set_text(labelCancel, print_file_dialog_menu.cancle); + } + #if ENABLED(USE_WIFI_FUNCTION) + else if (uiCfg.dialogType == DIALOG_TYPE_UPLOAD_FILE) { + if (upload_result == 2) { + btnCancel = lv_btn_create(scr, NULL); + lv_obj_set_pos(btnCancel, BTN_OK_X+90, BTN_OK_Y); + lv_obj_set_size(btnCancel, 100, 50); + lv_obj_set_event_cb(btnCancel, btn_cancel_event_cb); + lv_btn_set_style(btnCancel, LV_BTN_STYLE_REL, &style_btn_rel); + lv_btn_set_style(btnCancel, LV_BTN_STYLE_PR, &style_btn_pr); + lv_obj_t *labelCancel = lv_label_create(btnCancel, NULL); + lv_label_set_text(labelCancel, print_file_dialog_menu.cancle); + } + else if (upload_result == 3) { + btnOk = lv_btn_create(scr, NULL); + lv_obj_set_pos(btnOk, BTN_OK_X+90, BTN_OK_Y); + lv_obj_set_size(btnOk, 100, 50); + lv_obj_set_event_cb(btnOk, btn_ok_event_cb); + lv_btn_set_style(btnOk, LV_BTN_STYLE_REL, &style_btn_rel); + lv_btn_set_style(btnOk, LV_BTN_STYLE_PR, &style_btn_pr); + lv_obj_t *labelOk = lv_label_create(btnOk, NULL); + lv_label_set_text(labelOk, print_file_dialog_menu.confirm); + } + } + #endif //USE_WIFI_FUNCTION + else if (uiCfg.dialogType == DIALOG_TYPE_FILAMENT_LOAD_HEAT + || uiCfg.dialogType == DIALOG_TYPE_FILAMENT_UNLOAD_HEAT + ) { + btnCancel = lv_btn_create(scr, NULL); + lv_obj_set_pos(btnCancel, BTN_OK_X+90, BTN_OK_Y); + lv_obj_set_size(btnCancel, 100, 50); + lv_obj_set_event_cb(btnCancel, btn_cancel_event_cb); + lv_btn_set_style(btnCancel, LV_BTN_STYLE_REL, &style_btn_rel); + lv_btn_set_style(btnCancel, LV_BTN_STYLE_PR, &style_btn_pr); + lv_obj_t *labelCancel = lv_label_create(btnCancel, NULL); + lv_label_set_text(labelCancel, print_file_dialog_menu.cancle); + + tempText1 = lv_label_create(scr, NULL); + lv_obj_set_style(tempText1, &tft_style_label_rel); + filament_sprayer_temp(); + } + else if (uiCfg.dialogType == DIALOG_TYPE_FILAMENT_LOAD_COMPLETED + || uiCfg.dialogType == DIALOG_TYPE_FILAMENT_UNLOAD_COMPLETED + ) { + btnOk = lv_btn_create(scr, NULL); + lv_obj_set_pos(btnOk, BTN_OK_X+90, BTN_OK_Y); + lv_obj_set_size(btnOk, 100, 50); + lv_obj_set_event_cb(btnOk, btn_ok_event_cb); + lv_btn_set_style(btnOk, LV_BTN_STYLE_REL, &style_btn_rel); + lv_btn_set_style(btnOk, LV_BTN_STYLE_PR, &style_btn_pr); + lv_obj_t *labelOk = lv_label_create(btnOk, NULL); + lv_label_set_text(labelOk, print_file_dialog_menu.confirm); + } + else if (uiCfg.dialogType == DIALOG_TYPE_FILAMENT_LOADING + || uiCfg.dialogType == DIALOG_TYPE_FILAMENT_UNLOADING + ) { + btnCancel = lv_btn_create(scr, NULL); + lv_obj_set_pos(btnCancel, BTN_OK_X+90, BTN_OK_Y); + lv_obj_set_size(btnCancel, 100, 50); + lv_obj_set_event_cb(btnCancel, btn_cancel_event_cb); + lv_btn_set_style(btnCancel, LV_BTN_STYLE_REL, &style_btn_rel); + lv_btn_set_style(btnCancel, LV_BTN_STYLE_PR, &style_btn_pr); + lv_obj_t *labelCancel = lv_label_create(btnCancel, NULL); + lv_label_set_text(labelCancel, print_file_dialog_menu.cancle); + + filament_bar = lv_bar_create(scr, NULL); + lv_obj_set_pos(filament_bar, (TFT_WIDTH-400)/2, ((TFT_HEIGHT - titleHeight)-40)/2); + lv_obj_set_size(filament_bar, 400, 25); + lv_bar_set_style(filament_bar, LV_BAR_STYLE_INDIC, &lv_bar_style_indic); + lv_bar_set_anim_time(filament_bar, 1000); + lv_bar_set_value(filament_bar, 0, LV_ANIM_ON); + } else { - lv_obj_t * btnOk = lv_btn_create(scr, NULL); // Add a button the current screen + btnOk = lv_btn_create(scr, NULL); // Add a button the current screen lv_obj_set_pos(btnOk, BTN_OK_X, BTN_OK_Y); // Set its position lv_obj_set_size(btnOk, 100, 50); // Set its size lv_obj_set_event_cb(btnOk, btn_ok_event_cb); lv_btn_set_style(btnOk, LV_BTN_STYLE_REL, &style_btn_rel); // Set the button's released style lv_btn_set_style(btnOk, LV_BTN_STYLE_PR, &style_btn_pr); // Set the button's pressed style - lv_obj_t * labelOk = lv_label_create(btnOk, NULL); // Add a label to the button + lv_obj_t *labelOk = lv_label_create(btnOk, NULL); // Add a label to the button - lv_obj_t * btnCancel = lv_btn_create(scr, NULL); // Add a button the current screen + btnCancel = lv_btn_create(scr, NULL); // Add a button the current screen lv_obj_set_pos(btnCancel, BTN_CANCEL_X, BTN_CANCEL_Y); // Set its position lv_obj_set_size(btnCancel, 100, 50); // Set its size lv_obj_set_event_cb(btnCancel, btn_cancel_event_cb); lv_btn_set_style(btnCancel, LV_BTN_STYLE_REL, &style_btn_rel); // Set the button's released style lv_btn_set_style(btnCancel, LV_BTN_STYLE_PR, &style_btn_pr); // Set the button's pressed style - lv_obj_t * labelCancel = lv_label_create(btnCancel, NULL); // Add a label to the button + lv_obj_t *labelCancel = lv_label_create(btnCancel, NULL); // Add a label to the button - if (DialogType == DIALOG_PAUSE_MESSAGE_OPTION) { + if (uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_OPTION) { lv_label_set_text(labelOk, pause_msg_menu.purgeMore); // Set the labels text lv_label_set_text(labelCancel, pause_msg_menu.continuePrint); } @@ -293,82 +433,271 @@ void lv_draw_dialog(uint8_t type) { lv_label_set_text(labelCancel, print_file_dialog_menu.cancle); } } - if (DialogType == DIALOG_TYPE_PRINT_FILE) { + if (uiCfg.dialogType == DIALOG_TYPE_PRINT_FILE) { lv_label_set_text(labelDialog, print_file_dialog_menu.print_file); lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); - lv_obj_t * labelFile = lv_label_create(scr, NULL); + lv_obj_t *labelFile = lv_label_create(scr, NULL); lv_obj_set_style(labelFile, &tft_style_label_rel); lv_label_set_text(labelFile, list_file.long_name[sel_id]); lv_obj_align(labelFile, NULL, LV_ALIGN_CENTER, 0, -60); } - else if (DialogType == DIALOG_TYPE_STOP) { + else if (uiCfg.dialogType == DIALOG_TYPE_STOP) { lv_label_set_text(labelDialog, print_file_dialog_menu.cancle_print); lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); } - else if (DialogType == DIALOG_TYPE_FINISH_PRINT) { + else if (uiCfg.dialogType == DIALOG_TYPE_FINISH_PRINT) { lv_label_set_text(labelDialog, print_file_dialog_menu.print_finish); lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); } - else if (DialogType == DIALOG_PAUSE_MESSAGE_PAUSING) { + else if (uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_PAUSING) { lv_label_set_text(labelDialog, pause_msg_menu.pausing); lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); } - else if (DialogType == DIALOG_PAUSE_MESSAGE_CHANGING) { + else if (uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_CHANGING) { lv_label_set_text(labelDialog, pause_msg_menu.changing); lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); } - else if (DialogType == DIALOG_PAUSE_MESSAGE_UNLOAD) { + else if (uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_UNLOAD) { lv_label_set_text(labelDialog, pause_msg_menu.unload); lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); } - else if (DialogType == DIALOG_PAUSE_MESSAGE_WAITING) { + else if (uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_WAITING) { lv_label_set_text(labelDialog, pause_msg_menu.waiting); lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); } - else if (DialogType == DIALOG_PAUSE_MESSAGE_INSERT) { + else if (uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_INSERT) { lv_label_set_text(labelDialog, pause_msg_menu.insert); lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); } - else if (DialogType == DIALOG_PAUSE_MESSAGE_LOAD) { + else if (uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_LOAD) { lv_label_set_text(labelDialog, pause_msg_menu.load); lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); } - else if (DialogType == DIALOG_PAUSE_MESSAGE_PURGE) { + else if (uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_PURGE) { lv_label_set_text(labelDialog, pause_msg_menu.purge); lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); } - else if (DialogType == DIALOG_PAUSE_MESSAGE_RESUME) { + else if (uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_RESUME) { lv_label_set_text(labelDialog, pause_msg_menu.resume); lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); } - else if (DialogType == DIALOG_PAUSE_MESSAGE_HEAT) { + else if (uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_HEAT) { lv_label_set_text(labelDialog, pause_msg_menu.heat); lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); } - else if (DialogType == DIALOG_PAUSE_MESSAGE_HEATING) { + else if (uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_HEATING) { lv_label_set_text(labelDialog, pause_msg_menu.heating); lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); } - else if (DialogType == DIALOG_PAUSE_MESSAGE_OPTION) { + else if (uiCfg.dialogType == DIALOG_PAUSE_MESSAGE_OPTION) { lv_label_set_text(labelDialog, pause_msg_menu.option); lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); } - else if (DialogType == DIALOG_STORE_EEPROM_TIPS) { + else if (uiCfg.dialogType == DIALOG_STORE_EEPROM_TIPS) { lv_label_set_text(labelDialog, eeprom_menu.storeTips); lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); } - else if (DialogType == DIALOG_READ_EEPROM_TIPS) { + else if (uiCfg.dialogType == DIALOG_READ_EEPROM_TIPS) { lv_label_set_text(labelDialog, eeprom_menu.readTips); lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); } - else if (DialogType == DIALOG_REVERT_EEPROM_TIPS) { + else if (uiCfg.dialogType == DIALOG_REVERT_EEPROM_TIPS) { lv_label_set_text(labelDialog, eeprom_menu.revertTips); lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); } + else if (uiCfg.dialogType == DIALOG_WIFI_CONFIG_TIPS) { + lv_label_set_text(labelDialog, machine_menu.wifiConfigTips); + lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); + } + else if (uiCfg.dialogType == WIFI_ENABLE_TIPS) { + lv_label_set_text(labelDialog, print_file_dialog_menu.wifi_enable_tips); + lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); + } + else if (uiCfg.dialogType == DIALOG_TRANSFER_NO_DEVICE) { + lv_label_set_text(labelDialog, DIALOG_UPDATE_NO_DEVICE_EN); + lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); + } + #if ENABLED(USE_WIFI_FUNCTION) + else if (uiCfg.dialogType == DIALOG_TYPE_UPLOAD_FILE) { + if (upload_result == 1) { + lv_label_set_text(labelDialog, DIALOG_UPLOAD_ING_EN); + lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); + } + else if (upload_result == 2) { + lv_label_set_text(labelDialog, DIALOG_UPLOAD_ERROR_EN); + lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); + } + else if (upload_result == 3) { + char buf[200]; + int _index = 0; + + ZERO(buf); + + strcpy(buf, DIALOG_UPLOAD_FINISH_EN); + _index = strlen(buf); + buf[_index] = '\n'; + _index++; + strcat(buf, DIALOG_UPLOAD_SIZE_EN); + + _index = strlen(buf); + buf[_index] = ':'; + _index++; + sprintf(&buf[_index], " %d KBytes\n", (int)(upload_size / 1024)); + + strcat(buf, DIALOG_UPLOAD_TIME_EN); + _index = strlen(buf); + buf[_index] = ':'; + _index++; + sprintf(&buf[_index], " %d s\n", (int)upload_time); + + strcat(buf, DIALOG_UPLOAD_SPEED_EN); + _index = strlen(buf); + buf[_index] = ':'; + _index++; + sprintf(&buf[_index], " %d KBytes/s\n", (int)(upload_size / upload_time / 1024)); + + lv_label_set_text(labelDialog, buf); + lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); + + } + } + #endif //USE_WIFI_FUNCTION + else if (uiCfg.dialogType == DIALOG_TYPE_FILAMENT_LOAD_HEAT) { + lv_label_set_text(labelDialog, filament_menu.filament_dialog_load_heat); + lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); + } + else if (uiCfg.dialogType == DIALOG_TYPE_FILAMENT_HEAT_LOAD_COMPLETED) { + lv_label_set_text(labelDialog, filament_menu.filament_dialog_load_heat_confirm); + lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); + } + else if (uiCfg.dialogType == DIALOG_TYPE_FILAMENT_UNLOAD_HEAT) { + lv_label_set_text(labelDialog, filament_menu.filament_dialog_unload_heat); + lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); + } + else if (uiCfg.dialogType == DIALOG_TYPE_FILAMENT_HEAT_UNLOAD_COMPLETED) { + lv_label_set_text(labelDialog, filament_menu.filament_dialog_unload_heat_confirm); + lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); + } + else if (uiCfg.dialogType == DIALOG_TYPE_FILAMENT_LOAD_COMPLETED) { + lv_label_set_text(labelDialog, filament_menu.filament_dialog_load_completed); + lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); + } + else if (uiCfg.dialogType == DIALOG_TYPE_FILAMENT_UNLOAD_COMPLETED) { + lv_label_set_text(labelDialog, filament_menu.filament_dialog_unload_completed); + lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -20); + } + else if (uiCfg.dialogType == DIALOG_TYPE_FILAMENT_LOADING) { + lv_label_set_text(labelDialog, filament_menu.filament_dialog_loading); + lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -70); + } + else if (uiCfg.dialogType == DIALOG_TYPE_FILAMENT_UNLOADING) { + lv_label_set_text(labelDialog, filament_menu.filament_dialog_unloading); + lv_obj_align(labelDialog, NULL, LV_ALIGN_CENTER, 0, -70); + } + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + if (btnOk) lv_group_add_obj(g, btnOk); + if (btnCancel) lv_group_add_obj(g, btnCancel); + } + #endif +} + +void filament_sprayer_temp() { + char buf[20] = {0}; + + public_buf_l[0] = '\0'; + + if (uiCfg.curSprayerChoose < 1) + strcat(public_buf_l, preheat_menu.ext1); + else + strcat(public_buf_l, preheat_menu.ext2); + sprintf(buf, preheat_menu.value_state, (int)thermalManager.temp_hotend[uiCfg.curSprayerChoose].celsius, (int)thermalManager.temp_hotend[uiCfg.curSprayerChoose].target); + + strcat_P(public_buf_l, PSTR(": ")); + strcat(public_buf_l, buf); + lv_label_set_text(tempText1, public_buf_l); + lv_obj_align(tempText1, NULL, LV_ALIGN_CENTER, 0, -50); +} + +void filament_dialog_handle() { + if ((temperature_change_frequency == 1) + && ((uiCfg.dialogType == DIALOG_TYPE_FILAMENT_LOAD_HEAT) + || (uiCfg.dialogType == DIALOG_TYPE_FILAMENT_UNLOAD_HEAT)) + ) { + filament_sprayer_temp(); + temperature_change_frequency = 0; + } + if (uiCfg.filament_heat_completed_load == 1) { + uiCfg.filament_heat_completed_load = 0; + lv_clear_dialog(); + lv_draw_dialog(DIALOG_TYPE_FILAMENT_LOADING); + planner.synchronize(); + uiCfg.filament_loading_time_flg = 1; + uiCfg.filament_loading_time_cnt = 0; + ZERO(public_buf_m); + sprintf_P(public_buf_m,PSTR("T%d\nG91\nG1 E%d F%d\nG90"),uiCfg.curSprayerChoose,gCfgItems.filamentchange_load_length,gCfgItems.filamentchange_load_speed); + queue.inject_P(PSTR(public_buf_m)); + //gcode.process_subcommands_now_P(PSTR(public_buf_m)); + } + if (uiCfg.filament_heat_completed_unload == 1) { + uiCfg.filament_heat_completed_unload = 0; + lv_clear_dialog(); + lv_draw_dialog(DIALOG_TYPE_FILAMENT_UNLOADING); + planner.synchronize(); + uiCfg.filament_unloading_time_flg = 1; + uiCfg.filament_unloading_time_cnt = 0; + ZERO(public_buf_m); + sprintf_P(public_buf_m,PSTR("T%d\nG91\nG1 E-%d F%d\nG90"),uiCfg.curSprayerChoose,gCfgItems.filamentchange_unload_length,gCfgItems.filamentchange_unload_speed); + queue.inject_P(PSTR(public_buf_m)); + } + + if (((abs((int)((int)thermalManager.temp_hotend[uiCfg.curSprayerChoose].celsius - gCfgItems.filament_limit_temper)) <= 1) + || ((int)thermalManager.temp_hotend[uiCfg.curSprayerChoose].celsius > gCfgItems.filament_limit_temper)) + && (uiCfg.filament_load_heat_flg == 1) + ) { + uiCfg.filament_load_heat_flg = 0; + lv_clear_dialog(); + lv_draw_dialog(DIALOG_TYPE_FILAMENT_HEAT_LOAD_COMPLETED); + } + + if (uiCfg.filament_loading_completed == 1) { + uiCfg.filament_rate = 0; + uiCfg.filament_loading_completed = 0; + lv_clear_dialog(); + lv_draw_dialog(DIALOG_TYPE_FILAMENT_LOAD_COMPLETED); + } + if (((abs((int)((int)thermalManager.temp_hotend[uiCfg.curSprayerChoose].celsius - gCfgItems.filament_limit_temper)) <= 1) + || ((int)thermalManager.temp_hotend[uiCfg.curSprayerChoose].celsius > gCfgItems.filament_limit_temper)) + && (uiCfg.filament_unload_heat_flg == 1) + ) { + uiCfg.filament_unload_heat_flg = 0; + lv_clear_dialog(); + lv_draw_dialog(DIALOG_TYPE_FILAMENT_HEAT_UNLOAD_COMPLETED); + } + + if (uiCfg.filament_unloading_completed == 1) { + uiCfg.filament_rate = 0; + uiCfg.filament_unloading_completed = 0; + lv_clear_dialog(); + lv_draw_dialog(DIALOG_TYPE_FILAMENT_UNLOAD_COMPLETED); + } + + if ( uiCfg.dialogType == DIALOG_TYPE_FILAMENT_LOADING + || uiCfg.dialogType == DIALOG_TYPE_FILAMENT_UNLOADING + ) lv_filament_setbar(); } -void lv_clear_dialog() { lv_obj_del(scr); } +void lv_filament_setbar() { + lv_bar_set_value(filament_bar, uiCfg.filament_rate, LV_ANIM_ON); +} + +void lv_clear_dialog() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} #endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_dialog.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_dialog.h index a5b829a2cf..dc5adc5ad6 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_dialog.h +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_dialog.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus -extern "C" { /* C-declarations for C++ */ + extern "C" { /* C-declarations for C++ */ #endif #define DIALOG_TYPE_STOP 0 @@ -69,6 +69,8 @@ extern "C" { /* C-declarations for C++ */ #define DIALOG_READ_EEPROM_TIPS 33 #define DIALOG_REVERT_EEPROM_TIPS 34 +#define DIALOG_WIFI_CONFIG_TIPS 35 +#define DIALOG_TRANSFER_NO_DEVICE 36 #define BTN_OK_X 100 #define BTN_OK_Y 180 #define BTN_CANCEL_X 280 @@ -76,8 +78,11 @@ extern "C" { /* C-declarations for C++ */ extern void lv_draw_dialog(uint8_t type); extern void lv_clear_dialog(); +extern void filament_sprayer_temp(); +extern void filament_dialog_handle(); +extern void lv_filament_setbar(); //extern void disp_temp_ready_print(); #ifdef __cplusplus -} /* C-declarations for C++ */ + } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_eeprom_settings.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_eeprom_settings.cpp index f340ca4632..ca7d2d1e31 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_eeprom_settings.cpp +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_eeprom_settings.cpp @@ -28,6 +28,7 @@ #include "../../../../MarlinCore.h" +extern lv_group_t * g; static lv_obj_t * scr; #define ID_EEPROM_RETURN 1 @@ -48,26 +49,25 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { draw_return_ui(); } break; + case ID_EEPROM_STORE: + if (event == LV_EVENT_CLICKED) { - #if 0 - case ID_EEPROM_STORE: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_eeprom_settings(); - lv_draw_dialog(DIALOG_STORE_EEPROM_TIPS); - } - break; - case ID_EEPROM_STORE_ARROW: - if (event == LV_EVENT_CLICKED) { + } + else if (event == LV_EVENT_RELEASED) { + lv_clear_eeprom_settings(); + lv_draw_dialog(DIALOG_STORE_EEPROM_TIPS); + } + break; + case ID_EEPROM_STORE_ARROW: + if (event == LV_EVENT_CLICKED) { - } - else if (event == LV_EVENT_RELEASED) { - lv_clear_eeprom_settings(); - lv_draw_dialog(DIALOG_STORE_EEPROM_TIPS); - } - break; + } + else if (event == LV_EVENT_RELEASED) { + lv_clear_eeprom_settings(); + lv_draw_dialog(DIALOG_STORE_EEPROM_TIPS); + } + break; + #if 0 case ID_EEPROM_READ: if (event == LV_EVENT_CLICKED) { @@ -111,10 +111,10 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { void lv_draw_eeprom_settings(void) { lv_obj_t *buttonBack, *label_Back; - //lv_obj_t *buttonStore,*labelStore,*buttonStoreNarrow; + lv_obj_t *buttonStore,*labelStore,*buttonStoreNarrow; //lv_obj_t *buttonRead,*labelRead,*buttonReadNarrow; lv_obj_t *buttonRevert, *labelRevert, *buttonRevertNarrow; - lv_obj_t * line1; // * line2,* line3; + lv_obj_t * line1, * line2; //* line3; if (disp_state_stack._disp_state[disp_state_stack._disp_index] != EEPROM_SETTINGS_UI) { disp_state_stack._disp_index++; disp_state_stack._disp_state[disp_state_stack._disp_index] = EEPROM_SETTINGS_UI; @@ -134,53 +134,6 @@ void lv_draw_eeprom_settings(void) { lv_refr_now(lv_refr_get_disp_refreshing()); - LV_IMG_DECLARE(bmp_para_back); - LV_IMG_DECLARE(bmp_para_arrow); - #if 0 - buttonStore = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonStore, PARA_UI_POS_X, PARA_UI_POS_Y); /*Set its position*/ - lv_obj_set_size(buttonStore, PARA_UI_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - //lv_obj_set_event_cb(buttonMachine, event_handler); - lv_obj_set_event_cb_mks(buttonStore, event_handler, ID_EEPROM_STORE, NULL, 0); - lv_btn_set_style(buttonStore, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonStore, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonStore, LV_LAYOUT_OFF); - labelStore = lv_label_create(buttonStore, NULL); /*Add a label to the button*/ - - buttonStoreNarrow = lv_imgbtn_create(scr, NULL); - lv_obj_set_pos(buttonStoreNarrow, PARA_UI_POS_X + PARA_UI_SIZE_X, PARA_UI_POS_Y + PARA_UI_ARROW_V); - lv_obj_set_event_cb_mks(buttonStoreNarrow, event_handler, ID_EEPROM_STORE_ARROW, "bmp_arrow.bin", 0); - lv_imgbtn_set_src(buttonStoreNarrow, LV_BTN_STATE_REL, &bmp_para_arrow); - lv_imgbtn_set_src(buttonStoreNarrow, LV_BTN_STATE_PR, &bmp_para_arrow); - lv_imgbtn_set_style(buttonStoreNarrow, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonStoreNarrow, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_btn_set_layout(buttonStoreNarrow, LV_LAYOUT_OFF); - - line1 = lv_line_create(scr, NULL); - lv_ex_line(line1, line_points[0]); - - buttonRead = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonRead, PARA_UI_POS_X, PARA_UI_POS_Y * 2); /*Set its position*/ - lv_obj_set_size(buttonRead, PARA_UI_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - //lv_obj_set_event_cb(buttonMotor, event_handler); - lv_obj_set_event_cb_mks(buttonRead, event_handler, ID_EEPROM_READ, NULL, 0); - lv_btn_set_style(buttonRead, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonRead, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonRead, LV_LAYOUT_OFF); - labelRead = lv_label_create(buttonRead, NULL); /*Add a label to the button*/ - - buttonReadNarrow = lv_imgbtn_create(scr, NULL); - lv_obj_set_pos(buttonReadNarrow, PARA_UI_POS_X + PARA_UI_SIZE_X, PARA_UI_POS_Y * 2 + PARA_UI_ARROW_V); - lv_obj_set_event_cb_mks(buttonReadNarrow, event_handler, ID_EEPROM_READ_ARROW, "bmp_arrow.bin", 0); - lv_imgbtn_set_src(buttonReadNarrow, LV_BTN_STATE_REL, &bmp_para_arrow); - lv_imgbtn_set_src(buttonReadNarrow, LV_BTN_STATE_PR, &bmp_para_arrow); - lv_imgbtn_set_style(buttonReadNarrow, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonReadNarrow, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_btn_set_layout(buttonReadNarrow, LV_LAYOUT_OFF); - - line2 = lv_line_create(scr, NULL); - lv_ex_line(line2, line_points[1]); - #endif // if 0 buttonRevert = lv_btn_create(scr, NULL); /*Add a button the current screen*/ lv_obj_set_pos(buttonRevert, PARA_UI_POS_X, PARA_UI_POS_Y); /*Set its position*/ lv_obj_set_size(buttonRevert, PARA_UI_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ @@ -193,9 +146,9 @@ void lv_draw_eeprom_settings(void) { buttonRevertNarrow = lv_imgbtn_create(scr, NULL); lv_obj_set_pos(buttonRevertNarrow, PARA_UI_POS_X + PARA_UI_SIZE_X, PARA_UI_POS_Y + PARA_UI_ARROW_V); - lv_obj_set_event_cb_mks(buttonRevertNarrow, event_handler, ID_EEPROM_REVERT_ARROW, "bmp_arrow.bin", 0); - lv_imgbtn_set_src(buttonRevertNarrow, LV_BTN_STATE_REL, &bmp_para_arrow); - lv_imgbtn_set_src(buttonRevertNarrow, LV_BTN_STATE_PR, &bmp_para_arrow); + lv_obj_set_event_cb_mks(buttonRevertNarrow, event_handler, ID_EEPROM_REVERT_ARROW, NULL, 0); + lv_imgbtn_set_src(buttonRevertNarrow, LV_BTN_STATE_REL, "F:/bmp_arrow.bin"); + lv_imgbtn_set_src(buttonRevertNarrow, LV_BTN_STATE_PR, "F:/bmp_arrow.bin"); lv_imgbtn_set_style(buttonRevertNarrow, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonRevertNarrow, LV_BTN_STATE_REL, &tft_style_label_rel); lv_btn_set_layout(buttonRevertNarrow, LV_LAYOUT_OFF); @@ -205,10 +158,32 @@ void lv_draw_eeprom_settings(void) { line1 = lv_line_create(scr, NULL); lv_ex_line(line1, line_points[0]); + buttonStore = lv_btn_create(scr, NULL); /*Add a button the current screen*/ + lv_obj_set_pos(buttonStore, PARA_UI_POS_X, PARA_UI_POS_Y * 2); /*Set its position*/ + lv_obj_set_size(buttonStore, PARA_UI_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ + //lv_obj_set_event_cb(buttonMotor, event_handler); + lv_obj_set_event_cb_mks(buttonStore, event_handler, ID_EEPROM_STORE, NULL, 0); + lv_btn_set_style(buttonStore, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ + lv_btn_set_style(buttonStore, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ + lv_btn_set_layout(buttonStore, LV_LAYOUT_OFF); + labelStore = lv_label_create(buttonStore, NULL); /*Add a label to the button*/ + + buttonStoreNarrow = lv_imgbtn_create(scr, NULL); + lv_obj_set_pos(buttonStoreNarrow, PARA_UI_POS_X + PARA_UI_SIZE_X, PARA_UI_POS_Y * 2 + PARA_UI_ARROW_V); + lv_obj_set_event_cb_mks(buttonStoreNarrow, event_handler, ID_EEPROM_STORE_ARROW, NULL, 0); + lv_imgbtn_set_src(buttonStoreNarrow, LV_BTN_STATE_REL, "F:/bmp_arrow.bin"); + lv_imgbtn_set_src(buttonStoreNarrow, LV_BTN_STATE_PR, "F:/bmp_arrow.bin"); + lv_imgbtn_set_style(buttonStoreNarrow, LV_BTN_STATE_PR, &tft_style_label_pre); + lv_imgbtn_set_style(buttonStoreNarrow, LV_BTN_STATE_REL, &tft_style_label_rel); + lv_btn_set_layout(buttonStoreNarrow, LV_LAYOUT_OFF); + + line2 = lv_line_create(scr, NULL); + lv_ex_line(line2, line_points[1]); + buttonBack = lv_imgbtn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_EEPROM_RETURN, "bmp_back70x40.bin", 0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, &bmp_para_back); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, &bmp_para_back); + lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_EEPROM_RETURN, NULL, 0); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_back70x40.bin"); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_back70x40.bin"); lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); @@ -220,8 +195,8 @@ void lv_draw_eeprom_settings(void) { lv_label_set_text(label_Back, common_menu.text_back); lv_obj_align(label_Back, buttonBack, LV_ALIGN_CENTER, 0, 0); - //lv_label_set_text(labelStore, eeprom_menu.store); - //lv_obj_align(labelStore, buttonStore, LV_ALIGN_IN_LEFT_MID,0, 0); + lv_label_set_text(labelStore, eeprom_menu.store); + lv_obj_align(labelStore, buttonStore, LV_ALIGN_IN_LEFT_MID,0, 0); //lv_label_set_text(labelRead, eeprom_menu.read); //lv_obj_align(labelRead, buttonRead, LV_ALIGN_IN_LEFT_MID,0, 0); @@ -229,9 +204,21 @@ void lv_draw_eeprom_settings(void) { lv_label_set_text(labelRevert, eeprom_menu.revert); lv_obj_align(labelRevert, buttonRevert, LV_ALIGN_IN_LEFT_MID, 0, 0); } + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonRevert); + lv_group_add_obj(g, buttonStore); + lv_group_add_obj(g, buttonBack); + } + #endif } -void lv_clear_eeprom_settings() { lv_obj_del(scr); } +void lv_clear_eeprom_settings() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} #endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_eeprom_settings.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_eeprom_settings.h index da699353ba..6d5ecf0870 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_eeprom_settings.h +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_eeprom_settings.h @@ -22,12 +22,12 @@ #pragma once #ifdef __cplusplus -extern "C" { /* C-declarations for C++ */ + extern "C" { /* C-declarations for C++ */ #endif extern void lv_draw_eeprom_settings(void); extern void lv_clear_eeprom_settings(); #ifdef __cplusplus -} /* C-declarations for C++ */ + } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_encoder_settings.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_encoder_settings.cpp new file mode 100644 index 0000000000..0ad2bb5f1d --- /dev/null +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_encoder_settings.cpp @@ -0,0 +1,172 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "lv_conf.h" +#include "draw_ui.h" + +#include "../../../../MarlinCore.h" +#include "../../../../module/planner.h" +#include "../../../../module/stepper/indirection.h" +#include "../../../../feature/tmc_util.h" +#include "../../../../gcode/gcode.h" +#include "../../../../module/planner.h" + +#if BUTTONS_EXIST(EN1, EN2) + +extern lv_group_t * g; +static lv_obj_t * scr; +static lv_obj_t * buttonEncoderState = NULL; +static lv_obj_t *labelEncoderState = NULL; + +#define ID_ENCODER_RETURN 1 +#define ID_ENCODER_STATE 2 + +static void event_handler(lv_obj_t * obj, lv_event_t event) { + switch (obj->mks_obj_id) { + case ID_ENCODER_RETURN: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + lv_clear_encoder_settings(); + draw_return_ui(); + } + break; + case ID_ENCODER_STATE: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + if (gCfgItems.encoder_enable) { + gCfgItems.encoder_enable = false; + lv_imgbtn_set_src(buttonEncoderState, LV_BTN_STATE_REL, "F:/bmp_disable.bin"); + lv_imgbtn_set_src(buttonEncoderState, LV_BTN_STATE_PR, "F:/bmp_disable.bin"); + lv_label_set_text(labelEncoderState, machine_menu.disable); + update_spi_flash(); + } + else { + gCfgItems.encoder_enable = true; + lv_imgbtn_set_src(buttonEncoderState, LV_BTN_STATE_REL, "F:/bmp_enable.bin"); + lv_imgbtn_set_src(buttonEncoderState, LV_BTN_STATE_PR, "F:/bmp_enable.bin"); + lv_label_set_text(labelEncoderState, machine_menu.enable); + update_spi_flash(); + } + } + break; + } +} + +void lv_draw_encoder_settings(void) { + lv_obj_t *buttonBack = NULL, *label_Back = NULL; + lv_obj_t *labelEncoderTips = NULL; + + lv_obj_t * line1 = NULL; + + if (disp_state_stack._disp_state[disp_state_stack._disp_index] != ENCODER_SETTINGS_UI) { + disp_state_stack._disp_index++; + disp_state_stack._disp_state[disp_state_stack._disp_index] = ENCODER_SETTINGS_UI; + } + disp_state = ENCODER_SETTINGS_UI; + + scr = lv_obj_create(NULL, NULL); + + lv_obj_set_style(scr, &tft_style_scr); + lv_scr_load(scr); + lv_obj_clean(scr); + + lv_obj_t * title = lv_label_create(scr, NULL); + lv_obj_set_style(title, &tft_style_label_rel); + lv_obj_set_pos(title, TITLE_XPOS, TITLE_YPOS); + lv_label_set_text(title, machine_menu.EncoderConfTitle); + + lv_refr_now(lv_refr_get_disp_refreshing()); + + labelEncoderTips = lv_label_create(scr, NULL); + lv_obj_set_style(labelEncoderTips, &tft_style_label_rel); + lv_obj_set_pos(labelEncoderTips, PARA_UI_POS_X, PARA_UI_POS_Y + 10); + lv_label_set_text(labelEncoderTips, machine_menu.EncoderConfText); + + buttonEncoderState = lv_imgbtn_create(scr, NULL); + lv_obj_set_pos(buttonEncoderState, PARA_UI_STATE_POS_X, PARA_UI_POS_Y + PARA_UI_STATE_V); + if (gCfgItems.encoder_enable) { + lv_imgbtn_set_src(buttonEncoderState, LV_BTN_STATE_REL, "F:/bmp_enable.bin"); + lv_imgbtn_set_src(buttonEncoderState, LV_BTN_STATE_PR, "F:/bmp_enable.bin"); + } + else { + lv_imgbtn_set_src(buttonEncoderState, LV_BTN_STATE_REL, "F:/bmp_disable.bin"); + lv_imgbtn_set_src(buttonEncoderState, LV_BTN_STATE_PR, "F:/bmp_disable.bin"); + } + + lv_obj_set_event_cb_mks(buttonEncoderState, event_handler, ID_ENCODER_STATE, NULL, 0); + + lv_imgbtn_set_style(buttonEncoderState, LV_BTN_STATE_PR, &tft_style_label_pre); + lv_imgbtn_set_style(buttonEncoderState, LV_BTN_STATE_REL, &tft_style_label_rel); + lv_btn_set_layout(buttonEncoderState, LV_LAYOUT_OFF); + labelEncoderState = lv_label_create(buttonEncoderState, NULL); + + line1 = lv_line_create(scr, NULL); + lv_ex_line(line1, line_points[0]); + + buttonBack = lv_imgbtn_create(scr, NULL); + lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_ENCODER_RETURN, NULL, 0); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_back70x40.bin"); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_back70x40.bin"); + lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); + lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); + + lv_obj_set_pos(buttonBack, PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y); + lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); + label_Back = lv_label_create(buttonBack, NULL); + + if (gCfgItems.encoder_enable) { + lv_label_set_text(labelEncoderState, machine_menu.enable); + lv_obj_align(labelEncoderState, buttonEncoderState, LV_ALIGN_CENTER, 0, 0); + } + else { + lv_label_set_text(labelEncoderState, machine_menu.disable); + lv_obj_align(labelEncoderState, buttonEncoderState, LV_ALIGN_CENTER, 0, 0); + } + + lv_label_set_text(label_Back, common_menu.text_back); + lv_obj_align(label_Back, buttonBack, LV_ALIGN_CENTER, 0, 0); + + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonEncoderState); + lv_group_add_obj(g, buttonBack); + } + #endif +} + +void lv_clear_encoder_settings() { + #if HAS_ROTARY_ENCODER + lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // BUTTONS_EXIST(EN1, EN2) + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_encoder_settings.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_encoder_settings.h new file mode 100644 index 0000000000..62892a6ec1 --- /dev/null +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_encoder_settings.h @@ -0,0 +1,33 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#ifdef __cplusplus + extern "C" { /* C-declarations for C++ */ +#endif + +extern void lv_draw_encoder_settings(void); +extern void lv_clear_encoder_settings(); + +#ifdef __cplusplus + } /* C-declarations for C++ */ +#endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_error_message.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_error_message.h index 010b612ff7..8f64d67f93 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_error_message.h +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_error_message.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus -extern "C" { /* C-declarations for C++ */ + extern "C" { /* C-declarations for C++ */ #endif #ifndef PGM_P @@ -34,5 +34,5 @@ extern void lv_clear_error_message(); //extern void disp_temp_ready_print(); #ifdef __cplusplus -} /* C-declarations for C++ */ + } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_extrusion.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_extrusion.cpp index ca84b4b5ec..543202067f 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_extrusion.cpp +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_extrusion.cpp @@ -35,10 +35,11 @@ #include "../../../../gcode/queue.h" static lv_obj_t * scr; +extern lv_group_t* g; static lv_obj_t * buttoType, *buttonStep, *buttonSpeed; -static lv_obj_t * labelType; -static lv_obj_t * labelStep; -static lv_obj_t * labelSpeed; +static lv_obj_t *labelType; +static lv_obj_t *labelStep; +static lv_obj_t *labelSpeed; static lv_obj_t * tempText; static lv_obj_t * ExtruText; @@ -90,7 +91,7 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { // nothing to do } else if (event == LV_EVENT_RELEASED) { - if (EXTRUDERS == 2) { + if (ENABLED(HAS_MULTI_EXTRUDER)) { if (uiCfg.curSprayerChoose == 0) { uiCfg.curSprayerChoose = 1; queue.inject_P(PSTR("T1")); @@ -100,9 +101,9 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { queue.inject_P(PSTR("T0")); } } - else { + else uiCfg.curSprayerChoose = 0; - } + extructAmount = 0; disp_hotend_temp(); disp_ext_type(); @@ -149,7 +150,6 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { } } - void lv_draw_extrusion(void) { lv_obj_t *buttonAdd, *buttonDec, *buttonBack; @@ -172,9 +172,7 @@ void lv_draw_extrusion(void) { lv_refr_now(lv_refr_get_disp_refreshing()); - LV_IMG_DECLARE(bmp_pic); - - /*Create an Image button*/ + // Create image buttons buttonAdd = lv_imgbtn_create(scr, NULL); buttonDec = lv_imgbtn_create(scr, NULL); buttoType = lv_imgbtn_create(scr, NULL); @@ -182,37 +180,35 @@ void lv_draw_extrusion(void) { buttonSpeed = lv_imgbtn_create(scr, NULL); buttonBack = lv_imgbtn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonAdd, event_handler, ID_E_ADD, "bmp_in.bin", 0); - lv_imgbtn_set_src(buttonAdd, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonAdd, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonAdd, event_handler, ID_E_ADD, NULL, 0); + lv_imgbtn_set_src(buttonAdd, LV_BTN_STATE_REL, "F:/bmp_in.bin"); + lv_imgbtn_set_src(buttonAdd, LV_BTN_STATE_PR, "F:/bmp_in.bin"); lv_imgbtn_set_style(buttonAdd, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonAdd, LV_BTN_STATE_REL, &tft_style_label_rel); lv_obj_clear_protect(buttonAdd, LV_PROTECT_FOLLOW); + #if 1 - lv_obj_set_event_cb_mks(buttonDec, event_handler, ID_E_DEC, "bmp_out.bin", 0); - lv_imgbtn_set_src(buttonDec, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonDec, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonDec, event_handler, ID_E_DEC, NULL, 0); + lv_imgbtn_set_src(buttonDec, LV_BTN_STATE_REL, "F:/bmp_out.bin"); + lv_imgbtn_set_src(buttonDec, LV_BTN_STATE_PR, "F:/bmp_out.bin"); lv_imgbtn_set_style(buttonDec, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonDec, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_imgbtn_set_src(buttoType, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttoType, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttoType, event_handler, ID_E_TYPE, NULL, 0); lv_imgbtn_set_style(buttoType, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttoType, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_imgbtn_set_src(buttonStep, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonStep, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonStep, event_handler, ID_E_STEP, NULL, 0); lv_imgbtn_set_style(buttonStep, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonStep, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_imgbtn_set_src(buttonSpeed, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonSpeed, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonSpeed, event_handler, ID_E_SPEED, NULL, 0); lv_imgbtn_set_style(buttonSpeed, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonSpeed, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_E_RETURN, "bmp_return.bin", 0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_E_RETURN, NULL, 0); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_return.bin"); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_return.bin"); lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); #endif @@ -224,7 +220,7 @@ void lv_draw_extrusion(void) { lv_obj_set_pos(buttonSpeed, BTN_X_PIXEL * 2 + INTERVAL_V * 3, BTN_Y_PIXEL + INTERVAL_H + titleHeight); lv_obj_set_pos(buttonBack, BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - /*Create a label on the Image button*/ + // Create labels on the image buttons lv_btn_set_layout(buttonAdd, LV_LAYOUT_OFF); lv_btn_set_layout(buttonDec, LV_LAYOUT_OFF); lv_btn_set_layout(buttoType, LV_LAYOUT_OFF); @@ -232,12 +228,12 @@ void lv_draw_extrusion(void) { lv_btn_set_layout(buttonSpeed, LV_LAYOUT_OFF); lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); - lv_obj_t * labelAdd = lv_label_create(buttonAdd, NULL); - lv_obj_t * labelDec = lv_label_create(buttonDec, NULL); - labelType = lv_label_create(buttoType, NULL); - labelStep = lv_label_create(buttonStep, NULL); - labelSpeed = lv_label_create(buttonSpeed, NULL); - lv_obj_t * label_Back = lv_label_create(buttonBack, NULL); + lv_obj_t *labelAdd = lv_label_create(buttonAdd, NULL); + lv_obj_t *labelDec = lv_label_create(buttonDec, NULL); + labelType = lv_label_create(buttoType, NULL); + labelStep = lv_label_create(buttonStep, NULL); + labelSpeed = lv_label_create(buttonSpeed, NULL); + lv_obj_t *label_Back = lv_label_create(buttonBack, NULL); if (gCfgItems.multiple_language != 0) { lv_label_set_text(labelAdd, extrude_menu.in); @@ -250,6 +246,17 @@ void lv_draw_extrusion(void) { lv_obj_align(label_Back, buttonBack, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); } + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonAdd); + lv_group_add_obj(g, buttonDec); + lv_group_add_obj(g, buttoType); + lv_group_add_obj(g, buttonStep); + lv_group_add_obj(g, buttonSpeed); + lv_group_add_obj(g, buttonBack); + } + #endif + disp_ext_type(); disp_ext_step(); disp_ext_speed(); @@ -265,14 +272,16 @@ void lv_draw_extrusion(void) { void disp_ext_type() { if (uiCfg.curSprayerChoose == 1) { - lv_obj_set_event_cb_mks(buttoType, event_handler, ID_E_TYPE, "bmp_extru2.bin", 0); + lv_imgbtn_set_src(buttoType, LV_BTN_STATE_REL, "F:/bmp_extru2.bin"); + lv_imgbtn_set_src(buttoType, LV_BTN_STATE_PR, "F:/bmp_extru2.bin"); if (gCfgItems.multiple_language != 0) { lv_label_set_text(labelType, extrude_menu.ext2); lv_obj_align(labelType, buttoType, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); } } else { - lv_obj_set_event_cb_mks(buttoType, event_handler, ID_E_TYPE, "bmp_extru1.bin", 0); + lv_imgbtn_set_src(buttoType, LV_BTN_STATE_REL, "F:/bmp_extru1.bin"); + lv_imgbtn_set_src(buttoType, LV_BTN_STATE_PR, "F:/bmp_extru1.bin"); if (gCfgItems.multiple_language != 0) { lv_label_set_text(labelType, extrude_menu.ext1); lv_obj_align(labelType, buttoType, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); @@ -281,12 +290,18 @@ void disp_ext_type() { } void disp_ext_speed() { - if (uiCfg.extruSpeed == 20) - lv_obj_set_event_cb_mks(buttonSpeed, event_handler, ID_E_SPEED, "bmp_speed_high.bin", 0); - else if (uiCfg.extruSpeed == 1) - lv_obj_set_event_cb_mks(buttonSpeed, event_handler, ID_E_SPEED, "bmp_speed_slow.bin", 0); - else - lv_obj_set_event_cb_mks(buttonSpeed, event_handler, ID_E_SPEED, "bmp_speed_normal.bin", 0); + if (uiCfg.extruSpeed == 20) { + lv_imgbtn_set_src(buttonSpeed, LV_BTN_STATE_REL, "F:/bmp_speed_high.bin"); + lv_imgbtn_set_src(buttonSpeed, LV_BTN_STATE_PR, "F:/bmp_speed_high.bin"); + } + else if (uiCfg.extruSpeed == 1) { + lv_imgbtn_set_src(buttonSpeed, LV_BTN_STATE_REL, "F:/bmp_speed_slow.bin"); + lv_imgbtn_set_src(buttonSpeed, LV_BTN_STATE_PR, "F:/bmp_speed_slow.bin"); + } + else { + lv_imgbtn_set_src(buttonSpeed, LV_BTN_STATE_REL, "F:/bmp_speed_normal.bin"); + lv_imgbtn_set_src(buttonSpeed, LV_BTN_STATE_PR, "F:/bmp_speed_normal.bin"); + } if (gCfgItems.multiple_language != 0) { if (uiCfg.extruSpeed == 20) { @@ -349,12 +364,18 @@ void disp_extru_amount() { } void disp_ext_step() { - if (uiCfg.extruStep == 1) - lv_obj_set_event_cb_mks(buttonStep, event_handler, ID_E_STEP, "bmp_step1_mm.bin", 0); - else if (uiCfg.extruStep == 5) - lv_obj_set_event_cb_mks(buttonStep, event_handler, ID_E_STEP, "bmp_step5_mm.bin", 0); - else if (uiCfg.extruStep == 10) - lv_obj_set_event_cb_mks(buttonStep, event_handler, ID_E_STEP, "bmp_step10_mm.bin", 0); + if (uiCfg.extruStep == 1) { + lv_imgbtn_set_src(buttonStep, LV_BTN_STATE_REL, "F:/bmp_step1_mm.bin"); + lv_imgbtn_set_src(buttonStep, LV_BTN_STATE_PR, "F:/bmp_step1_mm.bin"); + } + else if (uiCfg.extruStep == 5) { + lv_imgbtn_set_src(buttonStep, LV_BTN_STATE_REL, "F:/bmp_step5_mm.bin"); + lv_imgbtn_set_src(buttonStep, LV_BTN_STATE_PR, "F:/bmp_step5_mm.bin"); + } + else if (uiCfg.extruStep == 10) { + lv_imgbtn_set_src(buttonStep, LV_BTN_STATE_REL, "F:/bmp_step10_mm.bin"); + lv_imgbtn_set_src(buttonStep, LV_BTN_STATE_PR, "F:/bmp_step10_mm.bin"); + } if (gCfgItems.multiple_language != 0) { if (uiCfg.extruStep == 1) { @@ -372,6 +393,11 @@ void disp_ext_step() { } } -void lv_clear_extrusion() { lv_obj_del(scr); } +void lv_clear_extrusion() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} #endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_extrusion.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_extrusion.h index a7b2afcd8a..576cc6c66c 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_extrusion.h +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_extrusion.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus -extern "C" { /* C-declarations for C++ */ + extern "C" { /* C-declarations for C++ */ #endif extern void lv_draw_extrusion(void); @@ -35,5 +35,5 @@ extern void disp_extru_amount(); //extern void disp_temp_ready_print(); #ifdef __cplusplus -} /* C-declarations for C++ */ + } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_fan.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_fan.cpp index 4dcac62aee..8cdc14964f 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_fan.cpp +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_fan.cpp @@ -35,6 +35,7 @@ #include "../../../../gcode/queue.h" #include "../../../../gcode/gcode.h" +extern lv_group_t * g; static lv_obj_t * scr; static lv_obj_t * fanText; @@ -138,52 +139,52 @@ void lv_draw_fan(void) { lv_refr_now(lv_refr_get_disp_refreshing()); - LV_IMG_DECLARE(bmp_pic); - - /*Create an Image button*/ - buttonAdd = lv_imgbtn_create(scr, NULL); - buttonDec = lv_imgbtn_create(scr, NULL); + // Create an Image button + buttonAdd = lv_imgbtn_create(scr, NULL); + buttonDec = lv_imgbtn_create(scr, NULL); buttonHigh = lv_imgbtn_create(scr, NULL); - buttonMid = lv_imgbtn_create(scr, NULL); - buttonOff = lv_imgbtn_create(scr, NULL); + buttonMid = lv_imgbtn_create(scr, NULL); + buttonOff = lv_imgbtn_create(scr, NULL); buttonBack = lv_imgbtn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonAdd, event_handler, ID_F_ADD, "bmp_Add.bin", 0); - lv_imgbtn_set_src(buttonAdd, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonAdd, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonAdd, event_handler, ID_F_ADD, NULL, 0); + lv_imgbtn_set_src(buttonAdd, LV_BTN_STATE_REL, "F:/bmp_Add.bin"); + lv_imgbtn_set_src(buttonAdd, LV_BTN_STATE_PR, "F:/bmp_Add.bin"); lv_imgbtn_set_style(buttonAdd, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonAdd, LV_BTN_STATE_REL, &tft_style_label_rel); lv_obj_clear_protect(buttonAdd, LV_PROTECT_FOLLOW); + #if 1 - lv_obj_set_event_cb_mks(buttonDec, event_handler, ID_F_DEC, "bmp_Dec.bin", 0); - lv_imgbtn_set_src(buttonDec, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonDec, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonDec, event_handler, ID_F_DEC, NULL, 0); + lv_imgbtn_set_src(buttonDec, LV_BTN_STATE_REL, "F:/bmp_Dec.bin"); + lv_imgbtn_set_src(buttonDec, LV_BTN_STATE_PR, "F:/bmp_Dec.bin"); lv_imgbtn_set_style(buttonDec, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonDec, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_set_event_cb_mks(buttonHigh, event_handler,ID_F_HIGH,"bmp_speed255.bin",0); - lv_imgbtn_set_src(buttonHigh, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonHigh, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonHigh, event_handler,ID_F_HIGH, NULL,0); + lv_imgbtn_set_src(buttonHigh, LV_BTN_STATE_REL, "F:/bmp_speed255.bin"); + lv_imgbtn_set_src(buttonHigh, LV_BTN_STATE_PR, "F:/bmp_speed255.bin"); lv_imgbtn_set_style(buttonHigh, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonHigh, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_set_event_cb_mks(buttonMid, event_handler,ID_F_MID,"bmp_speed127.bin",0); - lv_imgbtn_set_src(buttonMid, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonMid, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonMid, event_handler,ID_F_MID, NULL,0); + lv_imgbtn_set_src(buttonMid, LV_BTN_STATE_REL, "F:/bmp_speed127.bin"); + lv_imgbtn_set_src(buttonMid, LV_BTN_STATE_PR, "F:/bmp_speed127.bin"); lv_imgbtn_set_style(buttonMid, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonMid, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_set_event_cb_mks(buttonOff, event_handler,ID_F_OFF,"bmp_speed0.bin",0); - lv_imgbtn_set_src(buttonOff, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonOff, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonOff, event_handler,ID_F_OFF, NULL,0); + lv_imgbtn_set_src(buttonOff, LV_BTN_STATE_REL, "F:/bmp_speed0.bin"); + lv_imgbtn_set_src(buttonOff, LV_BTN_STATE_PR, "F:/bmp_speed0.bin"); lv_imgbtn_set_style(buttonOff, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonOff, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_set_event_cb_mks(buttonBack, event_handler,ID_F_RETURN,"bmp_return.bin",0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonBack, event_handler,ID_F_RETURN, NULL,0); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_return.bin"); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_return.bin"); lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); + #endif lv_obj_set_pos(buttonAdd, INTERVAL_V, titleHeight); @@ -193,7 +194,7 @@ void lv_draw_fan(void) { lv_obj_set_pos(buttonOff, BTN_X_PIXEL * 2 + INTERVAL_V * 3, BTN_Y_PIXEL + INTERVAL_H + titleHeight); lv_obj_set_pos(buttonBack, BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - /*Create a label on the Image button*/ + // Create labels on the image buttons lv_btn_set_layout(buttonAdd, LV_LAYOUT_OFF); lv_btn_set_layout(buttonDec, LV_LAYOUT_OFF); lv_btn_set_layout(buttonHigh, LV_LAYOUT_OFF); @@ -201,13 +202,12 @@ void lv_draw_fan(void) { lv_btn_set_layout(buttonOff, LV_LAYOUT_OFF); lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); - lv_obj_t * labelAdd = lv_label_create(buttonAdd, NULL); - lv_obj_t * labelDec = lv_label_create(buttonDec, NULL); - lv_obj_t * labelHigh = lv_label_create(buttonHigh, NULL); - lv_obj_t * labelMid = lv_label_create(buttonMid, NULL); - lv_obj_t * labelOff = lv_label_create(buttonOff, NULL); - lv_obj_t * label_Back = lv_label_create(buttonBack, NULL); - + lv_obj_t *labelAdd = lv_label_create(buttonAdd, NULL); + lv_obj_t *labelDec = lv_label_create(buttonDec, NULL); + lv_obj_t *labelHigh = lv_label_create(buttonHigh, NULL); + lv_obj_t *labelMid = lv_label_create(buttonMid, NULL); + lv_obj_t *labelOff = lv_label_create(buttonOff, NULL); + lv_obj_t *label_Back = lv_label_create(buttonBack, NULL); if (gCfgItems.multiple_language != 0) { lv_label_set_text(labelAdd, fan_menu.add); @@ -228,6 +228,16 @@ void lv_draw_fan(void) { lv_label_set_text(label_Back, common_menu.text_back); lv_obj_align(label_Back, buttonBack, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); } + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonAdd); + lv_group_add_obj(g, buttonDec); + lv_group_add_obj(g, buttonHigh); + lv_group_add_obj(g, buttonMid); + lv_group_add_obj(g, buttonOff); + lv_group_add_obj(g, buttonBack); + } + #endif fanText = lv_label_create(scr, NULL); lv_obj_set_style(fanText, &tft_style_label_rel); @@ -245,6 +255,11 @@ void disp_fan_value() { lv_obj_align(fanText, NULL, LV_ALIGN_CENTER, 0, -65); } -void lv_clear_fan() { lv_obj_del(scr); } +void lv_clear_fan() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} #endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_fan.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_fan.h index ef17885926..602d02c6c0 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_fan.h +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_fan.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus -extern "C" { /* C-declarations for C++ */ + extern "C" { /* C-declarations for C++ */ #endif extern void lv_draw_fan(void); @@ -31,5 +31,5 @@ extern void disp_fan_value(); //extern void disp_temp_ready_print(); #ifdef __cplusplus -} /* C-declarations for C++ */ + } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_filament_change.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_filament_change.cpp new file mode 100644 index 0000000000..83f9e53677 --- /dev/null +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_filament_change.cpp @@ -0,0 +1,270 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "lv_conf.h" +#include "draw_ui.h" + +#include "../../../../MarlinCore.h" +#include "../../../../module/temperature.h" +#include "../../../../gcode/queue.h" +#include "../../../../gcode/gcode.h" +#include "../../../../module/motion.h" +#include "../../../../module/planner.h" + +extern lv_group_t * g; +static lv_obj_t * scr; +static lv_obj_t *buttoType; +static lv_obj_t *labelType; +static lv_obj_t * tempText1; + +#define ID_FILAMNT_IN 1 +#define ID_FILAMNT_OUT 2 +#define ID_FILAMNT_TYPE 3 +#define ID_FILAMNT_RETURN 4 + +extern feedRate_t feedrate_mm_s; + +static void event_handler(lv_obj_t * obj, lv_event_t event) { + switch (obj->mks_obj_id) { + case ID_FILAMNT_IN: + if (event == LV_EVENT_CLICKED) { + // nothing to do + } + else if (event == LV_EVENT_RELEASED) { + uiCfg.filament_load_heat_flg = 1; + if ((abs(thermalManager.temp_hotend[uiCfg.curSprayerChoose].target - thermalManager.temp_hotend[uiCfg.curSprayerChoose].celsius) <= 1) + || (gCfgItems.filament_limit_temper <= thermalManager.temp_hotend[uiCfg.curSprayerChoose].celsius)) { + lv_clear_filament_change(); + lv_draw_dialog(DIALOG_TYPE_FILAMENT_HEAT_LOAD_COMPLETED); + } + else { + lv_clear_filament_change(); + lv_draw_dialog(DIALOG_TYPE_FILAMENT_LOAD_HEAT); + if (thermalManager.temp_hotend[uiCfg.curSprayerChoose].target < gCfgItems.filament_limit_temper) { + thermalManager.temp_hotend[uiCfg.curSprayerChoose].target = gCfgItems.filament_limit_temper; + thermalManager.start_watching_hotend(uiCfg.curSprayerChoose); + } + } + } + break; + case ID_FILAMNT_OUT: + if (event == LV_EVENT_CLICKED) { + // nothing to do + } + else if (event == LV_EVENT_RELEASED) { + uiCfg.filament_unload_heat_flg=1; + if ((thermalManager.temp_hotend[uiCfg.curSprayerChoose].target > 0) + && ((abs((int)((int)thermalManager.temp_hotend[uiCfg.curSprayerChoose].target - thermalManager.temp_hotend[uiCfg.curSprayerChoose].celsius)) <= 1) + || ((int)thermalManager.temp_hotend[uiCfg.curSprayerChoose].celsius >= gCfgItems.filament_limit_temper)) + ) { + lv_clear_filament_change(); + lv_draw_dialog(DIALOG_TYPE_FILAMENT_HEAT_UNLOAD_COMPLETED); + } + else { + lv_clear_filament_change(); + lv_draw_dialog(DIALOG_TYPE_FILAMENT_UNLOAD_HEAT); + if (thermalManager.temp_hotend[uiCfg.curSprayerChoose].target < gCfgItems.filament_limit_temper) { + thermalManager.temp_hotend[uiCfg.curSprayerChoose].target = gCfgItems.filament_limit_temper; + thermalManager.start_watching_hotend(uiCfg.curSprayerChoose); + } + filament_sprayer_temp(); + } + } + break; + case ID_FILAMNT_TYPE: + if (event == LV_EVENT_CLICKED) { + // nothing to do + } + else if (event == LV_EVENT_RELEASED) { + #if HAS_MULTI_EXTRUDER + if (uiCfg.curSprayerChoose == 0) + uiCfg.curSprayerChoose = 1; + else if (uiCfg.curSprayerChoose == 1) + uiCfg.curSprayerChoose = 0; + #endif + disp_filament_type(); + } + break; + case ID_FILAMNT_RETURN: + if (event == LV_EVENT_CLICKED) { + // nothing to do + } + else if (event == LV_EVENT_RELEASED) { + #if HAS_MULTI_EXTRUDER + if (uiCfg.print_state != IDLE && uiCfg.print_state != REPRINTED) + gcode.process_subcommands_now_P(uiCfg.curSprayerChoose_bak == 1 ? PSTR("T1") : PSTR("T0")); + #endif + feedrate_mm_s = (float)uiCfg.moveSpeed_bak; + if (uiCfg.print_state == PAUSED) + planner.set_e_position_mm((destination.e = current_position.e = uiCfg.current_e_position_bak)); + //current_position.e = destination.e = uiCfg.current_e_position_bak; + thermalManager.temp_hotend[uiCfg.curSprayerChoose].target = uiCfg.desireSprayerTempBak; + + clear_cur_ui(); + draw_return_ui(); + } + break; + } +} + +void lv_draw_filament_change(void) { + lv_obj_t *buttonIn, *buttonOut; + lv_obj_t *buttonBack; + + if (disp_state_stack._disp_state[disp_state_stack._disp_index] != FILAMENTCHANGE_UI) { + disp_state_stack._disp_index++; + disp_state_stack._disp_state[disp_state_stack._disp_index] = FILAMENTCHANGE_UI; + } + disp_state = FILAMENTCHANGE_UI; + + scr = lv_obj_create(NULL, NULL); + + lv_obj_set_style(scr, &tft_style_scr); + lv_scr_load(scr); + lv_obj_clean(scr); + + lv_obj_t * title = lv_label_create(scr, NULL); + lv_obj_set_style(title, &tft_style_label_rel); + lv_obj_set_pos(title, TITLE_XPOS, TITLE_YPOS); + lv_label_set_text(title, creat_title_text()); + + lv_refr_now(lv_refr_get_disp_refreshing()); + + // Create an Image button + buttonIn = lv_imgbtn_create(scr, NULL); + buttonOut = lv_imgbtn_create(scr, NULL); + buttoType = lv_imgbtn_create(scr, NULL); + buttonBack = lv_imgbtn_create(scr, NULL); + + lv_obj_set_event_cb_mks(buttonIn, event_handler, ID_FILAMNT_IN, NULL, 0); + lv_imgbtn_set_src(buttonIn, LV_BTN_STATE_REL, "F:/bmp_in.bin"); + lv_imgbtn_set_src(buttonIn, LV_BTN_STATE_PR, "F:/bmp_in.bin"); + lv_imgbtn_set_style(buttonIn, LV_BTN_STATE_PR, &tft_style_label_pre); + lv_imgbtn_set_style(buttonIn, LV_BTN_STATE_REL, &tft_style_label_rel); + lv_obj_clear_protect(buttonIn, LV_PROTECT_FOLLOW); + + lv_obj_set_event_cb_mks(buttonOut, event_handler, ID_FILAMNT_OUT, NULL, 0); + lv_imgbtn_set_src(buttonOut, LV_BTN_STATE_REL, "F:/bmp_out.bin"); + lv_imgbtn_set_src(buttonOut, LV_BTN_STATE_PR, "F:/bmp_out.bin"); + lv_imgbtn_set_style(buttonOut, LV_BTN_STATE_PR, &tft_style_label_pre); + lv_imgbtn_set_style(buttonOut, LV_BTN_STATE_REL, &tft_style_label_rel); + + lv_obj_set_event_cb_mks(buttoType, event_handler, ID_FILAMNT_TYPE, NULL, 0); + lv_imgbtn_set_style(buttoType, LV_BTN_STATE_PR, &tft_style_label_pre); + lv_imgbtn_set_style(buttoType, LV_BTN_STATE_REL, &tft_style_label_rel); + + lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_FILAMNT_RETURN, NULL, 0); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_return.bin"); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_return.bin"); + lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); + lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); + + lv_obj_set_pos(buttonIn, INTERVAL_V, titleHeight); + lv_obj_set_pos(buttonOut, BTN_X_PIXEL * 3 + INTERVAL_V * 4, titleHeight); + lv_obj_set_pos(buttoType, INTERVAL_V, BTN_Y_PIXEL + INTERVAL_H + titleHeight); + lv_obj_set_pos(buttonBack, BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight); + + // Create labels on the image buttons + lv_btn_set_layout(buttonIn, LV_LAYOUT_OFF); + lv_btn_set_layout(buttonOut, LV_LAYOUT_OFF); + lv_btn_set_layout(buttoType, LV_LAYOUT_OFF); + lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); + + lv_obj_t *labelIn = lv_label_create(buttonIn, NULL); + lv_obj_t *labelOut = lv_label_create(buttonOut, NULL); + labelType = lv_label_create(buttoType, NULL); + lv_obj_t *label_Back = lv_label_create(buttonBack, NULL); + + if (gCfgItems.multiple_language != 0) { + lv_label_set_text(labelIn, filament_menu.in); + lv_obj_align(labelIn, buttonIn, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + + lv_label_set_text(labelOut, filament_menu.out); + lv_obj_align(labelOut, buttonOut, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + + lv_label_set_text(label_Back, common_menu.text_back); + lv_obj_align(label_Back, buttonBack, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + } + + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonIn); + lv_group_add_obj(g, buttonOut); + lv_group_add_obj(g, buttoType); + lv_group_add_obj(g, buttonBack); + } + #endif + + disp_filament_type(); + + tempText1 = lv_label_create(scr, NULL); + lv_obj_set_style(tempText1, &tft_style_label_rel); + disp_filament_temp(); +} + +void disp_filament_type() { + if (uiCfg.curSprayerChoose == 1) { + lv_imgbtn_set_src(buttoType, LV_BTN_STATE_REL, "F:/bmp_extru2.bin"); + lv_imgbtn_set_src(buttoType, LV_BTN_STATE_PR, "F:/bmp_extru2.bin"); + if (gCfgItems.multiple_language != 0) { + lv_label_set_text(labelType, preheat_menu.ext2); + lv_obj_align(labelType, buttoType, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + } + } + else { + lv_imgbtn_set_src(buttoType, LV_BTN_STATE_REL, "F:/bmp_extru1.bin"); + lv_imgbtn_set_src(buttoType, LV_BTN_STATE_PR, "F:/bmp_extru1.bin"); + if (gCfgItems.multiple_language != 0) { + lv_label_set_text(labelType, preheat_menu.ext1); + lv_obj_align(labelType, buttoType, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + } + } +} + +void disp_filament_temp() { + char buf[20] = {0}; + + public_buf_l[0] = '\0'; + + if (uiCfg.curSprayerChoose < 1) + strcat(public_buf_l, preheat_menu.ext1); + else + strcat(public_buf_l, preheat_menu.ext2); + sprintf(buf, preheat_menu.value_state, (int)thermalManager.temp_hotend[uiCfg.curSprayerChoose].celsius, (int)thermalManager.temp_hotend[uiCfg.curSprayerChoose].target); + + strcat_P(public_buf_l, PSTR(": ")); + strcat(public_buf_l, buf); + lv_label_set_text(tempText1, public_buf_l); + lv_obj_align(tempText1, NULL, LV_ALIGN_CENTER, 0, -50); +} + +void lv_clear_filament_change() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_filament_change.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_filament_change.h new file mode 100644 index 0000000000..b0068f7f0f --- /dev/null +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_filament_change.h @@ -0,0 +1,36 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#ifdef __cplusplus + extern "C" { /* C-declarations for C++ */ +#endif + +extern void lv_draw_filament_change(void); +extern void lv_clear_filament_change(); +extern void disp_filament_type(); +extern void disp_filament_temp(); + +//extern void disp_temp_ready_print(); +#ifdef __cplusplus + } /* C-declarations for C++ */ +#endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_filament_settings.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_filament_settings.cpp new file mode 100644 index 0000000000..06ab35f3f0 --- /dev/null +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_filament_settings.cpp @@ -0,0 +1,329 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "lv_conf.h" +#include "draw_ui.h" + +#include "../../../../MarlinCore.h" +#include "../../../../module/planner.h" + +extern lv_group_t * g; +static lv_obj_t * scr; + +#define ID_FILAMENT_SET_RETURN 1 +#define ID_FILAMENT_SET_IN_LENGTH 2 +#define ID_FILAMENT_SET_IN_SPEED 3 +#define ID_FILAMENT_SET_OUT_LENGTH 4 +#define ID_FILAMENT_SET_OUT_SPEED 5 +#define ID_FILAMENT_SET_TEMP 6 +#define ID_FILAMENT_SET_DOWN 12 +#define ID_FILAMENT_SET_UP 13 + +static void event_handler(lv_obj_t * obj, lv_event_t event) { + switch (obj->mks_obj_id) { + case ID_FILAMENT_SET_RETURN: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + uiCfg.para_ui_page = 0; + lv_clear_filament_settings(); + draw_return_ui(); + } + break; + case ID_FILAMENT_SET_IN_LENGTH: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + value = load_length; + lv_clear_filament_settings(); + lv_draw_number_key(); + } + break; + case ID_FILAMENT_SET_IN_SPEED: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + value = load_speed; + lv_clear_filament_settings(); + lv_draw_number_key(); + } + break; + case ID_FILAMENT_SET_OUT_LENGTH: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + value = unload_length; + lv_clear_filament_settings(); + lv_draw_number_key(); + } + break; + case ID_FILAMENT_SET_OUT_SPEED: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + value = unload_speed; + lv_clear_filament_settings(); + lv_draw_number_key(); + } + break; + case ID_FILAMENT_SET_TEMP: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + value = filament_temp; + lv_clear_filament_settings(); + lv_draw_number_key(); + } + break; + case ID_FILAMENT_SET_UP: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + uiCfg.para_ui_page = 0; + lv_clear_filament_settings(); + lv_draw_filament_settings(); + } + break; + case ID_FILAMENT_SET_DOWN: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + uiCfg.para_ui_page = 1; + lv_clear_filament_settings(); + lv_draw_filament_settings(); + } + break; + } +} + +void lv_draw_filament_settings(void) { + lv_obj_t *buttonBack = NULL, *label_Back = NULL, *buttonTurnPage = NULL, *labelTurnPage = NULL; + lv_obj_t *labelInLengthText = NULL, *buttonInLengthValue = NULL, *labelInLengthValue = NULL; + lv_obj_t *labelInSpeedText = NULL, *buttonInSpeedValue = NULL, *labelInSpeedValue = NULL; + lv_obj_t *labelOutLengthText = NULL, *buttonOutLengthValue = NULL, *labelOutLengthValue = NULL; + lv_obj_t *labelOutSpeedText = NULL, *buttonOutSpeedValue = NULL, *labelOutSpeedValue = NULL; + lv_obj_t *labelTemperText = NULL, *buttonTemperValue = NULL, *labelTemperValue = NULL; + lv_obj_t * line1 = NULL, * line2 = NULL, * line3 = NULL, * line4 = NULL; + if (disp_state_stack._disp_state[disp_state_stack._disp_index] != FILAMENT_SETTINGS_UI) { + disp_state_stack._disp_index++; + disp_state_stack._disp_state[disp_state_stack._disp_index] = FILAMENT_SETTINGS_UI; + } + disp_state = FILAMENT_SETTINGS_UI; + + scr = lv_obj_create(NULL, NULL); + + lv_obj_set_style(scr, &tft_style_scr); + lv_scr_load(scr); + lv_obj_clean(scr); + + lv_obj_t * title = lv_label_create(scr, NULL); + lv_obj_set_style(title, &tft_style_label_rel); + lv_obj_set_pos(title, TITLE_XPOS, TITLE_YPOS); + lv_label_set_text(title, machine_menu.FilamentConfTitle); + + lv_refr_now(lv_refr_get_disp_refreshing()); + + if (uiCfg.para_ui_page != 1) { + labelInLengthText = lv_label_create(scr, NULL); + lv_obj_set_style(labelInLengthText, &tft_style_label_rel); + lv_obj_set_pos(labelInLengthText, PARA_UI_POS_X, PARA_UI_POS_Y + 10); + lv_label_set_text(labelInLengthText, machine_menu.InLength); + + buttonInLengthValue = lv_btn_create(scr, NULL); + lv_obj_set_pos(buttonInLengthValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y + PARA_UI_VALUE_V_2); + lv_obj_set_size(buttonInLengthValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonInLengthValue, event_handler, ID_FILAMENT_SET_IN_LENGTH, NULL, 0); + lv_btn_set_style(buttonInLengthValue, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonInLengthValue, LV_BTN_STYLE_PR, &style_para_value); + labelInLengthValue = lv_label_create(buttonInLengthValue, NULL); + + line1 = lv_line_create(scr, NULL); + lv_ex_line(line1, line_points[0]); + + labelInSpeedText = lv_label_create(scr, NULL); + lv_obj_set_style(labelInSpeedText, &tft_style_label_rel); + lv_obj_set_pos(labelInSpeedText, PARA_UI_POS_X, PARA_UI_POS_Y * 2 + 10); + lv_label_set_text(labelInSpeedText, machine_menu.InSpeed); + + buttonInSpeedValue = lv_btn_create(scr, NULL); + lv_obj_set_pos(buttonInSpeedValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 2 + PARA_UI_VALUE_V_2); + lv_obj_set_size(buttonInSpeedValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonInSpeedValue, event_handler, ID_FILAMENT_SET_IN_SPEED, NULL, 0); + lv_btn_set_style(buttonInSpeedValue, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonInSpeedValue, LV_BTN_STYLE_PR, &style_para_value); + labelInSpeedValue = lv_label_create(buttonInSpeedValue, NULL); + + line2 = lv_line_create(scr, NULL); + lv_ex_line(line2, line_points[1]); + + labelOutLengthText = lv_label_create(scr, NULL); + lv_obj_set_style(labelOutLengthText, &tft_style_label_rel); + lv_obj_set_pos(labelOutLengthText, PARA_UI_POS_X, PARA_UI_POS_Y * 3 + 6); + lv_label_set_text(labelOutLengthText, machine_menu.OutLength); + + buttonOutLengthValue = lv_btn_create(scr, NULL); + lv_obj_set_pos(buttonOutLengthValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 3 + PARA_UI_VALUE_V_2); + lv_obj_set_size(buttonOutLengthValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonOutLengthValue, event_handler, ID_FILAMENT_SET_OUT_LENGTH, NULL, 0); + lv_btn_set_style(buttonOutLengthValue, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonOutLengthValue, LV_BTN_STYLE_PR, &style_para_value); + labelOutLengthValue = lv_label_create(buttonOutLengthValue, NULL); + + line3 = lv_line_create(scr, NULL); + lv_ex_line(line3, line_points[2]); + + labelOutSpeedText = lv_label_create(scr, NULL); + lv_obj_set_style(labelOutSpeedText, &tft_style_label_rel); + lv_obj_set_pos(labelOutSpeedText, PARA_UI_POS_X, PARA_UI_POS_Y * 4 + 10); + lv_label_set_text(labelOutSpeedText, machine_menu.OutSpeed); + + buttonOutSpeedValue = lv_btn_create(scr, NULL); + lv_obj_set_pos(buttonOutSpeedValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 4 + PARA_UI_VALUE_V_2); + lv_obj_set_size(buttonOutSpeedValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonOutSpeedValue, event_handler, ID_FILAMENT_SET_OUT_SPEED, NULL, 0); + lv_btn_set_style(buttonOutSpeedValue, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonOutSpeedValue, LV_BTN_STYLE_PR, &style_para_value); + labelOutSpeedValue = lv_label_create(buttonOutSpeedValue, NULL); + + line4 = lv_line_create(scr, NULL); + lv_ex_line(line4, line_points[3]); + + buttonTurnPage = lv_btn_create(scr, NULL); + lv_obj_set_event_cb_mks(buttonTurnPage, event_handler, ID_FILAMENT_SET_DOWN, NULL, 0); + lv_btn_set_style(buttonTurnPage, LV_BTN_STYLE_REL, &style_para_back); + lv_btn_set_style(buttonTurnPage, LV_BTN_STYLE_PR, &style_para_back); + + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonInLengthValue); + lv_group_add_obj(g, buttonInSpeedValue); + lv_group_add_obj(g, buttonOutLengthValue); + lv_group_add_obj(g, buttonOutSpeedValue); + lv_group_add_obj(g, buttonTurnPage); + } + #endif + } + else { + labelTemperText = lv_label_create(scr, NULL); + lv_obj_set_style(labelTemperText, &tft_style_label_rel); + lv_obj_set_pos(labelTemperText, PARA_UI_POS_X, PARA_UI_POS_Y + 10); + lv_label_set_text(labelTemperText, machine_menu.FilamentTemperature); + + buttonTemperValue = lv_btn_create(scr, NULL); + lv_obj_set_pos(buttonTemperValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y + PARA_UI_VALUE_V_2); + lv_obj_set_size(buttonTemperValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonTemperValue, event_handler, ID_FILAMENT_SET_TEMP, NULL, 0); + lv_btn_set_style(buttonTemperValue, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonTemperValue, LV_BTN_STYLE_PR, &style_para_value); + labelTemperValue = lv_label_create(buttonTemperValue, NULL); + + line1 = lv_line_create(scr, NULL); + lv_ex_line(line1, line_points[0]); + + buttonTurnPage = lv_btn_create(scr, NULL); + lv_obj_set_event_cb_mks(buttonTurnPage, event_handler, ID_FILAMENT_SET_UP, NULL, 0); + lv_btn_set_style(buttonTurnPage, LV_BTN_STYLE_REL, &style_para_back); + lv_btn_set_style(buttonTurnPage, LV_BTN_STYLE_PR, &style_para_back); + + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonTemperValue); + lv_group_add_obj(g, buttonTurnPage); + } + #endif + } + + lv_obj_set_pos(buttonTurnPage, PARA_UI_TURN_PAGE_POS_X, PARA_UI_TURN_PAGE_POS_Y); + lv_obj_set_size(buttonTurnPage, PARA_UI_BACK_BTN_X_SIZE, PARA_UI_BACK_BTN_Y_SIZE); + labelTurnPage = lv_label_create(buttonTurnPage, NULL); + + buttonBack = lv_btn_create(scr, NULL); + lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_FILAMENT_SET_RETURN, NULL, 0); + lv_btn_set_style(buttonBack, LV_BTN_STYLE_REL, &style_para_back); + lv_btn_set_style(buttonBack, LV_BTN_STYLE_PR, &style_para_back); + lv_obj_set_pos(buttonBack, PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y); + lv_obj_set_size(buttonBack, PARA_UI_BACK_BTN_X_SIZE, PARA_UI_BACK_BTN_Y_SIZE); + label_Back = lv_label_create(buttonBack, NULL); + + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonBack); + #endif + + if (gCfgItems.multiple_language != 0) { + if (uiCfg.para_ui_page != 1) { + ZERO(public_buf_l); + sprintf_P(public_buf_l, PSTR("%d"), gCfgItems.filamentchange_load_length); + lv_label_set_text(labelInLengthValue, public_buf_l); + lv_obj_align(labelInLengthValue, buttonInLengthValue, LV_ALIGN_CENTER, 0, 0); + + ZERO(public_buf_l); + sprintf_P(public_buf_l, PSTR("%d"), gCfgItems.filamentchange_load_speed); + lv_label_set_text(labelInSpeedValue, public_buf_l); + lv_obj_align(labelInSpeedValue, buttonInSpeedValue, LV_ALIGN_CENTER, 0, 0); + + ZERO(public_buf_l); + sprintf_P(public_buf_l, PSTR("%d"), gCfgItems.filamentchange_unload_length); + lv_label_set_text(labelOutLengthValue, public_buf_l); + lv_obj_align(labelOutLengthValue, buttonOutLengthValue, LV_ALIGN_CENTER, 0, 0); + + ZERO(public_buf_l); + sprintf_P(public_buf_l, PSTR("%d"), gCfgItems.filamentchange_unload_speed); + lv_label_set_text(labelOutSpeedValue, public_buf_l); + lv_obj_align(labelOutSpeedValue, buttonOutSpeedValue, LV_ALIGN_CENTER, 0, 0); + + lv_label_set_text(labelTurnPage, machine_menu.next); + lv_obj_align(labelTurnPage, buttonTurnPage, LV_ALIGN_CENTER, 0, 0); + } + else { + ZERO(public_buf_l); + sprintf_P(public_buf_l, PSTR("%d"), gCfgItems.filament_limit_temper); + lv_label_set_text(labelTemperValue, public_buf_l); + lv_obj_align(labelTemperValue, buttonTemperValue, LV_ALIGN_CENTER, 0, 0); + + lv_label_set_text(labelTurnPage, machine_menu.previous); + lv_obj_align(labelTurnPage, buttonTurnPage, LV_ALIGN_CENTER, 0, 0); + } + + lv_label_set_text(label_Back, common_menu.text_back); + lv_obj_align(label_Back, buttonBack, LV_ALIGN_CENTER, 0, 0); + } +} + +void lv_clear_filament_settings() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_filament_settings.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_filament_settings.h new file mode 100644 index 0000000000..a5ae542895 --- /dev/null +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_filament_settings.h @@ -0,0 +1,33 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#ifdef __cplusplus + extern "C" { /* C-declarations for C++ */ +#endif + +extern void lv_draw_filament_settings(void); +extern void lv_clear_filament_settings(); + +#ifdef __cplusplus + } /* C-declarations for C++ */ +#endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_home.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_home.cpp index 35d442ebae..22e05f0e00 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_home.cpp +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_home.cpp @@ -34,6 +34,7 @@ #include "draw_ui.h" #include "../../../../gcode/queue.h" +extern lv_group_t * g; static lv_obj_t * scr; #define ID_H_ALL 1 @@ -92,11 +93,10 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { if (event == LV_EVENT_CLICKED) { } else if (event == LV_EVENT_RELEASED) { - lv_obj_del(scr); + lv_clear_home(); lv_draw_tool(); } break; - } } @@ -126,128 +126,93 @@ void lv_draw_home(void) { lv_refr_now(lv_refr_get_disp_refreshing()); - LV_IMG_DECLARE(bmp_pic); - - /*Create an Image button*/ - //buttonWifi = lv_imgbtn_create(scr, NULL); - buttonHomeAll = lv_imgbtn_create(scr, NULL); - buttonHomeX = lv_imgbtn_create(scr, NULL); + // Create image buttons + //buttonWifi = lv_imgbtn_create(scr, NULL); + buttonHomeAll = lv_imgbtn_create(scr, NULL); + buttonHomeX = lv_imgbtn_create(scr, NULL); //buttonContinue = lv_imgbtn_create(scr, NULL); - buttonHomeY = lv_imgbtn_create(scr, NULL); - buttonHomeZ = lv_imgbtn_create(scr, NULL); - buttonBack = lv_imgbtn_create(scr, NULL); - buttonOffAll = lv_imgbtn_create(scr, NULL); - buttonOffXY = lv_imgbtn_create(scr, NULL); - - //lv_obj_set_event_cb_mks(buttonWifi, event_handler,ID_S_WIFI,"bmp_Wifi.bin",0); - //lv_imgbtn_set_src(buttonWifi, LV_BTN_STATE_REL, &bmp_pic); - //lv_imgbtn_set_src(buttonWifi, LV_BTN_STATE_PR, &bmp_pic); - //lv_imgbtn_set_style(buttonWifi, LV_BTN_STATE_PR, &tft_style_label_pre); - //lv_imgbtn_set_style(buttonWifi, LV_BTN_STATE_REL, &tft_style_label_rel); - //lv_obj_clear_protect(buttonWifi, LV_PROTECT_FOLLOW); + buttonHomeY = lv_imgbtn_create(scr, NULL); + buttonHomeZ = lv_imgbtn_create(scr, NULL); + buttonOffAll = lv_imgbtn_create(scr, NULL); + buttonOffXY = lv_imgbtn_create(scr, NULL); + buttonBack = lv_imgbtn_create(scr, NULL); + #if 1 - lv_obj_set_event_cb_mks(buttonHomeAll, event_handler,ID_H_ALL,"bmp_zero.bin",0); - lv_imgbtn_set_src(buttonHomeAll, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonHomeAll, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonHomeAll, event_handler,ID_H_ALL, NULL,0); + lv_imgbtn_set_src(buttonHomeAll, LV_BTN_STATE_REL, "F:/bmp_zeroAll.bin"); + lv_imgbtn_set_src(buttonHomeAll, LV_BTN_STATE_PR, "F:/bmp_zeroAll.bin"); lv_imgbtn_set_style(buttonHomeAll, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonHomeAll, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_set_event_cb_mks(buttonHomeX, event_handler, ID_H_X, "bmp_zeroX.bin", 0); - lv_imgbtn_set_src(buttonHomeX, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonHomeX, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonHomeX, event_handler, ID_H_X, NULL, 0); + lv_imgbtn_set_src(buttonHomeX, LV_BTN_STATE_REL, "F:/bmp_zeroX.bin"); + lv_imgbtn_set_src(buttonHomeX, LV_BTN_STATE_PR, "F:/bmp_zeroX.bin"); lv_imgbtn_set_style(buttonHomeX, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonHomeX, LV_BTN_STATE_REL, &tft_style_label_rel); - //lv_obj_set_event_cb_mks(buttonContinue, event_handler,ID_S_CONTINUE,"bmp_Breakpoint.bin",0); - //lv_imgbtn_set_src(buttonContinue, LV_BTN_STATE_REL, &bmp_pic); - //lv_imgbtn_set_src(buttonContinue, LV_BTN_STATE_PR, &bmp_pic); - //lv_imgbtn_set_style(buttonContinue, LV_BTN_STATE_PR, &tft_style_label_pre); - //lv_imgbtn_set_style(buttonContinue, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonHomeY, event_handler, ID_H_Y, "bmp_zeroY.bin", 0); - lv_imgbtn_set_src(buttonHomeY, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonHomeY, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonHomeY, event_handler, ID_H_Y, NULL, 0); + lv_imgbtn_set_src(buttonHomeY, LV_BTN_STATE_REL, "F:/bmp_zeroY.bin"); + lv_imgbtn_set_src(buttonHomeY, LV_BTN_STATE_PR, "F:/bmp_zeroY.bin"); lv_imgbtn_set_style(buttonHomeY, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonHomeY, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_set_event_cb_mks(buttonHomeZ, event_handler, ID_H_Z, "bmp_zeroZ.bin", 0); - lv_imgbtn_set_src(buttonHomeZ, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonHomeZ, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonHomeZ, event_handler, ID_H_Z, NULL, 0); + lv_imgbtn_set_src(buttonHomeZ, LV_BTN_STATE_REL, "F:/bmp_zeroZ.bin"); + lv_imgbtn_set_src(buttonHomeZ, LV_BTN_STATE_PR, "F:/bmp_zeroZ.bin"); lv_imgbtn_set_style(buttonHomeZ, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonHomeZ, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_set_event_cb_mks(buttonOffAll, event_handler,ID_H_OFF_ALL,"bmp_function1.bin",0); - lv_imgbtn_set_src(buttonOffAll, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonOffAll, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonOffAll, event_handler,ID_H_OFF_ALL, NULL,0); + lv_imgbtn_set_src(buttonOffAll, LV_BTN_STATE_REL, "F:/bmp_function1.bin"); + lv_imgbtn_set_src(buttonOffAll, LV_BTN_STATE_PR, "F:/bmp_function1.bin"); lv_imgbtn_set_style(buttonOffAll, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonOffAll, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_set_event_cb_mks(buttonOffXY, event_handler,ID_H_OFF_XY,"bmp_function1.bin",0); - lv_imgbtn_set_src(buttonOffXY, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonOffXY, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonOffXY, event_handler,ID_H_OFF_XY, NULL,0); + lv_imgbtn_set_src(buttonOffXY, LV_BTN_STATE_REL, "F:/bmp_function1.bin"); + lv_imgbtn_set_src(buttonOffXY, LV_BTN_STATE_PR, "F:/bmp_function1.bin"); lv_imgbtn_set_style(buttonOffXY, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonOffXY, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_set_event_cb_mks(buttonBack, event_handler,ID_H_RETURN,"bmp_return.bin",0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonBack, event_handler,ID_H_RETURN, NULL,0); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_return.bin"); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_return.bin"); lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); #endif - /*lv_obj_set_pos(buttonWifi, INTERVAL_V, titleHeight); - lv_obj_set_pos(buttonFan, BTN_X_PIXEL+INTERVAL_V*2, titleHeight); - lv_obj_set_pos(buttonAbout, BTN_X_PIXEL*2+INTERVAL_V*3, titleHeight); - lv_obj_set_pos(buttonContinue, BTN_X_PIXEL*3+INTERVAL_V*4, titleHeight); - lv_obj_set_pos(buMotorOff, INTERVAL_V, BTN_Y_PIXEL+INTERVAL_H+titleHeight); - lv_obj_set_pos(buttonLanguage, BTN_X_PIXEL+INTERVAL_V*2, BTN_Y_PIXEL+INTERVAL_H+titleHeight); - lv_obj_set_pos(buttonBack, BTN_X_PIXEL*3+INTERVAL_V*4, BTN_Y_PIXEL+INTERVAL_H+titleHeight);*/ - - //lv_obj_set_pos(buttonWifi, INTERVAL_V, titleHeight); + lv_obj_set_pos(buttonHomeAll, INTERVAL_V, titleHeight); lv_obj_set_pos(buttonHomeX, BTN_X_PIXEL + INTERVAL_V * 2, titleHeight); lv_obj_set_pos(buttonHomeY, BTN_X_PIXEL * 2 + INTERVAL_V * 3, titleHeight); - //lv_obj_set_pos(buttonContinue,BTN_X_PIXEL*3+INTERVAL_V*4,titleHeight); lv_obj_set_pos(buttonHomeZ, BTN_X_PIXEL * 3 + INTERVAL_V * 4, titleHeight); - lv_obj_set_pos(buttonHomeAll, INTERVAL_V, titleHeight); lv_obj_set_pos(buttonOffAll, INTERVAL_V, BTN_Y_PIXEL + INTERVAL_H + titleHeight); lv_obj_set_pos(buttonOffXY, BTN_X_PIXEL + INTERVAL_V * 2, BTN_Y_PIXEL + INTERVAL_H + titleHeight); lv_obj_set_pos(buttonBack, BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - /*Create a label on the Image button*/ - //lv_btn_set_layout(buttonWifi, LV_LAYOUT_OFF); + // Create labels on the image buttons lv_btn_set_layout(buttonHomeAll, LV_LAYOUT_OFF); lv_btn_set_layout(buttonHomeX, LV_LAYOUT_OFF); - //lv_btn_set_layout(buttonContinue, LV_LAYOUT_OFF); lv_btn_set_layout(buttonHomeY, LV_LAYOUT_OFF); lv_btn_set_layout(buttonHomeZ, LV_LAYOUT_OFF); lv_btn_set_layout(buttonOffAll, LV_LAYOUT_OFF); lv_btn_set_layout(buttonOffXY, LV_LAYOUT_OFF); lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); - //lv_obj_t * labelWifi= lv_label_create(buttonWifi, NULL); - lv_obj_t * labelHomeAll = lv_label_create(buttonHomeAll, NULL); - lv_obj_t * labelHomeX = lv_label_create(buttonHomeX, NULL); - //lv_obj_t * label_Continue = lv_label_create(buttonContinue, NULL); - lv_obj_t * labelHomeY = lv_label_create(buttonHomeY, NULL); - lv_obj_t * labelHomeZ = lv_label_create(buttonHomeZ, NULL); - lv_obj_t * labelOffAll = lv_label_create(buttonOffAll, NULL); - lv_obj_t * labelOffXY = lv_label_create(buttonOffXY, NULL); - lv_obj_t * label_Back = lv_label_create(buttonBack, NULL); - + lv_obj_t *labelHomeAll = lv_label_create(buttonHomeAll, NULL); + lv_obj_t *labelHomeX = lv_label_create(buttonHomeX, NULL); + lv_obj_t *labelHomeY = lv_label_create(buttonHomeY, NULL); + lv_obj_t *labelHomeZ = lv_label_create(buttonHomeZ, NULL); + lv_obj_t *labelOffAll = lv_label_create(buttonOffAll, NULL); + lv_obj_t *labelOffXY = lv_label_create(buttonOffXY, NULL); + lv_obj_t *label_Back = lv_label_create(buttonBack, NULL); if (gCfgItems.multiple_language != 0) { - //lv_label_set_text(labelWifi, set_menu.wifi); - //lv_obj_align(labelWifi, buttonWifi, LV_ALIGN_IN_BOTTOM_MID,0, BUTTON_TEXT_Y_OFFSET); - lv_label_set_text(labelHomeAll, home_menu.home_all); lv_obj_align(labelHomeAll, buttonHomeAll, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); lv_label_set_text(labelHomeX, home_menu.home_x); lv_obj_align(labelHomeX, buttonHomeX, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - //lv_label_set_text(label_Continue, set_menu.breakpoint); - //lv_obj_align(label_Continue, buttonContinue, LV_ALIGN_IN_BOTTOM_MID,0, BUTTON_TEXT_Y_OFFSET); - lv_label_set_text(labelHomeY, home_menu.home_y); lv_obj_align(labelHomeY, buttonHomeY, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); @@ -263,8 +228,25 @@ void lv_draw_home(void) { lv_label_set_text(label_Back, common_menu.text_back); lv_obj_align(label_Back, buttonBack, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); } + + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonHomeAll); + lv_group_add_obj(g, buttonHomeX); + lv_group_add_obj(g, buttonHomeY); + lv_group_add_obj(g, buttonHomeZ); + lv_group_add_obj(g, buttonOffAll); + lv_group_add_obj(g, buttonOffXY); + lv_group_add_obj(g, buttonBack); + } + #endif } -void lv_clear_home() { lv_obj_del(scr); } +void lv_clear_home() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} #endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_home.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_home.h index e93c0a0fad..c5060127a8 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_home.h +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_home.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus -extern "C" { /* C-declarations for C++ */ + extern "C" { /* C-declarations for C++ */ #endif extern void lv_draw_home(void); @@ -30,5 +30,5 @@ extern void lv_clear_home(); //extern void disp_temp_ready_print(); #ifdef __cplusplus -} /* C-declarations for C++ */ + } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_homing_sensitivity_settings.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_homing_sensitivity_settings.cpp new file mode 100644 index 0000000000..d22eeb157e --- /dev/null +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_homing_sensitivity_settings.cpp @@ -0,0 +1,262 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "lv_conf.h" +#include "draw_ui.h" + +#include "../../../../MarlinCore.h" +#include "../../../../module/planner.h" +#include "../../../../module/probe.h" + +#if USE_SENSORLESS +#include "../../../../module/stepper/indirection.h" +#include "../../../../feature/tmc_util.h" + +extern lv_group_t * g; +static lv_obj_t * scr; + +#define ID_SENSITIVITY_RETURN 1 +#define ID_SENSITIVITY_X 2 +#define ID_SENSITIVITY_Y 3 +#define ID_SENSITIVITY_Z 4 +#define ID_SENSITIVITY_Z2 5 + +static void event_handler(lv_obj_t * obj, lv_event_t event) { + switch (obj->mks_obj_id) { + case ID_SENSITIVITY_RETURN: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + lv_clear_homing_sensitivity_settings(); + draw_return_ui(); + } + break; + case ID_SENSITIVITY_X: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + value = x_sensitivity; + lv_clear_homing_sensitivity_settings(); + lv_draw_number_key(); + } + break; + case ID_SENSITIVITY_Y: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + value = y_sensitivity; + lv_clear_homing_sensitivity_settings(); + lv_draw_number_key(); + } + break; + case ID_SENSITIVITY_Z: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + value = z_sensitivity; + lv_clear_homing_sensitivity_settings(); + lv_draw_number_key(); + } + break; + #if Z2_SENSORLESS + case ID_SENSITIVITY_Z2: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + value = z2_sensitivity; + lv_clear_homing_sensitivity_settings(); + lv_draw_number_key(); + } + break; + #endif + } +} + +void lv_draw_homing_sensitivity_settings(void) { + lv_obj_t *buttonBack = NULL, *label_Back = NULL; + lv_obj_t *labelXText = NULL, *buttonXValue = NULL, *labelXValue = NULL; + lv_obj_t *labelYText = NULL, *buttonYValue = NULL, *labelYValue = NULL; + lv_obj_t *labelZText = NULL, *buttonZValue = NULL, *labelZValue = NULL; + lv_obj_t * line1 = NULL, * line2 = NULL, * line3 = NULL; + #if Z2_SENSORLESS + lv_obj_t *labelZ2Text = NULL, *buttonZ2Value = NULL, *labelZ2Value = NULL; + lv_obj_t * line4 = NULL; + #endif + if (disp_state_stack._disp_state[disp_state_stack._disp_index] != HOMING_SENSITIVITY_UI) { + disp_state_stack._disp_index++; + disp_state_stack._disp_state[disp_state_stack._disp_index] = HOMING_SENSITIVITY_UI; + } + disp_state = HOMING_SENSITIVITY_UI; + + scr = lv_obj_create(NULL, NULL); + + lv_obj_set_style(scr, &tft_style_scr); + lv_scr_load(scr); + lv_obj_clean(scr); + + lv_obj_t * title = lv_label_create(scr, NULL); + lv_obj_set_style(title, &tft_style_label_rel); + lv_obj_set_pos(title, TITLE_XPOS, TITLE_YPOS); + lv_label_set_text(title, machine_menu.HomingSensitivityConfTitle); + + lv_refr_now(lv_refr_get_disp_refreshing()); + + labelXText = lv_label_create(scr, NULL); + lv_obj_set_style(labelXText, &tft_style_label_rel); + lv_obj_set_pos(labelXText, PARA_UI_POS_X, PARA_UI_POS_Y + 10); + lv_label_set_text(labelXText, machine_menu.X_Sensitivity); + + buttonXValue = lv_btn_create(scr, NULL); + lv_obj_set_pos(buttonXValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y + PARA_UI_VALUE_V_2); + lv_obj_set_size(buttonXValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonXValue, event_handler, ID_SENSITIVITY_X, NULL, 0); + lv_btn_set_style(buttonXValue, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonXValue, LV_BTN_STYLE_PR, &style_para_value); + labelXValue = lv_label_create(buttonXValue, NULL); + + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonXValue); + #endif + + line1 = lv_line_create(scr, NULL); + lv_ex_line(line1, line_points[0]); + + labelYText = lv_label_create(scr, NULL); + lv_obj_set_style(labelYText, &tft_style_label_rel); + lv_obj_set_pos(labelYText, PARA_UI_POS_X, PARA_UI_POS_Y * 2 + 10); + lv_label_set_text(labelYText, machine_menu.Y_Sensitivity); + + buttonYValue = lv_btn_create(scr, NULL); + lv_obj_set_pos(buttonYValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 2 + PARA_UI_VALUE_V_2); + lv_obj_set_size(buttonYValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonYValue, event_handler, ID_SENSITIVITY_Y, NULL, 0); + lv_btn_set_style(buttonYValue, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonYValue, LV_BTN_STYLE_PR, &style_para_value); + labelYValue = lv_label_create(buttonYValue, NULL); + + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonYValue); + #endif + + line2 = lv_line_create(scr, NULL); + lv_ex_line(line2, line_points[1]); + + labelZText = lv_label_create(scr, NULL); + lv_obj_set_style(labelZText, &tft_style_label_rel); + lv_obj_set_pos(labelZText, PARA_UI_POS_X, PARA_UI_POS_Y * 3 + 10); + lv_label_set_text(labelZText, machine_menu.Z_Sensitivity); + + buttonZValue = lv_btn_create(scr, NULL); + lv_obj_set_pos(buttonZValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 3 + PARA_UI_VALUE_V_2); + lv_obj_set_size(buttonZValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonZValue, event_handler, ID_SENSITIVITY_Z, NULL, 0); + lv_btn_set_style(buttonZValue, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonZValue, LV_BTN_STYLE_PR, &style_para_value); + labelZValue = lv_label_create(buttonZValue, NULL); + + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable == true) lv_group_add_obj(g, buttonZValue); + #endif + + line3 = lv_line_create(scr, NULL); + lv_ex_line(line3, line_points[2]); + + #if Z2_SENSORLESS + labelZ2Text = lv_label_create(scr, NULL); + lv_obj_set_style(labelZ2Text, &tft_style_label_rel); + lv_obj_set_pos(labelZ2Text, PARA_UI_POS_X, PARA_UI_POS_Y * 4 + 10); + lv_label_set_text(labelZ2Text, machine_menu.Z2_Sensitivity); + + buttonZ2Value = lv_btn_create(scr, NULL); + lv_obj_set_pos(buttonZ2Value, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 4 + PARA_UI_VALUE_V_2); + lv_obj_set_size(buttonZ2Value, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonZ2Value, event_handler, ID_SENSITIVITY_Z2, NULL, 0); + lv_btn_set_style(buttonZ2Value, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonZ2Value, LV_BTN_STYLE_PR, &style_para_value); + labelZ2Value = lv_label_create(buttonZ2Value, NULL); + + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonZ2Value); + #endif + + line4 = lv_line_create(scr, NULL); + lv_ex_line(line4, line_points[3]); + #endif + + buttonBack = lv_btn_create(scr, NULL); + lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_SENSITIVITY_RETURN, NULL, 0); + lv_btn_set_style(buttonBack, LV_BTN_STYLE_REL, &style_para_back); + lv_btn_set_style(buttonBack, LV_BTN_STYLE_PR, &style_para_back); + lv_obj_set_pos(buttonBack, PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y); + lv_obj_set_size(buttonBack, PARA_UI_BACK_BTN_X_SIZE, PARA_UI_BACK_BTN_Y_SIZE); + label_Back = lv_label_create(buttonBack, NULL); + + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonBack); + #endif + + if (gCfgItems.multiple_language != 0) { + ZERO(public_buf_l); + sprintf_P(public_buf_l, PSTR("%d"), TERN(X_SENSORLESS, stepperX.homing_threshold(), 0)); + lv_label_set_text(labelXValue, public_buf_l); + lv_obj_align(labelXValue, buttonXValue, LV_ALIGN_CENTER, 0, 0); + + ZERO(public_buf_l); + sprintf_P(public_buf_l, PSTR("%d"), TERN(Y_SENSORLESS, stepperY.homing_threshold(), 0)); + lv_label_set_text(labelYValue, public_buf_l); + lv_obj_align(labelYValue, buttonYValue, LV_ALIGN_CENTER, 0, 0); + + ZERO(public_buf_l); + sprintf_P(public_buf_l, PSTR("%d"), TERN(Z_SENSORLESS, stepperZ.homing_threshold(), 0)); + lv_label_set_text(labelZValue, public_buf_l); + lv_obj_align(labelZValue, buttonZValue, LV_ALIGN_CENTER, 0, 0); + + #if Z2_SENSORLESS + ZERO(public_buf_l); + sprintf_P(public_buf_l, PSTR("%d"), TERN(Z2_SENSORLESS, stepperZ2.homing_threshold(), 0)); + lv_label_set_text(labelZ2Value, public_buf_l); + lv_obj_align(labelZ2Value, buttonZ2Value, LV_ALIGN_CENTER, 0, 0); + #endif + + lv_label_set_text(label_Back, common_menu.text_back); + lv_obj_align(label_Back, buttonBack, LV_ALIGN_CENTER, 0, 0); + } +} + +void lv_clear_homing_sensitivity_settings() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // USE_SENSORLESS + +#endif // HAS_TFT_LVGL_UI && USE_SENSORLESS diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_homing_sensitivity_settings.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_homing_sensitivity_settings.h new file mode 100644 index 0000000000..0c554702b1 --- /dev/null +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_homing_sensitivity_settings.h @@ -0,0 +1,33 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#ifdef __cplusplus + extern "C" { /* C-declarations for C++ */ +#endif + +extern void lv_draw_homing_sensitivity_settings(void); +extern void lv_clear_homing_sensitivity_settings(); + +#ifdef __cplusplus + } /* C-declarations for C++ */ +#endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_jerk_settings.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_jerk_settings.cpp index a552762cf3..8c359233e6 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_jerk_settings.cpp +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_jerk_settings.cpp @@ -29,6 +29,7 @@ #include "../../../../MarlinCore.h" #include "../../../../module/planner.h" +extern lv_group_t * g; static lv_obj_t * scr; #define ID_JERK_RETURN 1 @@ -93,10 +94,10 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { void lv_draw_jerk_settings(void) { lv_obj_t *buttonBack = NULL, *label_Back = NULL; - lv_obj_t *buttonXText = NULL, *labelXText = NULL, *buttonXValue = NULL, *labelXValue = NULL; - lv_obj_t *buttonYText = NULL, *labelYText = NULL, *buttonYValue = NULL, *labelYValue = NULL; - lv_obj_t *buttonZText = NULL, *labelZText = NULL, *buttonZValue = NULL, *labelZValue = NULL; - lv_obj_t *buttonEText = NULL, *labelEText = NULL, *buttonEValue = NULL, *labelEValue = NULL; + lv_obj_t *labelXText = NULL, *buttonXValue = NULL, *labelXValue = NULL; + lv_obj_t *labelYText = NULL, *buttonYValue = NULL, *labelYValue = NULL; + lv_obj_t *labelZText = NULL, *buttonZValue = NULL, *labelZValue = NULL; + lv_obj_t *labelEText = NULL, *buttonEValue = NULL, *labelEValue = NULL; lv_obj_t * line1 = NULL, * line2 = NULL, * line3 = NULL, * line4 = NULL; if (disp_state_stack._disp_state[disp_state_stack._disp_index] != JERK_UI) { disp_state_stack._disp_index++; @@ -117,109 +118,89 @@ void lv_draw_jerk_settings(void) { lv_refr_now(lv_refr_get_disp_refreshing()); - LV_IMG_DECLARE(bmp_para_back); - // LV_IMG_DECLARE(bmp_para_arrow); - LV_IMG_DECLARE(bmp_para_bank); + labelXText = lv_label_create(scr, NULL); + lv_obj_set_style(labelXText, &tft_style_label_rel); + lv_obj_set_pos(labelXText, PARA_UI_POS_X, PARA_UI_POS_Y + 10); + lv_label_set_text(labelXText, machine_menu.X_Jerk); - buttonXText = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonXText, PARA_UI_POS_X, PARA_UI_POS_Y); /*Set its position*/ - lv_obj_set_size(buttonXText, PARA_UI_VALUE_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - lv_obj_set_event_cb(buttonXText, event_handler); - lv_btn_set_style(buttonXText, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonXText, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonXText, LV_LAYOUT_OFF); - labelXText = lv_label_create(buttonXText, NULL); /*Add a label to the button*/ - - buttonXValue = lv_imgbtn_create(scr, NULL); + buttonXValue = lv_btn_create(scr, NULL); lv_obj_set_pos(buttonXValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y + PARA_UI_VALUE_V); - lv_obj_set_event_cb_mks(buttonXValue, event_handler, ID_JERK_X, "bmp_value_blank.bin", 0); - lv_imgbtn_set_src(buttonXValue, LV_BTN_STATE_REL, &bmp_para_bank); - lv_imgbtn_set_src(buttonXValue, LV_BTN_STATE_PR, &bmp_para_bank); - lv_imgbtn_set_style(buttonXValue, LV_BTN_STATE_PR, &style_para_value_pre); - lv_imgbtn_set_style(buttonXValue, LV_BTN_STATE_REL, &style_para_value_rel); - lv_btn_set_layout(buttonXValue, LV_LAYOUT_OFF); + lv_obj_set_size(buttonXValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonXValue, event_handler, ID_JERK_X, NULL, 0); + lv_btn_set_style(buttonXValue, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonXValue, LV_BTN_STYLE_PR, &style_para_value); labelXValue = lv_label_create(buttonXValue, NULL); line1 = lv_line_create(scr, NULL); lv_ex_line(line1, line_points[0]); - buttonYText = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonYText, PARA_UI_POS_X, PARA_UI_POS_Y * 2); /*Set its position*/ - lv_obj_set_size(buttonYText, PARA_UI_VALUE_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - lv_obj_set_event_cb(buttonYText, event_handler); - lv_btn_set_style(buttonYText, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonYText, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonYText, LV_LAYOUT_OFF); - labelYText = lv_label_create(buttonYText, NULL); /*Add a label to the button*/ + labelYText = lv_label_create(scr, NULL); + lv_obj_set_style(labelYText, &tft_style_label_rel); + lv_obj_set_pos(labelYText, PARA_UI_POS_X, PARA_UI_POS_Y * 2 + 10); + lv_label_set_text(labelYText, machine_menu.Y_Jerk); - buttonYValue = lv_imgbtn_create(scr, NULL); + buttonYValue = lv_btn_create(scr, NULL); lv_obj_set_pos(buttonYValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 2 + PARA_UI_VALUE_V); - lv_obj_set_event_cb_mks(buttonYValue, event_handler, ID_JERK_Y, "bmp_value_blank.bin", 0); - lv_imgbtn_set_src(buttonYValue, LV_BTN_STATE_REL, &bmp_para_bank); - lv_imgbtn_set_src(buttonYValue, LV_BTN_STATE_PR, &bmp_para_bank); - lv_imgbtn_set_style(buttonYValue, LV_BTN_STATE_PR, &style_para_value_pre); - lv_imgbtn_set_style(buttonYValue, LV_BTN_STATE_REL, &style_para_value_rel); - lv_btn_set_layout(buttonYValue, LV_LAYOUT_OFF); + lv_obj_set_size(buttonYValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonYValue, event_handler, ID_JERK_Y, NULL, 0); + lv_btn_set_style(buttonYValue, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonYValue, LV_BTN_STYLE_PR, &style_para_value); labelYValue = lv_label_create(buttonYValue, NULL); line2 = lv_line_create(scr, NULL); lv_ex_line(line2, line_points[1]); - buttonZText = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonZText, PARA_UI_POS_X, PARA_UI_POS_Y * 3); /*Set its position*/ - lv_obj_set_size(buttonZText, PARA_UI_VALUE_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - lv_obj_set_event_cb(buttonZText, event_handler); - lv_btn_set_style(buttonZText, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonZText, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonZText, LV_LAYOUT_OFF); - labelZText = lv_label_create(buttonZText, NULL); /*Add a label to the button*/ + labelZText = lv_label_create(scr, NULL); + lv_obj_set_style(labelZText, &tft_style_label_rel); + lv_obj_set_pos(labelZText, PARA_UI_POS_X, PARA_UI_POS_Y * 3 + 10); + lv_label_set_text(labelZText, machine_menu.Z_Jerk); - buttonZValue = lv_imgbtn_create(scr, NULL); + buttonZValue = lv_btn_create(scr, NULL); lv_obj_set_pos(buttonZValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 3 + PARA_UI_VALUE_V); - lv_obj_set_event_cb_mks(buttonZValue, event_handler, ID_JERK_Z, "bmp_value_blank.bin", 0); - lv_imgbtn_set_src(buttonZValue, LV_BTN_STATE_REL, &bmp_para_bank); - lv_imgbtn_set_src(buttonZValue, LV_BTN_STATE_PR, &bmp_para_bank); - lv_imgbtn_set_style(buttonZValue, LV_BTN_STATE_PR, &style_para_value_pre); - lv_imgbtn_set_style(buttonZValue, LV_BTN_STATE_REL, &style_para_value_rel); - lv_btn_set_layout(buttonZValue, LV_LAYOUT_OFF); + lv_obj_set_size(buttonZValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonZValue, event_handler, ID_JERK_Z, NULL, 0); + lv_btn_set_style(buttonZValue, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonZValue, LV_BTN_STYLE_PR, &style_para_value); labelZValue = lv_label_create(buttonZValue, NULL); line3 = lv_line_create(scr, NULL); lv_ex_line(line3, line_points[2]); - buttonEText = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonEText, PARA_UI_POS_X, PARA_UI_POS_Y * 4); /*Set its position*/ - lv_obj_set_size(buttonEText, PARA_UI_VALUE_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - lv_obj_set_event_cb(buttonEText, event_handler); - lv_btn_set_style(buttonEText, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonEText, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonEText, LV_LAYOUT_OFF); - labelEText = lv_label_create(buttonEText, NULL); /*Add a label to the button*/ + labelEText = lv_label_create(scr, NULL); + lv_obj_set_style(labelEText, &tft_style_label_rel); + lv_obj_set_pos(labelEText, PARA_UI_POS_X, PARA_UI_POS_Y * 4 + 10); + lv_label_set_text(labelEText, machine_menu.E_Jerk); - buttonEValue = lv_imgbtn_create(scr, NULL); + buttonEValue = lv_btn_create(scr, NULL); lv_obj_set_pos(buttonEValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 4 + PARA_UI_VALUE_V); - lv_obj_set_event_cb_mks(buttonEValue, event_handler, ID_JERK_E, "bmp_value_blank.bin", 0); - lv_imgbtn_set_src(buttonEValue, LV_BTN_STATE_REL, &bmp_para_bank); - lv_imgbtn_set_src(buttonEValue, LV_BTN_STATE_PR, &bmp_para_bank); - lv_imgbtn_set_style(buttonEValue, LV_BTN_STATE_PR, &style_para_value_pre); - lv_imgbtn_set_style(buttonEValue, LV_BTN_STATE_REL, &style_para_value_rel); - lv_btn_set_layout(buttonEValue, LV_LAYOUT_OFF); + lv_obj_set_size(buttonEValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonEValue, event_handler, ID_JERK_E, NULL, 0); + lv_btn_set_style(buttonEValue, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonEValue, LV_BTN_STYLE_PR, &style_para_value); labelEValue = lv_label_create(buttonEValue, NULL); line4 = lv_line_create(scr, NULL); lv_ex_line(line4, line_points[3]); - buttonBack = lv_imgbtn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_JERK_RETURN, "bmp_back70x40.bin", 0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, &bmp_para_back); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, &bmp_para_back); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); + buttonBack = lv_btn_create(scr, NULL); + lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_JERK_RETURN, NULL, 0); + lv_btn_set_style(buttonBack, LV_BTN_STYLE_REL, &style_para_back); + lv_btn_set_style(buttonBack, LV_BTN_STYLE_PR, &style_para_back); lv_obj_set_pos(buttonBack, PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y); - lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); + lv_obj_set_size(buttonBack, PARA_UI_BACK_BTN_X_SIZE, PARA_UI_BACK_BTN_Y_SIZE); label_Back = lv_label_create(buttonBack, NULL); + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable == true) { + lv_group_add_obj(g, buttonXValue); + lv_group_add_obj(g, buttonYValue); + lv_group_add_obj(g, buttonZValue); + lv_group_add_obj(g, buttonEValue); + lv_group_add_obj(g, buttonBack); + } + #endif + if (gCfgItems.multiple_language != 0) { ZERO(public_buf_l); sprintf_P(public_buf_l, PSTR("%.1f"), planner.max_jerk[X_AXIS]); @@ -241,23 +222,16 @@ void lv_draw_jerk_settings(void) { lv_label_set_text(labelEValue, public_buf_l); lv_obj_align(labelEValue, buttonEValue, LV_ALIGN_CENTER, 0, 0); - lv_label_set_text(labelXText, machine_menu.X_Jerk); - lv_obj_align(labelXText, buttonXText, LV_ALIGN_IN_LEFT_MID, 0, 0); - - lv_label_set_text(labelYText, machine_menu.Y_Jerk); - lv_obj_align(labelYText, buttonYText, LV_ALIGN_IN_LEFT_MID, 0, 0); - - lv_label_set_text(labelZText, machine_menu.Z_Jerk); - lv_obj_align(labelZText, buttonZText, LV_ALIGN_IN_LEFT_MID, 0, 0); - - lv_label_set_text(labelEText, machine_menu.E_Jerk); - lv_obj_align(labelEText, buttonEText, LV_ALIGN_IN_LEFT_MID, 0, 0); - lv_label_set_text(label_Back, common_menu.text_back); lv_obj_align(label_Back, buttonBack, LV_ALIGN_CENTER, 0, 0); } } -void lv_clear_jerk_settings() { lv_obj_del(scr); } +void lv_clear_jerk_settings() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} #endif // HAS_TFT_LVGL_UI && HAS_CLASSIC_JERK diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_jerk_settings.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_jerk_settings.h index 5badcde529..0531dae9da 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_jerk_settings.h +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_jerk_settings.h @@ -22,12 +22,12 @@ #pragma once #ifdef __cplusplus -extern "C" { /* C-declarations for C++ */ + extern "C" { /* C-declarations for C++ */ #endif extern void lv_draw_jerk_settings(void); extern void lv_clear_jerk_settings(); #ifdef __cplusplus -} /* C-declarations for C++ */ + } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_keyboard.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_keyboard.cpp new file mode 100644 index 0000000000..f126ffe1dd --- /dev/null +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_keyboard.cpp @@ -0,0 +1,286 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "lv_conf.h" +#include "draw_ui.h" + +#include "../../../../../Configuration.h" +#include "../../../../MarlinCore.h" + +extern lv_group_t * g; +static lv_obj_t * scr; + +#define LV_KB_CTRL_BTN_FLAGS (LV_BTNM_CTRL_NO_REPEAT | LV_BTNM_CTRL_CLICK_TRIG) + +static const char * kb_map_lc[] = {"1#", "q", "w", "e", "r", "t", "y", "u", "i", "o", "p", LV_SYMBOL_BACKSPACE, "\n", + "ABC", "a", "s", "d", "f", "g", "h", "j", "k", "l", LV_SYMBOL_NEW_LINE, "\n", + "_", "-", "z", "x", "c", "v", "b", "n", "m", ".", ",", ":", "\n", + LV_SYMBOL_CLOSE, LV_SYMBOL_LEFT, " ", LV_SYMBOL_RIGHT, LV_SYMBOL_OK, ""}; + +static const lv_btnm_ctrl_t kb_ctrl_lc_map[] = { + LV_KB_CTRL_BTN_FLAGS | 5, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 7, + LV_KB_CTRL_BTN_FLAGS | 6, 3, 3, 3, 3, 3, 3, 3, 3, 3, 7, + 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, + LV_KB_CTRL_BTN_FLAGS | 2, 2, 6, 2, LV_KB_CTRL_BTN_FLAGS | 2}; + +static const char * kb_map_uc[] = {"1#", "Q", "W", "E", "R", "T", "Y", "U", "I", "O", "P", LV_SYMBOL_BACKSPACE, "\n", + "abc", "A", "S", "D", "F", "G", "H", "J", "K", "L", LV_SYMBOL_NEW_LINE, "\n", + "_", "-", "Z", "X", "C", "V", "B", "N", "M", ".", ",", ":", "\n", + LV_SYMBOL_CLOSE, LV_SYMBOL_LEFT, " ", LV_SYMBOL_RIGHT, LV_SYMBOL_OK, ""}; + +static const lv_btnm_ctrl_t kb_ctrl_uc_map[] = { + LV_KB_CTRL_BTN_FLAGS | 5, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 7, + LV_KB_CTRL_BTN_FLAGS | 6, 3, 3, 3, 3, 3, 3, 3, 3, 3, 7, + 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, + LV_KB_CTRL_BTN_FLAGS | 2, 2, 6, 2, LV_KB_CTRL_BTN_FLAGS | 2}; + +static const char * kb_map_spec[] = {"0", "1", "2", "3", "4" ,"5", "6", "7", "8", "9", LV_SYMBOL_BACKSPACE, "\n", + "abc", "+", "-", "/", "*", "=", "%", "!", "?", "#", "<", ">", "\n", + "\\", "@", "$", "(", ")", "{", "}", "[", "]", ";", "\"", "'", "\n", + LV_SYMBOL_CLOSE, LV_SYMBOL_LEFT, " ", LV_SYMBOL_RIGHT, LV_SYMBOL_OK, ""}; + +static const lv_btnm_ctrl_t kb_ctrl_spec_map[] = { + 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, LV_KB_CTRL_BTN_FLAGS | 2, + LV_KB_CTRL_BTN_FLAGS | 2, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, + 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, + LV_KB_CTRL_BTN_FLAGS | 2, 2, 6, 2, LV_KB_CTRL_BTN_FLAGS | 2}; + +static const lv_btnm_ctrl_t kb_ctrl_num_map[] = { + 1, 1, 1, LV_KB_CTRL_BTN_FLAGS | 2, + 1, 1, 1, LV_KB_CTRL_BTN_FLAGS | 2, + 1, 1, 1, 2, + 1, 1, 1, 1, 1}; + +static void lv_kb_event_cb(lv_obj_t * kb, lv_event_t event) { + //LV_ASSERT_OBJ(kb, LV_OBJX_NAME); + + if (event != LV_EVENT_VALUE_CHANGED) return; + + lv_kb_ext_t * ext = (lv_kb_ext_t * )lv_obj_get_ext_attr(kb); + const uint16_t btn_id = lv_btnm_get_active_btn(kb); + if (btn_id == LV_BTNM_BTN_NONE) return; + if (lv_btnm_get_btn_ctrl(kb, btn_id, LV_BTNM_CTRL_HIDDEN | LV_BTNM_CTRL_INACTIVE)) return; + if (lv_btnm_get_btn_ctrl(kb, btn_id, LV_BTNM_CTRL_NO_REPEAT) && event == LV_EVENT_LONG_PRESSED_REPEAT) return; + + const char * txt = lv_btnm_get_active_btn_text(kb); + if (txt == NULL) return; + + // Do the corresponding action according to the text of the button + if (strcmp(txt, "abc") == 0) { + lv_btnm_set_map(kb, kb_map_lc); + lv_btnm_set_ctrl_map(kb, kb_ctrl_lc_map); + return; + } + else if (strcmp(txt, "ABC") == 0) { + lv_btnm_set_map(kb, kb_map_uc); + lv_btnm_set_ctrl_map(kb, kb_ctrl_uc_map); + return; + } + else if (strcmp(txt, "1#") == 0) { + lv_btnm_set_map(kb, kb_map_spec); + lv_btnm_set_ctrl_map(kb, kb_ctrl_spec_map); + return; + } + else if (strcmp(txt, LV_SYMBOL_CLOSE) == 0) { + if (kb->event_cb != lv_kb_def_event_cb) { + //lv_res_t res = lv_event_send(kb, LV_EVENT_CANCEL, NULL); + //if (res != LV_RES_OK) return; + lv_clear_keyboard(); + draw_return_ui(); + } + else { + lv_kb_set_ta(kb, NULL); /*De-assign the text area to hide it cursor if needed*/ + lv_obj_del(kb); + return; + } + return; + } + else if (strcmp(txt, LV_SYMBOL_OK) == 0) { + if (kb->event_cb != lv_kb_def_event_cb) { + //lv_res_t res = lv_event_send(kb, LV_EVENT_APPLY, NULL); + //if (res != LV_RES_OK) return; + const char * ret_ta_txt = lv_ta_get_text(ext->ta); + switch (keyboard_value) { + #if ENABLED(USE_WIFI_FUNCTION) + case wifiName: + memcpy(uiCfg.wifi_name,ret_ta_txt,sizeof(uiCfg.wifi_name)); + lv_clear_keyboard(); + draw_return_ui(); + break; + case wifiPassWord: + memcpy(uiCfg.wifi_key,ret_ta_txt,sizeof(uiCfg.wifi_name)); + lv_clear_keyboard(); + draw_return_ui(); + break; + case wifiConfig: + memset((void *)uiCfg.wifi_name, 0, sizeof(uiCfg.wifi_name)); + memcpy((void *)uiCfg.wifi_name, wifi_list.wifiName[wifi_list.nameIndex], 32); + + memset((void *)uiCfg.wifi_key, 0, sizeof(uiCfg.wifi_key)); + memcpy((void *)uiCfg.wifi_key, ret_ta_txt, sizeof(uiCfg.wifi_key)); + + gCfgItems.wifi_mode_sel = STA_MODEL; + + package_to_wifi(WIFI_PARA_SET, (char *)0, 0); + + memset(public_buf_l,0,sizeof(public_buf_l)); + + public_buf_l[0] = 0xA5; + public_buf_l[1] = 0x09; + public_buf_l[2] = 0x01; + public_buf_l[3] = 0x00; + public_buf_l[4] = 0x01; + public_buf_l[5] = 0xFC; + public_buf_l[6] = 0x00; + raw_send_to_wifi(public_buf_l, 6); + + last_disp_state = KEY_BOARD_UI; + lv_clear_keyboard(); + wifi_tips_type = TIPS_TYPE_JOINING; + lv_draw_wifi_tips(); + break; + #endif // USE_WIFI_FUNCTION + case gcodeCommand: + uint8_t buf[100]; + strncpy((char *)buf,ret_ta_txt,sizeof(buf)); + update_gcode_command(AUTO_LEVELING_COMMAND_ADDR,buf); + lv_clear_keyboard(); + draw_return_ui(); + break; + default: break; + } + } + else { + lv_kb_set_ta(kb, NULL); /*De-assign the text area to hide it cursor if needed*/ + } + return; + } + + /*Add the characters to the text area if set*/ + if (ext->ta == NULL) return; + + if (strcmp(txt, "Enter") == 0 || strcmp(txt, LV_SYMBOL_NEW_LINE) == 0) + lv_ta_add_char(ext->ta, '\n'); + else if (strcmp(txt, LV_SYMBOL_LEFT) == 0) + lv_ta_cursor_left(ext->ta); + else if (strcmp(txt, LV_SYMBOL_RIGHT) == 0) + lv_ta_cursor_right(ext->ta); + else if (strcmp(txt, LV_SYMBOL_BACKSPACE) == 0) + lv_ta_del_char(ext->ta); + else if (strcmp(txt, "+/-") == 0) { + uint16_t cur = lv_ta_get_cursor_pos(ext->ta); + const char * ta_txt = lv_ta_get_text(ext->ta); + if (ta_txt[0] == '-') { + lv_ta_set_cursor_pos(ext->ta, 1); + lv_ta_del_char(ext->ta); + lv_ta_add_char(ext->ta, '+'); + lv_ta_set_cursor_pos(ext->ta, cur); + } + else if (ta_txt[0] == '+') { + lv_ta_set_cursor_pos(ext->ta, 1); + lv_ta_del_char(ext->ta); + lv_ta_add_char(ext->ta, '-'); + lv_ta_set_cursor_pos(ext->ta, cur); + } + else { + lv_ta_set_cursor_pos(ext->ta, 0); + lv_ta_add_char(ext->ta, '-'); + lv_ta_set_cursor_pos(ext->ta, cur + 1); + } + } + else { + lv_ta_add_text(ext->ta, txt); + } +} + +void lv_draw_keyboard() { + if (disp_state_stack._disp_state[disp_state_stack._disp_index] != KEY_BOARD_UI) { + disp_state_stack._disp_index++; + disp_state_stack._disp_state[disp_state_stack._disp_index] = KEY_BOARD_UI; + } + disp_state = KEY_BOARD_UI; + + scr = lv_obj_create(NULL, NULL); + + lv_obj_set_style(scr, &tft_style_scr); + lv_scr_load(scr); + lv_obj_clean(scr); + + lv_refr_now(lv_refr_get_disp_refreshing()); + + /*Create styles for the keyboard*/ + static lv_style_t rel_style, pr_style; + + lv_style_copy(&rel_style, &lv_style_btn_rel); + rel_style.body.radius = 0; + rel_style.body.border.width = 1; + rel_style.body.main_color = lv_color_make(0xa9, 0x62, 0x1d); + rel_style.body.grad_color = lv_color_make(0xa7, 0x59, 0x0e); + + lv_style_copy(&pr_style, &lv_style_btn_pr); + pr_style.body.radius = 0; + pr_style.body.border.width = 1; + pr_style.body.main_color = lv_color_make(0x72, 0x42, 0x15); + pr_style.body.grad_color = lv_color_make(0x6a, 0x3a, 0x0c); + + /*Create a keyboard and apply the styles*/ + lv_obj_t *kb = lv_kb_create(scr, NULL); + lv_obj_set_event_cb(kb, lv_kb_event_cb); + lv_kb_set_cursor_manage(kb, true); + lv_kb_set_style(kb, LV_KB_STYLE_BG, &lv_style_transp_tight); + lv_kb_set_style(kb, LV_KB_STYLE_BTN_REL, &rel_style); + lv_kb_set_style(kb, LV_KB_STYLE_BTN_PR, &pr_style); + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + //lv_group_add_obj(g, kb); + //lv_group_set_editing(g, true); + } + #endif + + /*Create a text area. The keyboard will write here*/ + lv_obj_t *ta = lv_ta_create(scr, NULL); + lv_obj_align(ta, NULL, LV_ALIGN_IN_TOP_MID, 0, 10); + if (keyboard_value == gcodeCommand) { + get_gcode_command(AUTO_LEVELING_COMMAND_ADDR,(uint8_t *)public_buf_m); + public_buf_m[sizeof(public_buf_m)-1] = 0; + lv_ta_set_text(ta, public_buf_m); + } + else { + lv_ta_set_text(ta, ""); + } + + /*Assign the text area to the keyboard*/ + lv_kb_set_ta(kb, ta); +} + +void lv_clear_keyboard() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { /* lv_group_remove_all_objs(g); */ } + #endif + lv_obj_del(scr); +} + + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_keyboard.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_keyboard.h new file mode 100644 index 0000000000..0013dc4030 --- /dev/null +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_keyboard.h @@ -0,0 +1,33 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#ifdef __cplusplus + extern "C" { /* C-declarations for C++ */ +#endif + +extern void lv_draw_keyboard(); +extern void lv_clear_keyboard(); + +#ifdef __cplusplus + } /* C-declarations for C++ */ +#endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_language.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_language.cpp index 65d0961248..3e4ad06477 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_language.cpp +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_language.cpp @@ -49,6 +49,7 @@ static void disp_language(uint8_t language, uint8_t state); +extern lv_group_t * g; static lv_obj_t * scr; static lv_obj_t *buttonCN, *buttonT_CN, *buttonEN, *buttonRU; static lv_obj_t *buttonES, *buttonFR, *buttonIT, *buttonBack; @@ -61,9 +62,11 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { } else if (event == LV_EVENT_RELEASED) { disp_language(gCfgItems.language, UNSELECTED); - lv_obj_set_event_cb_mks(buttonCN, event_handler, ID_CN, "bmp_simplified_cn_sel.bin", 0); + lv_imgbtn_set_src(buttonCN, LV_BTN_STATE_REL, "F:/bmp_simplified_cn_sel.bin"); + lv_imgbtn_set_src(buttonCN, LV_BTN_STATE_PR, "F:/bmp_simplified_cn_sel.bin"); + lv_obj_refresh_ext_draw_pad(buttonCN); gCfgItems.language = LANG_SIMPLE_CHINESE; - gCfg_to_spiFlah(); + update_spi_flash(); disp_language_init(); } break; @@ -73,9 +76,11 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { } else if (event == LV_EVENT_RELEASED) { disp_language(gCfgItems.language, UNSELECTED); - lv_obj_set_event_cb_mks(buttonT_CN, event_handler, ID_T_CN, "bmp_traditional_cn_sel.bin", 0); + lv_imgbtn_set_src(buttonT_CN, LV_BTN_STATE_REL, "F:/bmp_traditional_cn_sel.bin"); + lv_imgbtn_set_src(buttonT_CN, LV_BTN_STATE_PR, "F:/bmp_traditional_cn_sel.bin"); + lv_obj_refresh_ext_draw_pad(buttonT_CN); gCfgItems.language = LANG_COMPLEX_CHINESE; - gCfg_to_spiFlah(); + update_spi_flash(); disp_language_init(); } break; @@ -85,9 +90,11 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { } else if (event == LV_EVENT_RELEASED) { disp_language(gCfgItems.language, UNSELECTED); - lv_obj_set_event_cb_mks(buttonEN, event_handler, ID_EN, "bmp_english_sel.bin", 0); + lv_imgbtn_set_src(buttonEN, LV_BTN_STATE_REL, "F:/bmp_english_sel.bin"); + lv_imgbtn_set_src(buttonEN, LV_BTN_STATE_PR, "F:/bmp_english_sel.bin"); + lv_obj_refresh_ext_draw_pad(buttonEN); gCfgItems.language = LANG_ENGLISH; - gCfg_to_spiFlah(); + update_spi_flash(); disp_language_init(); } break; @@ -97,9 +104,11 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { } else if (event == LV_EVENT_RELEASED) { disp_language(gCfgItems.language, UNSELECTED); - lv_obj_set_event_cb_mks(buttonRU, event_handler, ID_RU, "bmp_russian_sel.bin", 0); + lv_imgbtn_set_src(buttonRU, LV_BTN_STATE_REL, "F:/bmp_russian_sel.bin"); + lv_imgbtn_set_src(buttonRU, LV_BTN_STATE_PR, "F:/bmp_russian_sel.bin"); + lv_obj_refresh_ext_draw_pad(buttonRU); gCfgItems.language = LANG_RUSSIAN; - gCfg_to_spiFlah(); + update_spi_flash(); disp_language_init(); } break; @@ -109,9 +118,11 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { } else if (event == LV_EVENT_RELEASED) { disp_language(gCfgItems.language, UNSELECTED); - lv_obj_set_event_cb_mks(buttonES, event_handler, ID_ES, "bmp_spanish_sel.bin", 0); + lv_imgbtn_set_src(buttonES, LV_BTN_STATE_REL, "F:/bmp_spanish_sel.bin"); + lv_imgbtn_set_src(buttonES, LV_BTN_STATE_PR, "F:/bmp_spanish_sel.bin"); + lv_obj_refresh_ext_draw_pad(buttonES); gCfgItems.language = LANG_SPANISH; - gCfg_to_spiFlah(); + update_spi_flash(); disp_language_init(); } break; @@ -121,9 +132,11 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { } else if (event == LV_EVENT_RELEASED) { disp_language(gCfgItems.language, UNSELECTED); - lv_obj_set_event_cb_mks(buttonFR, event_handler, ID_FR, "bmp_french_sel.bin", 0); + lv_imgbtn_set_src(buttonFR, LV_BTN_STATE_REL, "F:/bmp_french_sel.bin"); + lv_imgbtn_set_src(buttonFR, LV_BTN_STATE_PR, "F:/bmp_french_sel.bin"); + lv_obj_refresh_ext_draw_pad(buttonFR); gCfgItems.language = LANG_FRENCH; - gCfg_to_spiFlah(); + update_spi_flash(); disp_language_init(); } break; @@ -133,9 +146,11 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { } else if (event == LV_EVENT_RELEASED) { disp_language(gCfgItems.language, UNSELECTED); - lv_obj_set_event_cb_mks(buttonIT, event_handler, ID_FR, "bmp_italy_sel.bin", 0); + lv_imgbtn_set_src(buttonIT, LV_BTN_STATE_REL, "F:/bmp_italy_sel.bin"); + lv_imgbtn_set_src(buttonIT, LV_BTN_STATE_PR, "F:/bmp_italy_sel.bin"); + lv_obj_refresh_ext_draw_pad(buttonIT); gCfgItems.language = LANG_ITALY; - gCfg_to_spiFlah(); + update_spi_flash(); disp_language_init(); } break; @@ -154,8 +169,7 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { buttonFR = NULL; buttonIT = NULL; buttonBack = NULL; - - lv_obj_del(scr); + lv_clear_language(); lv_draw_set(); } break; @@ -172,42 +186,42 @@ static void disp_language(uint8_t language, uint8_t state) { switch (language) { case LANG_SIMPLE_CHINESE: id = ID_CN; - strcpy_P(public_buf_l, PSTR("bmp_simplified_cn")); + strcpy_P(public_buf_l, PSTR("F:/bmp_simplified_cn")); obj = buttonCN; break; case LANG_COMPLEX_CHINESE: id = ID_T_CN; - strcpy_P(public_buf_l, PSTR("bmp_traditional_cn")); + strcpy_P(public_buf_l, PSTR("F:/bmp_traditional_cn")); obj = buttonT_CN; break; case LANG_ENGLISH: id = ID_EN; - strcpy_P(public_buf_l, PSTR("bmp_english")); + strcpy_P(public_buf_l, PSTR("F:/bmp_english")); obj = buttonEN; break; case LANG_RUSSIAN: id = ID_RU; - strcpy_P(public_buf_l, PSTR("bmp_russian")); + strcpy_P(public_buf_l, PSTR("F:/bmp_russian")); obj = buttonRU; break; case LANG_SPANISH: id = ID_ES; - strcpy_P(public_buf_l, PSTR("bmp_spanish")); + strcpy_P(public_buf_l, PSTR("F:/bmp_spanish")); obj = buttonES; break; case LANG_FRENCH: id = ID_FR; - strcpy_P(public_buf_l, PSTR("bmp_french")); + strcpy_P(public_buf_l, PSTR("F:/bmp_french")); obj = buttonFR; break; case LANG_ITALY: id = ID_IT; - strcpy_P(public_buf_l, PSTR("bmp_italy")); + strcpy_P(public_buf_l, PSTR("F:/bmp_italy")); obj = buttonIT; break; default: id = ID_CN; - strcpy_P(public_buf_l, PSTR("bmp_simplified_cn")); + strcpy_P(public_buf_l, PSTR("F:/bmp_simplified_cn")); obj = buttonCN; break; } @@ -216,7 +230,9 @@ static void disp_language(uint8_t language, uint8_t state) { strcat_P(public_buf_l, PSTR(".bin")); - lv_obj_set_event_cb_mks(obj, event_handler, id, public_buf_l, 0); + lv_obj_set_event_cb_mks(obj, event_handler, id, NULL, 0); + lv_imgbtn_set_src(obj, LV_BTN_STATE_REL, public_buf_l); + lv_imgbtn_set_src(obj, LV_BTN_STATE_PR, public_buf_l); if (state == UNSELECTED) lv_obj_refresh_ext_draw_pad(obj); } @@ -244,9 +260,7 @@ void lv_draw_language(void) { lv_refr_now(lv_refr_get_disp_refreshing()); - LV_IMG_DECLARE(bmp_pic); - - /*Create an Image button*/ + // Create image buttons buttonCN = lv_imgbtn_create(scr, NULL); buttonT_CN = lv_imgbtn_create(scr, NULL); buttonEN = lv_imgbtn_create(scr, NULL); @@ -256,54 +270,56 @@ void lv_draw_language(void) { buttonIT = lv_imgbtn_create(scr, NULL); buttonBack = lv_imgbtn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonCN, event_handler, ID_CN, "bmp_simplified_cn.bin", 0); - lv_imgbtn_set_src(buttonCN, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonCN, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonCN, event_handler, ID_CN, NULL, 0); + lv_imgbtn_set_src(buttonCN, LV_BTN_STATE_REL, "F:/bmp_simplified_cn.bin"); + lv_imgbtn_set_src(buttonCN, LV_BTN_STATE_PR, "F:/bmp_simplified_cn.bin"); lv_imgbtn_set_style(buttonCN, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonCN, LV_BTN_STATE_REL, &tft_style_label_rel); lv_obj_clear_protect(buttonCN, LV_PROTECT_FOLLOW); + #if 1 - lv_obj_set_event_cb_mks(buttonT_CN, event_handler, ID_T_CN, "bmp_traditional_cn.bin", 0); - lv_imgbtn_set_src(buttonT_CN, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonT_CN, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonT_CN, event_handler, ID_T_CN, NULL, 0); + lv_imgbtn_set_src(buttonT_CN, LV_BTN_STATE_REL, "F:/bmp_traditional_cn.bin"); + lv_imgbtn_set_src(buttonT_CN, LV_BTN_STATE_PR, "F:/bmp_traditional_cn.bin"); lv_imgbtn_set_style(buttonT_CN, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonT_CN, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_set_event_cb_mks(buttonEN, event_handler, ID_EN, "bmp_english.bin", 0); - lv_imgbtn_set_src(buttonEN, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonEN, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonEN, event_handler, ID_EN, NULL, 0); + lv_imgbtn_set_src(buttonEN, LV_BTN_STATE_REL, "F:/bmp_english.bin"); + lv_imgbtn_set_src(buttonEN, LV_BTN_STATE_PR, "F:/bmp_english.bin"); lv_imgbtn_set_style(buttonEN, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonEN, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_set_event_cb_mks(buttonRU, event_handler, ID_RU, "bmp_russian.bin", 0); - lv_imgbtn_set_src(buttonRU, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonRU, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonRU, event_handler, ID_RU, NULL, 0); + lv_imgbtn_set_src(buttonRU, LV_BTN_STATE_REL, "F:/bmp_russian.bin"); + lv_imgbtn_set_src(buttonRU, LV_BTN_STATE_PR, "F:/bmp_russian.bin"); lv_imgbtn_set_style(buttonRU, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonRU, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_set_event_cb_mks(buttonES, event_handler, ID_ES, "bmp_spanish.bin", 0); - lv_imgbtn_set_src(buttonES, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonES, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonES, event_handler, ID_ES, NULL, 0); + lv_imgbtn_set_src(buttonES, LV_BTN_STATE_REL, "F:/bmp_spanish.bin"); + lv_imgbtn_set_src(buttonES, LV_BTN_STATE_PR, "F:/bmp_spanish.bin"); lv_imgbtn_set_style(buttonES, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonES, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_set_event_cb_mks(buttonFR, event_handler, ID_FR, "bmp_french.bin", 0); - lv_imgbtn_set_src(buttonFR, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonFR, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonFR, event_handler, ID_FR, NULL, 0); + lv_imgbtn_set_src(buttonFR, LV_BTN_STATE_REL, "F:/bmp_french.bin"); + lv_imgbtn_set_src(buttonFR, LV_BTN_STATE_PR, "F:/bmp_french.bin"); lv_imgbtn_set_style(buttonFR, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonFR, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_set_event_cb_mks(buttonIT, event_handler, ID_IT, "bmp_italy.bin", 0); - lv_imgbtn_set_src(buttonIT, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonIT, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonIT, event_handler, ID_IT, NULL, 0); + lv_imgbtn_set_src(buttonIT, LV_BTN_STATE_REL, "F:/bmp_italy.bin"); + lv_imgbtn_set_src(buttonIT, LV_BTN_STATE_PR, "F:/bmp_italy.bin"); lv_imgbtn_set_style(buttonIT, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonIT, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_L_RETURN, "bmp_return.bin", 0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_L_RETURN, NULL, 0); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_return.bin"); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_return.bin"); lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); + #endif // if 1 lv_obj_set_pos(buttonCN, INTERVAL_V, titleHeight); @@ -315,7 +331,7 @@ void lv_draw_language(void) { lv_obj_set_pos(buttonIT, BTN_X_PIXEL * 2 + INTERVAL_V * 3, BTN_Y_PIXEL + INTERVAL_H + titleHeight); lv_obj_set_pos(buttonBack, BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - /*Create a label on the Image button*/ + // Create labels on the image buttons lv_btn_set_layout(buttonCN, LV_LAYOUT_OFF); lv_btn_set_layout(buttonT_CN, LV_LAYOUT_OFF); lv_btn_set_layout(buttonEN, LV_LAYOUT_OFF); @@ -325,14 +341,14 @@ void lv_draw_language(void) { lv_btn_set_layout(buttonIT, LV_LAYOUT_OFF); lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); - lv_obj_t * label_CN = lv_label_create(buttonCN, NULL); - lv_obj_t * label_T_CN = lv_label_create(buttonT_CN, NULL); - lv_obj_t * label_EN = lv_label_create(buttonEN, NULL); - lv_obj_t * label_RU = lv_label_create(buttonRU, NULL); - lv_obj_t * label_ES = lv_label_create(buttonES, NULL); - lv_obj_t * label_FR = lv_label_create(buttonFR, NULL); - lv_obj_t * label_IT = lv_label_create(buttonIT, NULL); - lv_obj_t * label_Back = lv_label_create(buttonBack, NULL); + lv_obj_t *label_CN = lv_label_create(buttonCN, NULL); + lv_obj_t *label_T_CN = lv_label_create(buttonT_CN, NULL); + lv_obj_t *label_EN = lv_label_create(buttonEN, NULL); + lv_obj_t *label_RU = lv_label_create(buttonRU, NULL); + lv_obj_t *label_ES = lv_label_create(buttonES, NULL); + lv_obj_t *label_FR = lv_label_create(buttonFR, NULL); + lv_obj_t *label_IT = lv_label_create(buttonIT, NULL); + lv_obj_t *label_Back = lv_label_create(buttonBack, NULL); disp_language(gCfgItems.language, SELECTED); @@ -361,8 +377,25 @@ void lv_draw_language(void) { lv_label_set_text(label_Back, common_menu.text_back); lv_obj_align(label_Back, buttonBack, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); } + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonCN); + lv_group_add_obj(g, buttonT_CN); + lv_group_add_obj(g, buttonEN); + lv_group_add_obj(g, buttonRU); + lv_group_add_obj(g, buttonES); + lv_group_add_obj(g, buttonFR); + lv_group_add_obj(g, buttonIT); + lv_group_add_obj(g, buttonBack); + } + #endif } -void lv_clear_language() { lv_obj_del(scr); } +void lv_clear_language() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} #endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_language.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_language.h index 4b6b2b0221..ca6d40bfc3 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_language.h +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_language.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus -extern "C" { /* C-declarations for C++ */ + extern "C" { /* C-declarations for C++ */ #endif extern void lv_draw_language(void); @@ -30,5 +30,5 @@ extern void lv_clear_language(); //extern void disp_temp_ready_print(); #ifdef __cplusplus -} /* C-declarations for C++ */ + } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_level_settings.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_level_settings.cpp new file mode 100644 index 0000000000..0e0283d32a --- /dev/null +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_level_settings.cpp @@ -0,0 +1,261 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "lv_conf.h" +#include "draw_ui.h" + +#include "../../../../MarlinCore.h" + +extern lv_group_t * g; +static lv_obj_t * scr; + +#define ID_LEVEL_RETURN 1 +#define ID_LEVEL_POSITION 2 +#define ID_LEVEL_POSITION_ARROW 3 +#define ID_LEVEL_COMMAND 4 +#define ID_LEVEL_COMMAND_ARROW 5 +#define ID_LEVEL_ZOFFSET 6 +#define ID_LEVEL_ZOFFSET_ARROW 7 + + +static void event_handler(lv_obj_t * obj, lv_event_t event) { + switch (obj->mks_obj_id) { + case ID_LEVEL_RETURN: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + lv_clear_level_settings(); + draw_return_ui(); + } + break; + case ID_LEVEL_POSITION: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + lv_clear_level_settings(); + lv_draw_manual_level_pos_settings(); + } + break; + case ID_LEVEL_POSITION_ARROW: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + lv_clear_level_settings(); + lv_draw_manual_level_pos_settings(); + } + break; + case ID_LEVEL_COMMAND: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + keyboard_value = gcodeCommand; + lv_clear_level_settings(); + lv_draw_keyboard(); + } + break; + case ID_LEVEL_COMMAND_ARROW: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + keyboard_value = gcodeCommand; + lv_clear_level_settings(); + lv_draw_keyboard(); + } + break; + #if HAS_BED_PROBE + case ID_LEVEL_ZOFFSET: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + lv_clear_level_settings(); + lv_draw_auto_level_offset_settings(); + } + break; + case ID_LEVEL_ZOFFSET_ARROW: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + lv_clear_level_settings(); + lv_draw_auto_level_offset_settings(); + } + break; + #endif + } +} + +void lv_draw_level_settings(void) { + lv_obj_t *buttonBack, *label_Back; + lv_obj_t *buttonPosition, *labelPosition, *buttonPositionNarrow; + lv_obj_t *buttonCommand, *labelCommand, *buttonCommandNarrow; + #if HAS_BED_PROBE + lv_obj_t *buttonZoffset, *labelZoffset, *buttonZoffsetNarrow; + lv_obj_t * line3; + #endif + lv_obj_t * line1, * line2; + if (disp_state_stack._disp_state[disp_state_stack._disp_index] != LEVELING_PARA_UI) { + disp_state_stack._disp_index++; + disp_state_stack._disp_state[disp_state_stack._disp_index] = LEVELING_PARA_UI; + } + disp_state = LEVELING_PARA_UI; + + scr = lv_obj_create(NULL, NULL); + + lv_obj_set_style(scr, &tft_style_scr); + lv_scr_load(scr); + lv_obj_clean(scr); + + lv_obj_t * title = lv_label_create(scr, NULL); + lv_obj_set_style(title, &tft_style_label_rel); + lv_obj_set_pos(title, TITLE_XPOS, TITLE_YPOS); + lv_label_set_text(title, machine_menu.LevelingParaConfTitle); + + lv_refr_now(lv_refr_get_disp_refreshing()); + + + buttonPosition = lv_btn_create(scr, NULL); /*Add a button the current screen*/ + lv_obj_set_pos(buttonPosition, PARA_UI_POS_X, PARA_UI_POS_Y); /*Set its position*/ + lv_obj_set_size(buttonPosition, PARA_UI_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ + lv_obj_set_event_cb_mks(buttonPosition, event_handler, ID_LEVEL_POSITION, NULL, 0); + lv_btn_set_style(buttonPosition, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ + lv_btn_set_style(buttonPosition, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ + lv_btn_set_layout(buttonPosition, LV_LAYOUT_OFF); + labelPosition = lv_label_create(buttonPosition, NULL); /*Add a label to the button*/ + + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonPosition); + #endif + + buttonPositionNarrow = lv_imgbtn_create(scr, NULL); + lv_obj_set_pos(buttonPositionNarrow, PARA_UI_POS_X + PARA_UI_SIZE_X, PARA_UI_POS_Y + PARA_UI_ARROW_V); + lv_obj_set_event_cb_mks(buttonPositionNarrow, event_handler, ID_LEVEL_POSITION_ARROW, NULL, 0); + lv_imgbtn_set_src(buttonPositionNarrow, LV_BTN_STATE_REL, "F:/bmp_arrow.bin"); + lv_imgbtn_set_src(buttonPositionNarrow, LV_BTN_STATE_PR, "F:/bmp_arrow.bin"); + lv_imgbtn_set_style(buttonPositionNarrow, LV_BTN_STATE_PR, &tft_style_label_pre); + lv_imgbtn_set_style(buttonPositionNarrow, LV_BTN_STATE_REL, &tft_style_label_rel); + lv_btn_set_layout(buttonPositionNarrow, LV_LAYOUT_OFF); + + line1 = lv_line_create(scr, NULL); + lv_ex_line(line1, line_points[0]); + + buttonCommand = lv_btn_create(scr, NULL); + lv_obj_set_pos(buttonCommand, PARA_UI_POS_X, PARA_UI_POS_Y * 2); + lv_obj_set_size(buttonCommand, PARA_UI_SIZE_X, PARA_UI_SIZE_Y); + lv_obj_set_event_cb_mks(buttonCommand, event_handler, ID_LEVEL_COMMAND, NULL, 0); + lv_btn_set_style(buttonCommand, LV_BTN_STYLE_REL, &tft_style_label_rel); + lv_btn_set_style(buttonCommand, LV_BTN_STYLE_PR, &tft_style_label_pre); + lv_btn_set_layout(buttonCommand, LV_LAYOUT_OFF); + labelCommand = lv_label_create(buttonCommand, NULL); + + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonCommand); + #endif + + buttonCommandNarrow = lv_imgbtn_create(scr, NULL); + lv_obj_set_pos(buttonCommandNarrow, PARA_UI_POS_X + PARA_UI_SIZE_X, PARA_UI_POS_Y * 2 + PARA_UI_ARROW_V); + lv_obj_set_event_cb_mks(buttonCommandNarrow, event_handler, ID_LEVEL_COMMAND_ARROW, NULL, 0); + lv_imgbtn_set_src(buttonCommandNarrow, LV_BTN_STATE_REL, "F:/bmp_arrow.bin"); + lv_imgbtn_set_src(buttonCommandNarrow, LV_BTN_STATE_PR, "F:/bmp_arrow.bin"); + lv_imgbtn_set_style(buttonCommandNarrow, LV_BTN_STATE_PR, &tft_style_label_pre); + lv_imgbtn_set_style(buttonCommandNarrow, LV_BTN_STATE_REL, &tft_style_label_rel); + lv_btn_set_layout(buttonCommandNarrow, LV_LAYOUT_OFF); + + line2 = lv_line_create(scr, NULL); + lv_ex_line(line2, line_points[1]); + + #if HAS_BED_PROBE + + buttonZoffset = lv_btn_create(scr, NULL); /*Add a button the current screen*/ + lv_obj_set_pos(buttonZoffset, PARA_UI_POS_X, PARA_UI_POS_Y * 3); /*Set its position*/ + lv_obj_set_size(buttonZoffset, PARA_UI_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ + lv_obj_set_event_cb_mks(buttonZoffset, event_handler, ID_LEVEL_ZOFFSET, NULL, 0); + lv_btn_set_style(buttonZoffset, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ + lv_btn_set_style(buttonZoffset, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ + lv_btn_set_layout(buttonZoffset, LV_LAYOUT_OFF); + labelZoffset = lv_label_create(buttonZoffset, NULL); /*Add a label to the button*/ + + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonZoffset); + #endif + + buttonZoffsetNarrow = lv_imgbtn_create(scr, NULL); + lv_obj_set_pos(buttonZoffsetNarrow, PARA_UI_POS_X + PARA_UI_SIZE_X, PARA_UI_POS_Y * 3 + PARA_UI_ARROW_V); + lv_obj_set_event_cb_mks(buttonZoffsetNarrow, event_handler, ID_LEVEL_ZOFFSET_ARROW, NULL, 0); + lv_imgbtn_set_src(buttonZoffsetNarrow, LV_BTN_STATE_REL, "F:/bmp_arrow.bin"); + lv_imgbtn_set_src(buttonZoffsetNarrow, LV_BTN_STATE_PR, "F:/bmp_arrow.bin"); + lv_imgbtn_set_style(buttonZoffsetNarrow, LV_BTN_STATE_PR, &tft_style_label_pre); + lv_imgbtn_set_style(buttonZoffsetNarrow, LV_BTN_STATE_REL, &tft_style_label_rel); + lv_btn_set_layout(buttonZoffsetNarrow, LV_LAYOUT_OFF); + + line3 = lv_line_create(scr, NULL); + lv_ex_line(line3, line_points[2]); + + #endif // HAS_BED_PROBE + + buttonBack = lv_imgbtn_create(scr, NULL); + lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_LEVEL_RETURN, NULL, 0); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_back70x40.bin"); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_back70x40.bin"); + lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); + lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonBack); + #endif + + lv_obj_set_pos(buttonBack, PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y); + lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); + label_Back = lv_label_create(buttonBack, NULL); + + if (gCfgItems.multiple_language != 0) { + lv_label_set_text(label_Back, common_menu.text_back); + lv_obj_align(label_Back, buttonBack, LV_ALIGN_CENTER, 0, 0); + + lv_label_set_text(labelPosition, machine_menu.LevelingManuPosConf); + lv_obj_align(labelPosition, buttonPosition, LV_ALIGN_IN_LEFT_MID, 0, 0); + + lv_label_set_text(labelCommand, machine_menu.LevelingAutoCommandConf); + lv_obj_align(labelCommand, buttonCommand, LV_ALIGN_IN_LEFT_MID, 0, 0); + #if HAS_BED_PROBE + lv_label_set_text(labelZoffset, machine_menu.LevelingAutoZoffsetConf); + lv_obj_align(labelZoffset, buttonZoffset, LV_ALIGN_IN_LEFT_MID, 0, 0); + #endif + } + +} + +void lv_clear_level_settings() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_level_settings.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_level_settings.h new file mode 100644 index 0000000000..ce290172b6 --- /dev/null +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_level_settings.h @@ -0,0 +1,33 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#ifdef __cplusplus + extern "C" { /* C-declarations for C++ */ +#endif + +extern void lv_draw_level_settings(void); +extern void lv_clear_level_settings(); + +#ifdef __cplusplus + } /* C-declarations for C++ */ +#endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_machine_para.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_machine_para.cpp index d441f2ac51..9f03793c24 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_machine_para.cpp +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_machine_para.cpp @@ -28,6 +28,7 @@ #include "../../../../MarlinCore.h" +extern lv_group_t * g; static lv_obj_t * scr; #define ID_PARA_RETURN 1 @@ -35,8 +36,10 @@ static lv_obj_t * scr; #define ID_PARA_MACHINE_ARROW 3 #define ID_PARA_MOTOR 4 #define ID_PARA_MOTOR_ARROW 5 -#define ID_PARA_ADVANCE 6 -#define ID_PARA_ADVANCE_ARROW 7 +#define ID_PARA_LEVEL 6 +#define ID_PARA_LEVEL_ARROW 7 +#define ID_PARA_ADVANCE 8 +#define ID_PARA_ADVANCE_ARROW 9 static void event_handler(lv_obj_t * obj, lv_event_t event) { switch (obj->mks_obj_id) { @@ -85,6 +88,24 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { lv_draw_motor_settings(); } break; + case ID_PARA_LEVEL: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + lv_clear_machine_para(); + lv_draw_level_settings(); + } + break; + case ID_PARA_LEVEL_ARROW: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + lv_clear_machine_para(); + lv_draw_level_settings(); + } + break; case ID_PARA_ADVANCE: if (event == LV_EVENT_CLICKED) { @@ -110,8 +131,9 @@ void lv_draw_machine_para(void) { lv_obj_t *buttonBack, *label_Back; lv_obj_t *buttonMachine, *labelMachine, *buttonMachineNarrow; lv_obj_t *buttonMotor, *labelMotor, *buttonMotorNarrow; + lv_obj_t *buttonLevel, *labelLevel, *buttonLevelNarrow; lv_obj_t *buttonAdvance, *labelAdvance, *buttonAdvanceNarrow; - lv_obj_t * line1, * line2, * line3; + lv_obj_t * line1, * line2, * line3, * line4; if (disp_state_stack._disp_state[disp_state_stack._disp_index] != MACHINE_PARA_UI) { disp_state_stack._disp_index++; disp_state_stack._disp_state[disp_state_stack._disp_index] = MACHINE_PARA_UI; @@ -131,9 +153,6 @@ void lv_draw_machine_para(void) { lv_refr_now(lv_refr_get_disp_refreshing()); - LV_IMG_DECLARE(bmp_para_back); - LV_IMG_DECLARE(bmp_para_arrow); - buttonMachine = lv_btn_create(scr, NULL); /*Add a button the current screen*/ lv_obj_set_pos(buttonMachine, PARA_UI_POS_X, PARA_UI_POS_Y); /*Set its position*/ lv_obj_set_size(buttonMachine, PARA_UI_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ @@ -146,9 +165,9 @@ void lv_draw_machine_para(void) { buttonMachineNarrow = lv_imgbtn_create(scr, NULL); lv_obj_set_pos(buttonMachineNarrow, PARA_UI_POS_X + PARA_UI_SIZE_X, PARA_UI_POS_Y + PARA_UI_ARROW_V); - lv_obj_set_event_cb_mks(buttonMachineNarrow, event_handler, ID_PARA_MACHINE_ARROW, "bmp_arrow.bin", 0); - lv_imgbtn_set_src(buttonMachineNarrow, LV_BTN_STATE_REL, &bmp_para_arrow); - lv_imgbtn_set_src(buttonMachineNarrow, LV_BTN_STATE_PR, &bmp_para_arrow); + lv_obj_set_event_cb_mks(buttonMachineNarrow, event_handler, ID_PARA_MACHINE_ARROW, NULL, 0); + lv_imgbtn_set_src(buttonMachineNarrow, LV_BTN_STATE_REL, "F:/bmp_arrow.bin"); + lv_imgbtn_set_src(buttonMachineNarrow, LV_BTN_STATE_PR, "F:/bmp_arrow.bin"); lv_imgbtn_set_style(buttonMachineNarrow, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonMachineNarrow, LV_BTN_STATE_REL, &tft_style_label_rel); lv_btn_set_layout(buttonMachineNarrow, LV_LAYOUT_OFF); @@ -168,9 +187,9 @@ void lv_draw_machine_para(void) { buttonMotorNarrow = lv_imgbtn_create(scr, NULL); lv_obj_set_pos(buttonMotorNarrow, PARA_UI_POS_X + PARA_UI_SIZE_X, PARA_UI_POS_Y * 2 + PARA_UI_ARROW_V); - lv_obj_set_event_cb_mks(buttonMotorNarrow, event_handler, ID_PARA_MOTOR_ARROW, "bmp_arrow.bin", 0); - lv_imgbtn_set_src(buttonMotorNarrow, LV_BTN_STATE_REL, &bmp_para_arrow); - lv_imgbtn_set_src(buttonMotorNarrow, LV_BTN_STATE_PR, &bmp_para_arrow); + lv_obj_set_event_cb_mks(buttonMotorNarrow, event_handler, ID_PARA_MOTOR_ARROW, NULL, 0); + lv_imgbtn_set_src(buttonMotorNarrow, LV_BTN_STATE_REL, "F:/bmp_arrow.bin"); + lv_imgbtn_set_src(buttonMotorNarrow, LV_BTN_STATE_PR, "F:/bmp_arrow.bin"); lv_imgbtn_set_style(buttonMotorNarrow, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonMotorNarrow, LV_BTN_STATE_REL, &tft_style_label_rel); lv_btn_set_layout(buttonMotorNarrow, LV_LAYOUT_OFF); @@ -178,8 +197,30 @@ void lv_draw_machine_para(void) { line2 = lv_line_create(scr, NULL); lv_ex_line(line2, line_points[1]); + buttonLevel = lv_btn_create(scr, NULL); /*Add a button the current screen*/ + lv_obj_set_pos(buttonLevel, PARA_UI_POS_X, PARA_UI_POS_Y * 3); /*Set its position*/ + lv_obj_set_size(buttonLevel, PARA_UI_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ + //lv_obj_set_event_cb(buttonMotor, event_handler); + lv_obj_set_event_cb_mks(buttonLevel, event_handler, ID_PARA_LEVEL, NULL, 0); + lv_btn_set_style(buttonLevel, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ + lv_btn_set_style(buttonLevel, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ + lv_btn_set_layout(buttonLevel, LV_LAYOUT_OFF); + labelLevel = lv_label_create(buttonLevel, NULL); /*Add a label to the button*/ + + buttonLevelNarrow = lv_imgbtn_create(scr, NULL); + lv_obj_set_pos(buttonLevelNarrow, PARA_UI_POS_X + PARA_UI_SIZE_X, PARA_UI_POS_Y * 3 + PARA_UI_ARROW_V); + lv_obj_set_event_cb_mks(buttonLevelNarrow, event_handler, ID_PARA_LEVEL_ARROW, NULL, 0); + lv_imgbtn_set_src(buttonLevelNarrow, LV_BTN_STATE_REL, "F:/bmp_arrow.bin"); + lv_imgbtn_set_src(buttonLevelNarrow, LV_BTN_STATE_PR, "F:/bmp_arrow.bin"); + lv_imgbtn_set_style(buttonLevelNarrow, LV_BTN_STATE_PR, &tft_style_label_pre); + lv_imgbtn_set_style(buttonLevelNarrow, LV_BTN_STATE_REL, &tft_style_label_rel); + lv_btn_set_layout(buttonLevelNarrow, LV_LAYOUT_OFF); + + line3 = lv_line_create(scr, NULL); + lv_ex_line(line3, line_points[2]); + buttonAdvance = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonAdvance, PARA_UI_POS_X, PARA_UI_POS_Y * 3); /*Set its position*/ + lv_obj_set_pos(buttonAdvance, PARA_UI_POS_X, PARA_UI_POS_Y * 4); /*Set its position*/ lv_obj_set_size(buttonAdvance, PARA_UI_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ //lv_obj_set_event_cb(buttonMotor, event_handler); lv_obj_set_event_cb_mks(buttonAdvance, event_handler, ID_PARA_ADVANCE, NULL, 0); @@ -189,44 +230,61 @@ void lv_draw_machine_para(void) { labelAdvance = lv_label_create(buttonAdvance, NULL); /*Add a label to the button*/ buttonAdvanceNarrow = lv_imgbtn_create(scr, NULL); - lv_obj_set_pos(buttonAdvanceNarrow, PARA_UI_POS_X + PARA_UI_SIZE_X, PARA_UI_POS_Y * 3 + PARA_UI_ARROW_V); - lv_obj_set_event_cb_mks(buttonAdvanceNarrow, event_handler, ID_PARA_ADVANCE_ARROW, "bmp_arrow.bin", 0); - lv_imgbtn_set_src(buttonAdvanceNarrow, LV_BTN_STATE_REL, &bmp_para_arrow); - lv_imgbtn_set_src(buttonAdvanceNarrow, LV_BTN_STATE_PR, &bmp_para_arrow); + lv_obj_set_pos(buttonAdvanceNarrow, PARA_UI_POS_X + PARA_UI_SIZE_X, PARA_UI_POS_Y * 4 + PARA_UI_ARROW_V); + lv_obj_set_event_cb_mks(buttonAdvanceNarrow, event_handler, ID_PARA_ADVANCE_ARROW, NULL, 0); + lv_imgbtn_set_src(buttonAdvanceNarrow, LV_BTN_STATE_REL, "F:/bmp_arrow.bin"); + lv_imgbtn_set_src(buttonAdvanceNarrow, LV_BTN_STATE_PR, "F:/bmp_arrow.bin"); lv_imgbtn_set_style(buttonAdvanceNarrow, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonAdvanceNarrow, LV_BTN_STATE_REL, &tft_style_label_rel); lv_btn_set_layout(buttonAdvanceNarrow, LV_LAYOUT_OFF); - line3 = lv_line_create(scr, NULL); - lv_ex_line(line3, line_points[2]); + line4 = lv_line_create(scr, NULL); + lv_ex_line(line4, line_points[3]); buttonBack = lv_imgbtn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_PARA_RETURN, "bmp_back70x40.bin", 0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, &bmp_para_back); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, &bmp_para_back); + lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_PARA_RETURN, NULL, 0); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_back70x40.bin"); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_back70x40.bin"); lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_set_pos(buttonBack, PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y); + lv_obj_set_pos(buttonBack, PARA_UI_BACL_POS_X + 10, PARA_UI_BACL_POS_Y); lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); label_Back = lv_label_create(buttonBack, NULL); if (gCfgItems.multiple_language != 0) { lv_label_set_text(label_Back, common_menu.text_back); - lv_obj_align(label_Back, buttonBack, LV_ALIGN_CENTER, 0, 0); + lv_obj_align(label_Back, buttonBack, LV_ALIGN_CENTER, 0, -2); lv_label_set_text(labelMachine, MachinePara_menu.MachineSetting); - lv_obj_align(labelMachine, buttonMachine, LV_ALIGN_IN_LEFT_MID, 0, 0); + lv_obj_align(labelMachine, buttonMachine, LV_ALIGN_IN_LEFT_MID, 0, -3); lv_label_set_text(labelMotor, MachinePara_menu.MotorSetting); - lv_obj_align(labelMotor, buttonMotor, LV_ALIGN_IN_LEFT_MID, 0, 0); + lv_obj_align(labelMotor, buttonMotor, LV_ALIGN_IN_LEFT_MID, 0, -3); + + lv_label_set_text(labelLevel, MachinePara_menu.leveling); + lv_obj_align(labelLevel, buttonLevel, LV_ALIGN_IN_LEFT_MID, 0, -3); lv_label_set_text(labelAdvance, MachinePara_menu.AdvanceSetting); - lv_obj_align(labelAdvance, buttonAdvance, LV_ALIGN_IN_LEFT_MID, 0, 0); + lv_obj_align(labelAdvance, buttonAdvance, LV_ALIGN_IN_LEFT_MID, 0, -3); } + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonMachine); + lv_group_add_obj(g, buttonMotor); + lv_group_add_obj(g, buttonLevel); + lv_group_add_obj(g, buttonAdvance); + lv_group_add_obj(g, buttonBack); + } + #endif } -void lv_clear_machine_para() { lv_obj_del(scr); } +void lv_clear_machine_para() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} #endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_machine_para.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_machine_para.h index d75df293b1..e830f75db7 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_machine_para.h +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_machine_para.h @@ -22,12 +22,12 @@ #pragma once #ifdef __cplusplus -extern "C" { /* C-declarations for C++ */ + extern "C" { /* C-declarations for C++ */ #endif extern void lv_draw_machine_para(void); extern void lv_clear_machine_para(); #ifdef __cplusplus -} /* C-declarations for C++ */ + } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_machine_settings.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_machine_settings.cpp index 88a66c6599..0cf5bbaf7f 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_machine_settings.cpp +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_machine_settings.cpp @@ -28,6 +28,7 @@ #include "../../../../MarlinCore.h" +extern lv_group_t * g; static lv_obj_t * scr; #define ID_MACHINE_RETURN 1 @@ -138,24 +139,21 @@ void lv_draw_machine_settings(void) { lv_refr_now(lv_refr_get_disp_refreshing()); - LV_IMG_DECLARE(bmp_para_back); - LV_IMG_DECLARE(bmp_para_arrow); - - buttonAcceleration = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonAcceleration, PARA_UI_POS_X, PARA_UI_POS_Y); /*Set its position*/ - lv_obj_set_size(buttonAcceleration, PARA_UI_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ + buttonAcceleration = lv_btn_create(scr, NULL); // Add a button the current screen + lv_obj_set_pos(buttonAcceleration, PARA_UI_POS_X, PARA_UI_POS_Y); // Set its position + lv_obj_set_size(buttonAcceleration, PARA_UI_SIZE_X, PARA_UI_SIZE_Y); // Set its size //lv_obj_set_event_cb(buttonMachine, event_handler); lv_obj_set_event_cb_mks(buttonAcceleration, event_handler, ID_MACHINE_ACCELERATION, NULL, 0); - lv_btn_set_style(buttonAcceleration, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonAcceleration, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ + lv_btn_set_style(buttonAcceleration, LV_BTN_STYLE_REL, &tft_style_label_rel); // Set the button's released style + lv_btn_set_style(buttonAcceleration, LV_BTN_STYLE_PR, &tft_style_label_pre); // Set the button's pressed style lv_btn_set_layout(buttonAcceleration, LV_LAYOUT_OFF); - labelAcceleration = lv_label_create(buttonAcceleration, NULL); /*Add a label to the button*/ + labelAcceleration = lv_label_create(buttonAcceleration, NULL); // Add a label to the button buttonAccelerationNarrow = lv_imgbtn_create(scr, NULL); lv_obj_set_pos(buttonAccelerationNarrow, PARA_UI_POS_X + PARA_UI_SIZE_X, PARA_UI_POS_Y + PARA_UI_ARROW_V); - lv_obj_set_event_cb_mks(buttonAccelerationNarrow, event_handler, ID_MACHINE_ACCELERATION_ARROW, "bmp_arrow.bin", 0); - lv_imgbtn_set_src(buttonAccelerationNarrow, LV_BTN_STATE_REL, &bmp_para_arrow); - lv_imgbtn_set_src(buttonAccelerationNarrow, LV_BTN_STATE_PR, &bmp_para_arrow); + lv_obj_set_event_cb_mks(buttonAccelerationNarrow, event_handler, ID_MACHINE_ACCELERATION_ARROW, NULL, 0); + lv_imgbtn_set_src(buttonAccelerationNarrow, LV_BTN_STATE_REL, "F:/bmp_arrow.bin"); + lv_imgbtn_set_src(buttonAccelerationNarrow, LV_BTN_STATE_PR, "F:/bmp_arrow.bin"); lv_imgbtn_set_style(buttonAccelerationNarrow, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonAccelerationNarrow, LV_BTN_STATE_REL, &tft_style_label_rel); lv_btn_set_layout(buttonAccelerationNarrow, LV_LAYOUT_OFF); @@ -163,21 +161,21 @@ void lv_draw_machine_settings(void) { line1 = lv_line_create(lv_scr_act(), NULL); lv_ex_line(line1, line_points[0]); - buttonMaxFeedrate = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonMaxFeedrate, PARA_UI_POS_X, PARA_UI_POS_Y * 2); /*Set its position*/ - lv_obj_set_size(buttonMaxFeedrate, PARA_UI_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ + buttonMaxFeedrate = lv_btn_create(scr, NULL); // Add a button the current screen + lv_obj_set_pos(buttonMaxFeedrate, PARA_UI_POS_X, PARA_UI_POS_Y * 2); // Set its position + lv_obj_set_size(buttonMaxFeedrate, PARA_UI_SIZE_X, PARA_UI_SIZE_Y); // Set its size //lv_obj_set_event_cb(buttonMachine, event_handler); lv_obj_set_event_cb_mks(buttonMaxFeedrate, event_handler, ID_MACHINE_FEEDRATE, NULL, 0); - lv_btn_set_style(buttonMaxFeedrate, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonMaxFeedrate, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ + lv_btn_set_style(buttonMaxFeedrate, LV_BTN_STYLE_REL, &tft_style_label_rel); // Set the button's released style + lv_btn_set_style(buttonMaxFeedrate, LV_BTN_STYLE_PR, &tft_style_label_pre); // Set the button's pressed style lv_btn_set_layout(buttonMaxFeedrate, LV_LAYOUT_OFF); - labelMaxFeedrate = lv_label_create(buttonMaxFeedrate, NULL); /*Add a label to the button*/ + labelMaxFeedrate = lv_label_create(buttonMaxFeedrate, NULL); // Add a label to the button buttonMaxFeedrateNarrow = lv_imgbtn_create(scr, NULL); lv_obj_set_pos(buttonMaxFeedrateNarrow, PARA_UI_POS_X + PARA_UI_SIZE_X, PARA_UI_POS_Y * 2 + PARA_UI_ARROW_V); - lv_obj_set_event_cb_mks(buttonMaxFeedrateNarrow, event_handler, ID_MACHINE_FEEDRATE_ARROW, "bmp_arrow.bin", 0); - lv_imgbtn_set_src(buttonMaxFeedrateNarrow, LV_BTN_STATE_REL, &bmp_para_arrow); - lv_imgbtn_set_src(buttonMaxFeedrateNarrow, LV_BTN_STATE_PR, &bmp_para_arrow); + lv_obj_set_event_cb_mks(buttonMaxFeedrateNarrow, event_handler, ID_MACHINE_FEEDRATE_ARROW, NULL, 0); + lv_imgbtn_set_src(buttonMaxFeedrateNarrow, LV_BTN_STATE_REL, "F:/bmp_arrow.bin"); + lv_imgbtn_set_src(buttonMaxFeedrateNarrow, LV_BTN_STATE_PR, "F:/bmp_arrow.bin"); lv_imgbtn_set_style(buttonMaxFeedrateNarrow, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonMaxFeedrateNarrow, LV_BTN_STATE_REL, &tft_style_label_rel); lv_btn_set_layout(buttonMaxFeedrateNarrow, LV_LAYOUT_OFF); @@ -186,21 +184,21 @@ void lv_draw_machine_settings(void) { lv_ex_line(line2, line_points[1]); #if HAS_CLASSIC_JERK - buttonJerk = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonJerk, PARA_UI_POS_X, PARA_UI_POS_Y * 3); /*Set its position*/ - lv_obj_set_size(buttonJerk, PARA_UI_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ + buttonJerk = lv_btn_create(scr, NULL); // Add a button the current screen + lv_obj_set_pos(buttonJerk, PARA_UI_POS_X, PARA_UI_POS_Y * 3); // Set its position + lv_obj_set_size(buttonJerk, PARA_UI_SIZE_X, PARA_UI_SIZE_Y); // Set its size //lv_obj_set_event_cb(buttonMotor, event_handler); lv_obj_set_event_cb_mks(buttonJerk, event_handler, ID_MACHINE_JERK, NULL, 0); - lv_btn_set_style(buttonJerk, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonJerk, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ + lv_btn_set_style(buttonJerk, LV_BTN_STYLE_REL, &tft_style_label_rel); // Set the button's released style + lv_btn_set_style(buttonJerk, LV_BTN_STYLE_PR, &tft_style_label_pre); // Set the button's pressed style lv_btn_set_layout(buttonJerk, LV_LAYOUT_OFF); - labelJerk = lv_label_create(buttonJerk, NULL); /*Add a label to the button*/ + labelJerk = lv_label_create(buttonJerk, NULL); // Add a label to the button buttonJerkNarrow = lv_imgbtn_create(scr, NULL); lv_obj_set_pos(buttonJerkNarrow, PARA_UI_POS_X + PARA_UI_SIZE_X, PARA_UI_POS_Y * 3 + PARA_UI_ARROW_V); - lv_obj_set_event_cb_mks(buttonJerkNarrow, event_handler, ID_MACHINE_JERK_ARROW, "bmp_arrow.bin", 0); - lv_imgbtn_set_src(buttonJerkNarrow, LV_BTN_STATE_REL, &bmp_para_arrow); - lv_imgbtn_set_src(buttonJerkNarrow, LV_BTN_STATE_PR, &bmp_para_arrow); + lv_obj_set_event_cb_mks(buttonJerkNarrow, event_handler, ID_MACHINE_JERK_ARROW, NULL, 0); + lv_imgbtn_set_src(buttonJerkNarrow, LV_BTN_STATE_REL, "F:/bmp_arrow.bin"); + lv_imgbtn_set_src(buttonJerkNarrow, LV_BTN_STATE_PR, "F:/bmp_arrow.bin"); lv_imgbtn_set_style(buttonJerkNarrow, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonJerkNarrow, LV_BTN_STATE_REL, &tft_style_label_rel); lv_btn_set_layout(buttonJerkNarrow, LV_LAYOUT_OFF); @@ -210,9 +208,9 @@ void lv_draw_machine_settings(void) { #endif buttonBack = lv_imgbtn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_MACHINE_RETURN, "bmp_back70x40.bin", 0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, &bmp_para_back); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, &bmp_para_back); + lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_MACHINE_RETURN, NULL, 0); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_back70x40.bin"); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_back70x40.bin"); lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); @@ -234,8 +232,23 @@ void lv_draw_machine_settings(void) { lv_obj_align(labelJerk, buttonJerk, LV_ALIGN_IN_LEFT_MID, 0, 0); #endif } + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonAcceleration); + lv_group_add_obj(g, buttonMaxFeedrate); + #if HAS_CLASSIC_JERK + lv_group_add_obj(g, buttonJerk); + #endif + lv_group_add_obj(g, buttonBack); + } + #endif } -void lv_clear_machine_settings() { lv_obj_del(scr); } +void lv_clear_machine_settings() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} #endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_machine_settings.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_machine_settings.h index 37029c85c4..38d02e7189 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_machine_settings.h +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_machine_settings.h @@ -22,12 +22,12 @@ #pragma once #ifdef __cplusplus -extern "C" { /* C-declarations for C++ */ + extern "C" { /* C-declarations for C++ */ #endif extern void lv_draw_machine_settings(void); extern void lv_clear_machine_settings(); #ifdef __cplusplus -} /* C-declarations for C++ */ + } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_manuaLevel.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_manuaLevel.cpp index ab4d9eb881..3d68019b35 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_manuaLevel.cpp +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_manuaLevel.cpp @@ -32,7 +32,7 @@ #include "draw_ui.h" #include "../../../../gcode/queue.h" -//static lv_obj_t *buttonMoveZ,*buttonTest,*buttonZ0,*buttonStop,*buttonReturn; +extern lv_group_t * g; static lv_obj_t * scr; #define ID_M_POINT1 1 @@ -59,7 +59,7 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { queue.enqueue_now_P(PSTR("G1 Z10")); ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("G1 X%d Y%d"), X_MIN_POS + 30, Y_MIN_POS + 30); + sprintf_P(public_buf_l, PSTR("G1 X%d Y%d"), (int)gCfgItems.levelingPos[0][0], (int)gCfgItems.levelingPos[0][1]); queue.enqueue_one_now(public_buf_l); queue.enqueue_now_P(PSTR("G1 Z0")); } @@ -79,7 +79,7 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { queue.enqueue_now_P(PSTR("G1 Z10")); ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("G1 X%d Y%d"), X_MAX_POS - 30, Y_MIN_POS + 30); + sprintf_P(public_buf_l, PSTR("G1 X%d Y%d"), (int)gCfgItems.levelingPos[1][0], (int)gCfgItems.levelingPos[1][1]); queue.enqueue_one_now(public_buf_l); queue.enqueue_now_P(PSTR("G1 Z0")); } @@ -99,7 +99,7 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { queue.enqueue_now_P(PSTR("G1 Z10")); ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("G1 X%d Y%d"), X_MAX_POS - 30, Y_MAX_POS - 30); + sprintf_P(public_buf_l, PSTR("G1 X%d Y%d"), (int)gCfgItems.levelingPos[2][0], (int)gCfgItems.levelingPos[2][1]); queue.enqueue_one_now(public_buf_l); queue.enqueue_now_P(PSTR("G1 Z0")); } @@ -120,7 +120,7 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { queue.enqueue_now_P(PSTR("G1 Z10")); ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("G1 X%d Y%d"), X_MIN_POS + 30, Y_MAX_POS - 30); + sprintf_P(public_buf_l, PSTR("G1 X%d Y%d"), (int)gCfgItems.levelingPos[3][0], (int)gCfgItems.levelingPos[3][1]); queue.enqueue_one_now(public_buf_l); queue.enqueue_now_P(PSTR("G1 Z0")); } @@ -140,7 +140,7 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { queue.enqueue_now_P(PSTR("G1 Z10")); ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("G1 X%d Y%d"), X_BED_SIZE / 2, Y_BED_SIZE / 2); + sprintf_P(public_buf_l, PSTR("G1 X%d Y%d"), (int)gCfgItems.levelingPos[4][0], (int)gCfgItems.levelingPos[4][1]); queue.enqueue_one_now(public_buf_l); queue.enqueue_now_P(PSTR("G1 Z0")); } @@ -159,7 +159,6 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { } } - void lv_draw_manualLevel(void) { lv_obj_t *buttonPoint1, *buttonPoint2, *buttonPoint3, *buttonPoint4, *buttonPoint5; lv_obj_t *buttonBack; @@ -185,9 +184,7 @@ void lv_draw_manualLevel(void) { lv_refr_now(lv_refr_get_disp_refreshing()); - LV_IMG_DECLARE(bmp_pic); - - /*Create an Image button*/ + // Create an Image button buttonPoint1 = lv_imgbtn_create(scr, NULL); buttonPoint2 = lv_imgbtn_create(scr, NULL); buttonPoint3 = lv_imgbtn_create(scr, NULL); @@ -195,40 +192,41 @@ void lv_draw_manualLevel(void) { buttonPoint5 = lv_imgbtn_create(scr, NULL); buttonBack = lv_imgbtn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonPoint1, event_handler, ID_M_POINT1, "bmp_leveling1.bin", 0); - lv_imgbtn_set_src(buttonPoint1, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonPoint1, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonPoint1, event_handler, ID_M_POINT1, NULL, 0); + lv_imgbtn_set_src(buttonPoint1, LV_BTN_STATE_REL, "F:/bmp_leveling1.bin"); + lv_imgbtn_set_src(buttonPoint1, LV_BTN_STATE_PR, "F:/bmp_leveling1.bin"); lv_imgbtn_set_style(buttonPoint1, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonPoint1, LV_BTN_STATE_REL, &tft_style_label_rel); lv_obj_clear_protect(buttonPoint1, LV_PROTECT_FOLLOW); + #if 1 - lv_obj_set_event_cb_mks(buttonPoint2, event_handler, ID_M_POINT2, "bmp_leveling2.bin", 0); - lv_imgbtn_set_src(buttonPoint2, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonPoint2, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonPoint2, event_handler, ID_M_POINT2, NULL, 0); + lv_imgbtn_set_src(buttonPoint2, LV_BTN_STATE_REL, "F:/bmp_leveling2.bin"); + lv_imgbtn_set_src(buttonPoint2, LV_BTN_STATE_PR, "F:/bmp_leveling2.bin"); lv_imgbtn_set_style(buttonPoint2, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonPoint2, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_set_event_cb_mks(buttonPoint3, event_handler, ID_M_POINT3, "bmp_leveling3.bin", 0); - lv_imgbtn_set_src(buttonPoint3, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonPoint3, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonPoint3, event_handler, ID_M_POINT3, NULL, 0); + lv_imgbtn_set_src(buttonPoint3, LV_BTN_STATE_REL, "F:/bmp_leveling3.bin"); + lv_imgbtn_set_src(buttonPoint3, LV_BTN_STATE_PR, "F:/bmp_leveling3.bin"); lv_imgbtn_set_style(buttonPoint3, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonPoint3, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_set_event_cb_mks(buttonPoint4, event_handler, ID_M_POINT4, "bmp_leveling4.bin", 0); - lv_imgbtn_set_src(buttonPoint4, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonPoint4, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonPoint4, event_handler, ID_M_POINT4, NULL, 0); + lv_imgbtn_set_src(buttonPoint4, LV_BTN_STATE_REL, "F:/bmp_leveling4.bin"); + lv_imgbtn_set_src(buttonPoint4, LV_BTN_STATE_PR, "F:/bmp_leveling4.bin"); lv_imgbtn_set_style(buttonPoint4, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonPoint4, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_set_event_cb_mks(buttonPoint5, event_handler, ID_M_POINT5, "bmp_leveling5.bin", 0); - lv_imgbtn_set_src(buttonPoint5, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonPoint5, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonPoint5, event_handler, ID_M_POINT5, NULL, 0); + lv_imgbtn_set_src(buttonPoint5, LV_BTN_STATE_REL, "F:/bmp_leveling5.bin"); + lv_imgbtn_set_src(buttonPoint5, LV_BTN_STATE_PR, "F:/bmp_leveling5.bin"); lv_imgbtn_set_style(buttonPoint5, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonPoint5, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_MANUAL_RETURN, "bmp_return.bin", 0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_MANUAL_RETURN, NULL, 0); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_return.bin"); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_return.bin"); lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); #endif @@ -240,7 +238,7 @@ void lv_draw_manualLevel(void) { lv_obj_set_pos(buttonPoint5, INTERVAL_V, BTN_Y_PIXEL + INTERVAL_H + titleHeight); lv_obj_set_pos(buttonBack, BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - /*Create a label on the Image button*/ + // Create labels on the image buttons lv_btn_set_layout(buttonPoint1, LV_LAYOUT_OFF); lv_btn_set_layout(buttonPoint2, LV_LAYOUT_OFF); lv_btn_set_layout(buttonPoint3, LV_LAYOUT_OFF); @@ -248,12 +246,12 @@ void lv_draw_manualLevel(void) { lv_btn_set_layout(buttonPoint5, LV_LAYOUT_OFF); lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); - lv_obj_t * label_Point1 = lv_label_create(buttonPoint1, NULL); - lv_obj_t * label_Point2 = lv_label_create(buttonPoint2, NULL); - lv_obj_t * label_Point3 = lv_label_create(buttonPoint3, NULL); - lv_obj_t * label_Point4 = lv_label_create(buttonPoint4, NULL); - lv_obj_t * label_Point5 = lv_label_create(buttonPoint5, NULL); - lv_obj_t * label_Back = lv_label_create(buttonBack, NULL); + lv_obj_t *label_Point1 = lv_label_create(buttonPoint1, NULL); + lv_obj_t *label_Point2 = lv_label_create(buttonPoint2, NULL); + lv_obj_t *label_Point3 = lv_label_create(buttonPoint3, NULL); + lv_obj_t *label_Point4 = lv_label_create(buttonPoint4, NULL); + lv_obj_t *label_Point5 = lv_label_create(buttonPoint5, NULL); + lv_obj_t *label_Back = lv_label_create(buttonBack, NULL); if (gCfgItems.multiple_language != 0) { lv_label_set_text(label_Point1, leveling_menu.position1); @@ -274,8 +272,23 @@ void lv_draw_manualLevel(void) { lv_label_set_text(label_Back, common_menu.text_back); lv_obj_align(label_Back, buttonBack, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); } + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonPoint1); + lv_group_add_obj(g, buttonPoint2); + lv_group_add_obj(g, buttonPoint3); + lv_group_add_obj(g, buttonPoint4); + lv_group_add_obj(g, buttonPoint5); + lv_group_add_obj(g, buttonBack); + } + #endif } -void lv_clear_manualLevel() { lv_obj_del(scr); } +void lv_clear_manualLevel() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} #endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_manuaLevel.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_manuaLevel.h index 4ec33afce3..cfa10370e1 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_manuaLevel.h +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_manuaLevel.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus -extern "C" { /* C-declarations for C++ */ + extern "C" { /* C-declarations for C++ */ #endif extern void lv_draw_manualLevel(void); @@ -30,5 +30,5 @@ extern void lv_clear_manualLevel(); //extern void disp_temp_ready_print(); #ifdef __cplusplus -} /* C-declarations for C++ */ + } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_manual_level_pos_settings.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_manual_level_pos_settings.cpp new file mode 100644 index 0000000000..9b7200b5a9 --- /dev/null +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_manual_level_pos_settings.cpp @@ -0,0 +1,459 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "lv_conf.h" +#include "draw_ui.h" + +#include "../../../../MarlinCore.h" +#include "../../../../module/planner.h" + +extern lv_group_t * g; +static lv_obj_t * scr; + +#define ID_MANUAL_POS_RETURN 1 +#define ID_MANUAL_POS_X1 2 +#define ID_MANUAL_POS_Y1 3 +#define ID_MANUAL_POS_X2 4 +#define ID_MANUAL_POS_Y2 5 +#define ID_MANUAL_POS_X3 6 +#define ID_MANUAL_POS_Y3 7 +#define ID_MANUAL_POS_X4 8 +#define ID_MANUAL_POS_Y4 9 +#define ID_MANUAL_POS_X5 10 +#define ID_MANUAL_POS_Y5 11 +#define ID_MANUAL_POS_DOWN 12 +#define ID_MANUAL_POS_UP 13 + +static void event_handler(lv_obj_t * obj, lv_event_t event) { + switch (obj->mks_obj_id) { + case ID_MANUAL_POS_RETURN: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + uiCfg.para_ui_page = 0; + lv_clear_manual_level_pos_settings(); + draw_return_ui(); + } + break; + case ID_MANUAL_POS_X1: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + value = level_pos_x1; + lv_clear_manual_level_pos_settings(); + lv_draw_number_key(); + } + break; + case ID_MANUAL_POS_Y1: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + value = level_pos_y1; + lv_clear_manual_level_pos_settings(); + lv_draw_number_key(); + } + break; + case ID_MANUAL_POS_X2: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + value = level_pos_x2; + lv_clear_manual_level_pos_settings(); + lv_draw_number_key(); + } + break; + case ID_MANUAL_POS_Y2: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + value = level_pos_y2; + lv_clear_manual_level_pos_settings(); + lv_draw_number_key(); + } + break; + case ID_MANUAL_POS_X3: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + value = level_pos_x3; + lv_clear_manual_level_pos_settings(); + lv_draw_number_key(); + } + break; + case ID_MANUAL_POS_Y3: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + value = level_pos_y3; + lv_clear_manual_level_pos_settings(); + lv_draw_number_key(); + } + break; + case ID_MANUAL_POS_X4: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + value = level_pos_x4; + lv_clear_manual_level_pos_settings(); + lv_draw_number_key(); + } + break; + case ID_MANUAL_POS_Y4: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + value = level_pos_y4; + lv_clear_manual_level_pos_settings(); + lv_draw_number_key(); + } + break; + case ID_MANUAL_POS_X5: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + value = level_pos_y5; + lv_clear_manual_level_pos_settings(); + lv_draw_number_key(); + } + break; + case ID_MANUAL_POS_Y5: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + value = level_pos_y5; + lv_clear_manual_level_pos_settings(); + lv_draw_number_key(); + } + break; + case ID_MANUAL_POS_UP: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + uiCfg.para_ui_page = 0; + lv_clear_manual_level_pos_settings(); + lv_draw_manual_level_pos_settings(); + } + break; + case ID_MANUAL_POS_DOWN: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + uiCfg.para_ui_page = 1; + lv_clear_manual_level_pos_settings(); + lv_draw_manual_level_pos_settings(); + } + break; + } +} + +void lv_draw_manual_level_pos_settings(void) { + lv_obj_t *buttonBack = NULL, *label_Back = NULL, *buttonTurnPage = NULL, *labelTurnPage = NULL; + lv_obj_t *labelPoint1Text = NULL, *buttonX1Value = NULL, *labelX1Value = NULL; + lv_obj_t *buttonY1Value = NULL, *labelY1Value = NULL; + lv_obj_t *labelPoint2Text = NULL, *buttonX2Value = NULL, *labelX2Value = NULL; + lv_obj_t *buttonY2Value = NULL, *labelY2Value = NULL; + lv_obj_t *labelPoint3Text = NULL, *buttonX3Value = NULL, *labelX3Value = NULL; + lv_obj_t *buttonY3Value = NULL, *labelY3Value = NULL; + lv_obj_t *labelPoint4Text = NULL, *buttonX4Value = NULL, *labelX4Value = NULL; + lv_obj_t *buttonY4Value = NULL, *labelY4Value = NULL; + lv_obj_t *labelPoint5Text = NULL, *buttonX5Value = NULL, *labelX5Value = NULL; + lv_obj_t *buttonY5Value = NULL, *labelY5Value = NULL; + lv_obj_t * line1 = NULL, * line2 = NULL, * line3 = NULL, * line4 = NULL; + if (disp_state_stack._disp_state[disp_state_stack._disp_index] != MANUAL_LEVELING_POSIGION_UI) { + disp_state_stack._disp_index++; + disp_state_stack._disp_state[disp_state_stack._disp_index] = MANUAL_LEVELING_POSIGION_UI; + } + disp_state = MANUAL_LEVELING_POSIGION_UI; + + scr = lv_obj_create(NULL, NULL); + + lv_obj_set_style(scr, &tft_style_scr); + lv_scr_load(scr); + lv_obj_clean(scr); + + lv_obj_t * title = lv_label_create(scr, NULL); + lv_obj_set_style(title, &tft_style_label_rel); + lv_obj_set_pos(title, TITLE_XPOS, TITLE_YPOS); + lv_label_set_text(title, machine_menu.LevelingParaConfTitle); + + lv_refr_now(lv_refr_get_disp_refreshing()); + + if (uiCfg.para_ui_page != 1) { + labelPoint1Text = lv_label_create(scr, NULL); + lv_obj_set_style(labelPoint1Text, &tft_style_label_rel); + lv_obj_set_pos(labelPoint1Text, PARA_UI_POS_X, PARA_UI_POS_Y + 10); + lv_label_set_text(labelPoint1Text, leveling_menu.position1); + + buttonX1Value = lv_btn_create(scr, NULL); + lv_obj_set_pos(buttonX1Value, PARA_UI_VALUE_POS_X_2, PARA_UI_POS_Y + PARA_UI_VALUE_V_2); + lv_obj_set_size(buttonX1Value, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonX1Value, event_handler, ID_MANUAL_POS_X1, NULL, 0); + lv_btn_set_style(buttonX1Value, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonX1Value, LV_BTN_STYLE_PR, &style_para_value); + labelX1Value = lv_label_create(buttonX1Value, NULL); + + buttonY1Value = lv_btn_create(scr, NULL); + lv_obj_set_pos(buttonY1Value, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y + PARA_UI_VALUE_V_2); + lv_obj_set_size(buttonY1Value, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonY1Value, event_handler, ID_MANUAL_POS_Y1, NULL, 0); + lv_btn_set_style(buttonY1Value, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonY1Value, LV_BTN_STYLE_PR, &style_para_value); + labelY1Value = lv_label_create(buttonY1Value, NULL); + + line1 = lv_line_create(scr, NULL); + lv_ex_line(line1, line_points[0]); + + labelPoint2Text = lv_label_create(scr, NULL); + lv_obj_set_style(labelPoint2Text, &tft_style_label_rel); + lv_obj_set_pos(labelPoint2Text, PARA_UI_POS_X, PARA_UI_POS_Y * 2 + 10); + lv_label_set_text(labelPoint2Text, leveling_menu.position2); + + buttonX2Value = lv_btn_create(scr, NULL); + lv_obj_set_pos(buttonX2Value, PARA_UI_VALUE_POS_X_2, PARA_UI_POS_Y * 2 + PARA_UI_VALUE_V_2); + lv_obj_set_size(buttonX2Value, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonX2Value, event_handler, ID_MANUAL_POS_X2, NULL, 0); + lv_btn_set_style(buttonX2Value, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonX2Value, LV_BTN_STYLE_PR, &style_para_value); + labelX2Value = lv_label_create(buttonX2Value, NULL); + + buttonY2Value = lv_btn_create(scr, NULL); + lv_obj_set_pos(buttonY2Value, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 2 + PARA_UI_VALUE_V_2); + lv_obj_set_size(buttonY2Value, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonY2Value, event_handler, ID_MANUAL_POS_Y2, NULL, 0); + lv_btn_set_style(buttonY2Value, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonY2Value, LV_BTN_STYLE_PR, &style_para_value); + labelY2Value = lv_label_create(buttonY2Value, NULL); + + line2 = lv_line_create(scr, NULL); + lv_ex_line(line2, line_points[1]); + + labelPoint3Text = lv_label_create(scr, NULL); + lv_obj_set_style(labelPoint3Text, &tft_style_label_rel); + lv_obj_set_pos(labelPoint3Text, PARA_UI_POS_X, PARA_UI_POS_Y * 3 + 10); + lv_label_set_text(labelPoint3Text, leveling_menu.position3); + + buttonX3Value = lv_btn_create(scr, NULL); + lv_obj_set_pos(buttonX3Value, PARA_UI_VALUE_POS_X_2, PARA_UI_POS_Y * 3 + PARA_UI_VALUE_V_2); + lv_obj_set_size(buttonX3Value, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonX3Value, event_handler, ID_MANUAL_POS_X3, NULL, 0); + lv_btn_set_style(buttonX3Value, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonX3Value, LV_BTN_STYLE_PR, &style_para_value); + labelX3Value = lv_label_create(buttonX3Value, NULL); + + buttonY3Value = lv_btn_create(scr, NULL); + lv_obj_set_pos(buttonY3Value, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 3 + PARA_UI_VALUE_V_2); + lv_obj_set_size(buttonY3Value, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonY3Value, event_handler, ID_MANUAL_POS_Y3, NULL, 0); + lv_btn_set_style(buttonY3Value, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonY3Value, LV_BTN_STYLE_PR, &style_para_value); + labelY3Value = lv_label_create(buttonY3Value, NULL); + + line3 = lv_line_create(scr, NULL); + lv_ex_line(line3, line_points[2]); + + labelPoint4Text = lv_label_create(scr, NULL); + lv_obj_set_style(labelPoint4Text, &tft_style_label_rel); + lv_obj_set_pos(labelPoint4Text, PARA_UI_POS_X, PARA_UI_POS_Y * 4 + 10); + lv_label_set_text(labelPoint4Text, leveling_menu.position4); + + buttonX4Value = lv_btn_create(scr, NULL); + lv_obj_set_pos(buttonX4Value, PARA_UI_VALUE_POS_X_2, PARA_UI_POS_Y * 4 + PARA_UI_VALUE_V_2); + lv_obj_set_size(buttonX4Value, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonX4Value, event_handler, ID_MANUAL_POS_X4, NULL, 0); + lv_btn_set_style(buttonX4Value, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonX4Value, LV_BTN_STYLE_PR, &style_para_value); + labelX4Value = lv_label_create(buttonX4Value, NULL); + + buttonY4Value = lv_btn_create(scr, NULL); + lv_obj_set_pos(buttonY4Value, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 4 + PARA_UI_VALUE_V_2); + lv_obj_set_size(buttonY4Value, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonY4Value, event_handler, ID_MANUAL_POS_Y4, NULL, 0); + lv_btn_set_style(buttonY4Value, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonY4Value, LV_BTN_STYLE_PR, &style_para_value); + labelY4Value = lv_label_create(buttonY4Value, NULL); + + line4 = lv_line_create(scr, NULL); + lv_ex_line(line4, line_points[3]); + + buttonTurnPage = lv_btn_create(scr, NULL); + lv_obj_set_event_cb_mks(buttonTurnPage, event_handler, ID_MANUAL_POS_DOWN, NULL, 0); + lv_btn_set_style(buttonTurnPage, LV_BTN_STYLE_REL, &style_para_back); + lv_btn_set_style(buttonTurnPage, LV_BTN_STYLE_PR, &style_para_back); + + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonX1Value); + lv_group_add_obj(g, buttonY1Value); + lv_group_add_obj(g, buttonX2Value); + lv_group_add_obj(g, buttonY2Value); + lv_group_add_obj(g, buttonX3Value); + lv_group_add_obj(g, buttonY3Value); + lv_group_add_obj(g, buttonX4Value); + lv_group_add_obj(g, buttonY4Value); + lv_group_add_obj(g, buttonTurnPage); + } + #endif + } + else { + labelPoint5Text = lv_label_create(scr, NULL); + lv_obj_set_style(labelPoint5Text, &tft_style_label_rel); + lv_obj_set_pos(labelPoint5Text, PARA_UI_POS_X, PARA_UI_POS_Y + 10); + lv_label_set_text(labelPoint5Text, leveling_menu.position5); + + buttonX5Value = lv_btn_create(scr, NULL); + lv_obj_set_pos(buttonX5Value, PARA_UI_VALUE_POS_X_2, PARA_UI_POS_Y + PARA_UI_VALUE_V_2); + lv_obj_set_size(buttonX5Value, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonX5Value, event_handler, ID_MANUAL_POS_X5, NULL, 0); + lv_btn_set_style(buttonX5Value, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonX5Value, LV_BTN_STYLE_PR, &style_para_value); + labelX5Value = lv_label_create(buttonX5Value, NULL); + + buttonY5Value = lv_btn_create(scr, NULL); + lv_obj_set_pos(buttonY5Value, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y + PARA_UI_VALUE_V_2); + lv_obj_set_size(buttonY5Value, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonY5Value, event_handler, ID_MANUAL_POS_Y5, NULL, 0); + lv_btn_set_style(buttonY5Value, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonY5Value, LV_BTN_STYLE_PR, &style_para_value); + labelY5Value = lv_label_create(buttonY5Value, NULL); + + line1 = lv_line_create(scr, NULL); + lv_ex_line(line1, line_points[0]); + + buttonTurnPage = lv_btn_create(scr, NULL); + lv_obj_set_event_cb_mks(buttonTurnPage, event_handler, ID_MANUAL_POS_UP, NULL, 0); + lv_btn_set_style(buttonTurnPage, LV_BTN_STYLE_REL, &style_para_back); + lv_btn_set_style(buttonTurnPage, LV_BTN_STYLE_PR, &style_para_back); + + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonX5Value); + lv_group_add_obj(g, buttonY5Value); + lv_group_add_obj(g, buttonTurnPage); + } + #endif + } + + lv_obj_set_pos(buttonTurnPage, PARA_UI_TURN_PAGE_POS_X, PARA_UI_TURN_PAGE_POS_Y); + lv_obj_set_size(buttonTurnPage, PARA_UI_BACK_BTN_X_SIZE, PARA_UI_BACK_BTN_Y_SIZE); + labelTurnPage = lv_label_create(buttonTurnPage, NULL); + + buttonBack = lv_btn_create(scr, NULL); + lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_MANUAL_POS_RETURN, NULL, 0); + lv_btn_set_style(buttonBack, LV_BTN_STYLE_REL, &style_para_back); + lv_btn_set_style(buttonBack, LV_BTN_STYLE_PR, &style_para_back); + lv_obj_set_pos(buttonBack, PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y); + lv_obj_set_size(buttonBack, PARA_UI_BACK_BTN_X_SIZE, PARA_UI_BACK_BTN_Y_SIZE); + label_Back = lv_label_create(buttonBack, NULL); + + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonBack); + #endif + + if (gCfgItems.multiple_language != 0) { + if (uiCfg.para_ui_page != 1) { + ZERO(public_buf_l); + sprintf_P(public_buf_l, PSTR("%d"), gCfgItems.levelingPos[0][0]); + lv_label_set_text(labelX1Value, public_buf_l); + lv_obj_align(labelX1Value, buttonX1Value, LV_ALIGN_CENTER, 0, 0); + + ZERO(public_buf_l); + sprintf_P(public_buf_l, PSTR("%d"), gCfgItems.levelingPos[0][1]); + lv_label_set_text(labelY1Value, public_buf_l); + lv_obj_align(labelY1Value, buttonY1Value, LV_ALIGN_CENTER, 0, 0); + + ZERO(public_buf_l); + sprintf_P(public_buf_l, PSTR("%d"), gCfgItems.levelingPos[1][0]); + lv_label_set_text(labelX2Value, public_buf_l); + lv_obj_align(labelX2Value, buttonX2Value, LV_ALIGN_CENTER, 0, 0); + + ZERO(public_buf_l); + sprintf_P(public_buf_l, PSTR("%d"), gCfgItems.levelingPos[1][1]); + lv_label_set_text(labelY2Value, public_buf_l); + lv_obj_align(labelY2Value, buttonY2Value, LV_ALIGN_CENTER, 0, 0); + + ZERO(public_buf_l); + sprintf_P(public_buf_l, PSTR("%d"), gCfgItems.levelingPos[2][0]); + lv_label_set_text(labelX3Value, public_buf_l); + lv_obj_align(labelX3Value, buttonX3Value, LV_ALIGN_CENTER, 0, 0); + + ZERO(public_buf_l); + sprintf_P(public_buf_l, PSTR("%d"), gCfgItems.levelingPos[2][1]); + lv_label_set_text(labelY3Value, public_buf_l); + lv_obj_align(labelY3Value, buttonY3Value, LV_ALIGN_CENTER, 0, 0); + + ZERO(public_buf_l); + sprintf_P(public_buf_l, PSTR("%d"), gCfgItems.levelingPos[3][0]); + lv_label_set_text(labelX4Value, public_buf_l); + lv_obj_align(labelX4Value, buttonX4Value, LV_ALIGN_CENTER, 0, 0); + + ZERO(public_buf_l); + sprintf_P(public_buf_l, PSTR("%d"), gCfgItems.levelingPos[3][1]); + lv_label_set_text(labelY4Value, public_buf_l); + lv_obj_align(labelY4Value, buttonY4Value, LV_ALIGN_CENTER, 0, 0); + + lv_label_set_text(labelTurnPage, machine_menu.next); + lv_obj_align(labelTurnPage, buttonTurnPage, LV_ALIGN_CENTER, 0, 0); + } + else { + ZERO(public_buf_l); + sprintf_P(public_buf_l, PSTR("%d"), gCfgItems.levelingPos[4][0]); + lv_label_set_text(labelX5Value, public_buf_l); + lv_obj_align(labelX5Value, buttonX5Value, LV_ALIGN_CENTER, 0, 0); + + ZERO(public_buf_l); + sprintf_P(public_buf_l, PSTR("%d"), gCfgItems.levelingPos[4][1]); + lv_label_set_text(labelY5Value, public_buf_l); + lv_obj_align(labelY5Value, buttonY5Value, LV_ALIGN_CENTER, 0, 0); + + lv_label_set_text(labelTurnPage, machine_menu.previous); + lv_obj_align(labelTurnPage, buttonTurnPage, LV_ALIGN_CENTER, 0, 0); + } + + lv_label_set_text(label_Back, common_menu.text_back); + lv_obj_align(label_Back, buttonBack, LV_ALIGN_CENTER, 0, 0); + } +} + +void lv_clear_manual_level_pos_settings() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_manual_level_pos_settings.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_manual_level_pos_settings.h new file mode 100644 index 0000000000..8e89ecf559 --- /dev/null +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_manual_level_pos_settings.h @@ -0,0 +1,33 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#ifdef __cplusplus + extern "C" { /* C-declarations for C++ */ +#endif + +extern void lv_draw_manual_level_pos_settings(void); +extern void lv_clear_manual_level_pos_settings(); + +#ifdef __cplusplus + } /* C-declarations for C++ */ +#endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_max_feedrate_settings.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_max_feedrate_settings.cpp index c78c6f5bb8..e82124f705 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_max_feedrate_settings.cpp +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_max_feedrate_settings.cpp @@ -29,6 +29,7 @@ #include "../../../../MarlinCore.h" #include "../../../../module/planner.h" +extern lv_group_t * g; static lv_obj_t * scr; #define ID_FEED_RETURN 1 @@ -127,11 +128,11 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { void lv_draw_max_feedrate_settings(void) { lv_obj_t *buttonBack = NULL, *label_Back = NULL, *buttonTurnPage = NULL, *labelTurnPage = NULL; - lv_obj_t *buttonXText = NULL, *labelXText = NULL, *buttonXValue = NULL, *labelXValue = NULL; - lv_obj_t *buttonYText = NULL, *labelYText = NULL, *buttonYValue = NULL, *labelYValue = NULL; - lv_obj_t *buttonZText = NULL, *labelZText = NULL, *buttonZValue = NULL, *labelZValue = NULL; - lv_obj_t *buttonE0Text = NULL, *labelE0Text = NULL, *buttonE0Value = NULL, *labelE0Value = NULL; - lv_obj_t *buttonE1Text = NULL, *labelE1Text = NULL, *buttonE1Value = NULL, *labelE1Value = NULL; + lv_obj_t *labelXText = NULL, *buttonXValue = NULL, *labelXValue = NULL; + lv_obj_t *labelYText = NULL, *buttonYValue = NULL, *labelYValue = NULL; + lv_obj_t *labelZText = NULL, *buttonZValue = NULL, *labelZValue = NULL; + lv_obj_t *labelE0Text = NULL, *buttonE0Value = NULL, *labelE0Value = NULL; + lv_obj_t *labelE1Text = NULL, *buttonE1Value = NULL, *labelE1Value = NULL; lv_obj_t * line1 = NULL, * line2 = NULL, * line3 = NULL, * line4 = NULL; if (disp_state_stack._disp_state[disp_state_stack._disp_index] != MAXFEEDRATE_UI) { disp_state_stack._disp_index++; @@ -152,166 +153,139 @@ void lv_draw_max_feedrate_settings(void) { lv_refr_now(lv_refr_get_disp_refreshing()); - LV_IMG_DECLARE(bmp_para_back); - // LV_IMG_DECLARE(bmp_para_arrow); - LV_IMG_DECLARE(bmp_para_bank); - if (uiCfg.para_ui_page != 1) { - buttonXText = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonXText, PARA_UI_POS_X, PARA_UI_POS_Y); /*Set its position*/ - lv_obj_set_size(buttonXText, PARA_UI_VALUE_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - lv_obj_set_event_cb(buttonXText, event_handler); - lv_btn_set_style(buttonXText, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonXText, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonXText, LV_LAYOUT_OFF); - labelXText = lv_label_create(buttonXText, NULL); /*Add a label to the button*/ - - buttonXValue = lv_imgbtn_create(scr, NULL); + labelXText = lv_label_create(scr, NULL); + lv_obj_set_style(labelXText, &tft_style_label_rel); + lv_obj_set_pos(labelXText, PARA_UI_POS_X, PARA_UI_POS_Y + 10); + lv_label_set_text(labelXText, machine_menu.XMaxFeedRate); + + buttonXValue = lv_btn_create(scr, NULL); lv_obj_set_pos(buttonXValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y + PARA_UI_VALUE_V); - lv_obj_set_event_cb_mks(buttonXValue, event_handler, ID_FEED_X, "bmp_value_blank.bin", 0); - lv_imgbtn_set_src(buttonXValue, LV_BTN_STATE_REL, &bmp_para_bank); - lv_imgbtn_set_src(buttonXValue, LV_BTN_STATE_PR, &bmp_para_bank); - lv_imgbtn_set_style(buttonXValue, LV_BTN_STATE_PR, &style_para_value_pre); - lv_imgbtn_set_style(buttonXValue, LV_BTN_STATE_REL, &style_para_value_rel); + lv_obj_set_size(buttonXValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonXValue, event_handler, ID_FEED_X, NULL, 0); + lv_btn_set_style(buttonXValue, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonXValue, LV_BTN_STYLE_PR, &style_para_value); lv_btn_set_layout(buttonXValue, LV_LAYOUT_OFF); labelXValue = lv_label_create(buttonXValue, NULL); line1 = lv_line_create(scr, NULL); lv_ex_line(line1, line_points[0]); - buttonYText = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonYText, PARA_UI_POS_X, PARA_UI_POS_Y * 2); /*Set its position*/ - lv_obj_set_size(buttonYText, PARA_UI_VALUE_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - lv_obj_set_event_cb(buttonYText, event_handler); - lv_btn_set_style(buttonYText, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonYText, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonYText, LV_LAYOUT_OFF); - labelYText = lv_label_create(buttonYText, NULL); /*Add a label to the button*/ + labelYText = lv_label_create(scr, NULL); + lv_obj_set_style(labelYText, &tft_style_label_rel); + lv_obj_set_pos(labelYText, PARA_UI_POS_X, PARA_UI_POS_Y * 2 + 10); + lv_label_set_text(labelYText, machine_menu.YMaxFeedRate); - buttonYValue = lv_imgbtn_create(scr, NULL); + buttonYValue = lv_btn_create(scr, NULL); lv_obj_set_pos(buttonYValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 2 + PARA_UI_VALUE_V); - lv_obj_set_event_cb_mks(buttonYValue, event_handler, ID_FEED_Y, "bmp_value_blank.bin", 0); - lv_imgbtn_set_src(buttonYValue, LV_BTN_STATE_REL, &bmp_para_bank); - lv_imgbtn_set_src(buttonYValue, LV_BTN_STATE_PR, &bmp_para_bank); - lv_imgbtn_set_style(buttonYValue, LV_BTN_STATE_PR, &style_para_value_pre); - lv_imgbtn_set_style(buttonYValue, LV_BTN_STATE_REL, &style_para_value_rel); + lv_obj_set_size(buttonYValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonYValue, event_handler, ID_FEED_Y, NULL, 0); + lv_btn_set_style(buttonYValue, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonYValue, LV_BTN_STYLE_PR, &style_para_value); lv_btn_set_layout(buttonYValue, LV_LAYOUT_OFF); labelYValue = lv_label_create(buttonYValue, NULL); line2 = lv_line_create(scr, NULL); lv_ex_line(line2, line_points[1]); - buttonZText = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonZText, PARA_UI_POS_X, PARA_UI_POS_Y * 3); /*Set its position*/ - lv_obj_set_size(buttonZText, PARA_UI_VALUE_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - lv_obj_set_event_cb(buttonZText, event_handler); - lv_btn_set_style(buttonZText, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonZText, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonZText, LV_LAYOUT_OFF); - labelZText = lv_label_create(buttonZText, NULL); /*Add a label to the button*/ + labelZText = lv_label_create(scr, NULL); + lv_obj_set_style(labelZText, &tft_style_label_rel); + lv_obj_set_pos(labelZText, PARA_UI_POS_X, PARA_UI_POS_Y * 3 + 10); + lv_label_set_text(labelZText, machine_menu.ZMaxFeedRate); - buttonZValue = lv_imgbtn_create(scr, NULL); + buttonZValue = lv_btn_create(scr, NULL); lv_obj_set_pos(buttonZValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 3 + PARA_UI_VALUE_V); - lv_obj_set_event_cb_mks(buttonZValue, event_handler, ID_FEED_Z, "bmp_value_blank.bin", 0); - lv_imgbtn_set_src(buttonZValue, LV_BTN_STATE_REL, &bmp_para_bank); - lv_imgbtn_set_src(buttonZValue, LV_BTN_STATE_PR, &bmp_para_bank); - lv_imgbtn_set_style(buttonZValue, LV_BTN_STATE_PR, &style_para_value_pre); - lv_imgbtn_set_style(buttonZValue, LV_BTN_STATE_REL, &style_para_value_rel); + lv_obj_set_size(buttonZValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonZValue, event_handler, ID_FEED_Z, NULL, 0); + lv_btn_set_style(buttonZValue, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonZValue, LV_BTN_STYLE_PR, &style_para_value); lv_btn_set_layout(buttonZValue, LV_LAYOUT_OFF); labelZValue = lv_label_create(buttonZValue, NULL); line3 = lv_line_create(scr, NULL); lv_ex_line(line3, line_points[2]); - buttonE0Text = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonE0Text, PARA_UI_POS_X, PARA_UI_POS_Y * 4); /*Set its position*/ - lv_obj_set_size(buttonE0Text, PARA_UI_VALUE_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - lv_obj_set_event_cb(buttonE0Text, event_handler); - lv_btn_set_style(buttonE0Text, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonE0Text, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonE0Text, LV_LAYOUT_OFF); - labelE0Text = lv_label_create(buttonE0Text, NULL); /*Add a label to the button*/ + labelE0Text = lv_label_create(scr, NULL); + lv_obj_set_style(labelE0Text, &tft_style_label_rel); + lv_obj_set_pos(labelE0Text, PARA_UI_POS_X, PARA_UI_POS_Y * 4 + 10); + lv_label_set_text(labelE0Text, machine_menu.E0MaxFeedRate); - buttonE0Value = lv_imgbtn_create(scr, NULL); + buttonE0Value = lv_btn_create(scr, NULL); lv_obj_set_pos(buttonE0Value, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 4 + PARA_UI_VALUE_V); - lv_obj_set_event_cb_mks(buttonE0Value, event_handler, ID_FEED_E0, "bmp_value_blank.bin", 0); - lv_imgbtn_set_src(buttonE0Value, LV_BTN_STATE_REL, &bmp_para_bank); - lv_imgbtn_set_src(buttonE0Value, LV_BTN_STATE_PR, &bmp_para_bank); - lv_imgbtn_set_style(buttonE0Value, LV_BTN_STATE_PR, &style_para_value_pre); - lv_imgbtn_set_style(buttonE0Value, LV_BTN_STATE_REL, &style_para_value_rel); + lv_obj_set_size(buttonE0Value, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonE0Value, event_handler, ID_FEED_E0, NULL, 0); + lv_btn_set_style(buttonE0Value, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonE0Value, LV_BTN_STYLE_PR, &style_para_value); lv_btn_set_layout(buttonE0Value, LV_LAYOUT_OFF); labelE0Value = lv_label_create(buttonE0Value, NULL); line4 = lv_line_create(scr, NULL); lv_ex_line(line4, line_points[3]); - buttonTurnPage = lv_imgbtn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonTurnPage, event_handler, ID_FEED_DOWN, "bmp_back70x40.bin", 0); - lv_imgbtn_set_src(buttonTurnPage, LV_BTN_STATE_REL, &bmp_para_back); - lv_imgbtn_set_src(buttonTurnPage, LV_BTN_STATE_PR, &bmp_para_back); - lv_imgbtn_set_style(buttonTurnPage, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonTurnPage, LV_BTN_STATE_REL, &tft_style_label_rel); + buttonTurnPage = lv_btn_create(scr, NULL); + lv_obj_set_event_cb_mks(buttonTurnPage, event_handler, ID_FEED_DOWN, NULL, 0); + lv_btn_set_style(buttonTurnPage, LV_BTN_STYLE_REL, &style_para_back); + lv_btn_set_style(buttonTurnPage, LV_BTN_STYLE_PR, &style_para_back); + + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonXValue); + lv_group_add_obj(g, buttonYValue); + lv_group_add_obj(g, buttonZValue); + lv_group_add_obj(g, buttonE0Value); + lv_group_add_obj(g, buttonTurnPage); + } + #endif } else { - buttonE1Text = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonE1Text, PARA_UI_POS_X, PARA_UI_POS_Y); /*Set its position*/ - lv_obj_set_size(buttonE1Text, PARA_UI_VALUE_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - lv_obj_set_event_cb(buttonE1Text, event_handler); - lv_btn_set_style(buttonE1Text, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonE1Text, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonE1Text, LV_LAYOUT_OFF); - labelE1Text = lv_label_create(buttonE1Text, NULL); /*Add a label to the button*/ - - buttonE1Value = lv_imgbtn_create(scr, NULL); + labelE1Text = lv_label_create(scr, NULL); + lv_obj_set_style(labelE1Text, &tft_style_label_rel); + lv_obj_set_pos(labelE1Text, PARA_UI_POS_X, PARA_UI_POS_Y + 10); + lv_label_set_text(labelE1Text, machine_menu.E1MaxFeedRate); + + buttonE1Value = lv_btn_create(scr, NULL); lv_obj_set_pos(buttonE1Value, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y + PARA_UI_VALUE_V); - lv_obj_set_event_cb_mks(buttonE1Value, event_handler, ID_FEED_E1, "bmp_value_blank.bin", 0); - lv_imgbtn_set_src(buttonE1Value, LV_BTN_STATE_REL, &bmp_para_bank); - lv_imgbtn_set_src(buttonE1Value, LV_BTN_STATE_PR, &bmp_para_bank); - lv_imgbtn_set_style(buttonE1Value, LV_BTN_STATE_PR, &style_para_value_pre); - lv_imgbtn_set_style(buttonE1Value, LV_BTN_STATE_REL, &style_para_value_rel); + lv_obj_set_size(buttonE1Value, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonE1Value, event_handler, ID_FEED_E1, NULL, 0); + lv_btn_set_style(buttonE1Value, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonE1Value, LV_BTN_STYLE_PR, &style_para_value); lv_btn_set_layout(buttonE1Value, LV_LAYOUT_OFF); labelE1Value = lv_label_create(buttonE1Value, NULL); + line1 = lv_line_create(scr, NULL); lv_ex_line(line1, line_points[0]); - buttonTurnPage = lv_imgbtn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonTurnPage, event_handler, ID_FEED_UP, "bmp_back70x40.bin", 0); - lv_imgbtn_set_src(buttonTurnPage, LV_BTN_STATE_REL, &bmp_para_back); - lv_imgbtn_set_src(buttonTurnPage, LV_BTN_STATE_PR, &bmp_para_back); - lv_imgbtn_set_style(buttonTurnPage, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonTurnPage, LV_BTN_STATE_REL, &tft_style_label_rel); + buttonTurnPage = lv_btn_create(scr, NULL); + lv_obj_set_event_cb_mks(buttonTurnPage, event_handler, ID_FEED_UP, NULL, 0); + lv_btn_set_style(buttonTurnPage, LV_BTN_STYLE_REL, &style_para_back); + lv_btn_set_style(buttonTurnPage, LV_BTN_STYLE_PR, &style_para_back); + + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonE1Value); + lv_group_add_obj(g, buttonTurnPage); + } + #endif } lv_obj_set_pos(buttonTurnPage, PARA_UI_TURN_PAGE_POS_X, PARA_UI_TURN_PAGE_POS_Y); - lv_btn_set_layout(buttonTurnPage, LV_LAYOUT_OFF); + lv_obj_set_size(buttonTurnPage, PARA_UI_BACK_BTN_X_SIZE, PARA_UI_BACK_BTN_Y_SIZE); labelTurnPage = lv_label_create(buttonTurnPage, NULL); - - buttonBack = lv_imgbtn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_FEED_RETURN, "bmp_back70x40.bin", 0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, &bmp_para_back); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, &bmp_para_back); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); - + buttonBack = lv_btn_create(scr, NULL); + lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_FEED_RETURN, NULL, 0); lv_obj_set_pos(buttonBack, PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y); - lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); + lv_obj_set_size(buttonBack, PARA_UI_BACK_BTN_X_SIZE, PARA_UI_BACK_BTN_Y_SIZE); + lv_btn_set_style(buttonBack, LV_BTN_STYLE_REL, &style_para_back); + lv_btn_set_style(buttonBack, LV_BTN_STYLE_PR, &style_para_back); label_Back = lv_label_create(buttonBack, NULL); + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonBack); + #endif if (gCfgItems.multiple_language != 0) { if (uiCfg.para_ui_page != 1) { - lv_label_set_text(labelXText, machine_menu.XMaxFeedRate); - lv_obj_align(labelXText, buttonXText, LV_ALIGN_IN_LEFT_MID, 0, 0); - - lv_label_set_text(labelYText, machine_menu.YMaxFeedRate); - lv_obj_align(labelYText, buttonYText, LV_ALIGN_IN_LEFT_MID, 0, 0); - - lv_label_set_text(labelZText, machine_menu.ZMaxFeedRate); - lv_obj_align(labelZText, buttonZText, LV_ALIGN_IN_LEFT_MID, 0, 0); - - lv_label_set_text(labelE0Text, machine_menu.E0MaxFeedRate); - lv_obj_align(labelE0Text, buttonE0Text, LV_ALIGN_IN_LEFT_MID, 0, 0); lv_label_set_text(labelTurnPage, machine_menu.next); lv_obj_align(labelTurnPage, buttonTurnPage, LV_ALIGN_CENTER, 0, 0); @@ -337,9 +311,6 @@ void lv_draw_max_feedrate_settings(void) { lv_obj_align(labelE0Value, buttonE0Value, LV_ALIGN_CENTER, 0, 0); } else { - lv_label_set_text(labelE1Text, machine_menu.E1MaxFeedRate); - lv_obj_align(labelE1Text, buttonE1Text, LV_ALIGN_IN_LEFT_MID, 0, 0); - lv_label_set_text(labelTurnPage, machine_menu.previous); lv_obj_align(labelTurnPage, buttonTurnPage, LV_ALIGN_CENTER, 0, 0); @@ -354,6 +325,11 @@ void lv_draw_max_feedrate_settings(void) { } } -void lv_clear_max_feedrate_settings() { lv_obj_del(scr); } +void lv_clear_max_feedrate_settings() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} #endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_max_feedrate_settings.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_max_feedrate_settings.h index 24edae27e4..78caca5ade 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_max_feedrate_settings.h +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_max_feedrate_settings.h @@ -22,12 +22,12 @@ #pragma once #ifdef __cplusplus -extern "C" { /* C-declarations for C++ */ + extern "C" { /* C-declarations for C++ */ #endif extern void lv_draw_max_feedrate_settings(void); extern void lv_clear_max_feedrate_settings(); #ifdef __cplusplus -} /* C-declarations for C++ */ + } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_motor_settings.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_motor_settings.cpp index 7da477bd51..f6568df143 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_motor_settings.cpp +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_motor_settings.cpp @@ -28,6 +28,7 @@ #include "../../../../MarlinCore.h" +extern lv_group_t * g; static lv_obj_t * scr; #define ID_MOTOR_RETURN 1 @@ -37,6 +38,8 @@ static lv_obj_t * scr; #define ID_MOTOR_TMC_CURRENT_ARROW 5 #define ID_MOTOR_STEP_MODE 6 #define ID_MOTOR_STEP_MODE_ARROW 7 +#define ID_HOME_SENSE 8 +#define ID_HOME_SENSE_ARROW 9 static void event_handler(lv_obj_t * obj, lv_event_t event) { switch (obj->mks_obj_id) { @@ -67,6 +70,26 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { lv_draw_step_settings(); } break; + #if USE_SENSORLESS + case ID_HOME_SENSE: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + lv_clear_motor_settings(); + lv_draw_homing_sensitivity_settings(); + } + break; + case ID_HOME_SENSE_ARROW: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + lv_clear_motor_settings(); + lv_draw_homing_sensitivity_settings(); + } + break; + #endif #if HAS_TRINAMIC_CONFIG case ID_MOTOR_TMC_CURRENT: if (event == LV_EVENT_CLICKED) { @@ -113,15 +136,27 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { void lv_draw_motor_settings(void) { lv_obj_t *buttonBack, *label_Back; lv_obj_t *buttonSteps, *labelSteps, *buttonStepsNarrow; + lv_obj_t * line1; + #if USE_SENSORLESS + lv_obj_t *buttonSensitivity, *labelSensitivity, *buttonSensitivityNarrow; + lv_obj_t * line2; + #endif #if HAS_TRINAMIC_CONFIG + #if USE_SENSORLESS + lv_obj_t * line3; + #else + lv_obj_t * line2; + #endif lv_obj_t *buttonTMCcurrent, *labelTMCcurrent, *buttonTMCcurrentNarrow; - lv_obj_t * line2; #if HAS_STEALTHCHOP + #if USE_SENSORLESS + lv_obj_t * line4; + #else + lv_obj_t * line3; + #endif lv_obj_t *buttonStepMode, *labelStepMode, *buttonStepModeNarrow; - lv_obj_t * line3; #endif #endif - lv_obj_t * line1; if (disp_state_stack._disp_state[disp_state_stack._disp_index] != MOTOR_SETTINGS_UI) { disp_state_stack._disp_index++; disp_state_stack._disp_state[disp_state_stack._disp_index] = MOTOR_SETTINGS_UI; @@ -141,9 +176,6 @@ void lv_draw_motor_settings(void) { lv_refr_now(lv_refr_get_disp_refreshing()); - LV_IMG_DECLARE(bmp_para_back); - LV_IMG_DECLARE(bmp_para_arrow); - buttonSteps = lv_btn_create(scr, NULL); /*Add a button the current screen*/ lv_obj_set_pos(buttonSteps, PARA_UI_POS_X, PARA_UI_POS_Y); /*Set its position*/ lv_obj_set_size(buttonSteps, PARA_UI_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ @@ -154,20 +186,54 @@ void lv_draw_motor_settings(void) { lv_btn_set_layout(buttonSteps, LV_LAYOUT_OFF); labelSteps = lv_label_create(buttonSteps, NULL); /*Add a label to the button*/ + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonSteps); + #endif + buttonStepsNarrow = lv_imgbtn_create(scr, NULL); lv_obj_set_pos(buttonStepsNarrow, PARA_UI_POS_X + PARA_UI_SIZE_X, PARA_UI_POS_Y + PARA_UI_ARROW_V); - lv_obj_set_event_cb_mks(buttonStepsNarrow, event_handler, ID_MOTOR_STEPS_ARROW, "bmp_arrow.bin", 0); - lv_imgbtn_set_src(buttonStepsNarrow, LV_BTN_STATE_REL, &bmp_para_arrow); - lv_imgbtn_set_src(buttonStepsNarrow, LV_BTN_STATE_PR, &bmp_para_arrow); + lv_obj_set_event_cb_mks(buttonStepsNarrow, event_handler, ID_MOTOR_STEPS_ARROW, NULL, 0); + lv_imgbtn_set_src(buttonStepsNarrow, LV_BTN_STATE_REL, "F:/bmp_arrow.bin"); + lv_imgbtn_set_src(buttonStepsNarrow, LV_BTN_STATE_PR, "F:/bmp_arrow.bin"); lv_imgbtn_set_style(buttonStepsNarrow, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonStepsNarrow, LV_BTN_STATE_REL, &tft_style_label_rel); lv_btn_set_layout(buttonStepsNarrow, LV_LAYOUT_OFF); - line1 = lv_line_create(lv_scr_act(), NULL); + line1 = lv_line_create(scr, NULL); lv_ex_line(line1, line_points[0]); + + #if USE_SENSORLESS + buttonSensitivity = lv_btn_create(scr, NULL); /*Add a button the current screen*/ + lv_obj_set_pos(buttonSensitivity, PARA_UI_POS_X, PARA_UI_POS_Y * 2); /*Set its position*/ + lv_obj_set_size(buttonSensitivity, PARA_UI_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ + //lv_obj_set_event_cb(buttonMachine, event_handler); + lv_obj_set_event_cb_mks(buttonSensitivity, event_handler, ID_HOME_SENSE, NULL, 0); + lv_btn_set_style(buttonSensitivity, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ + lv_btn_set_style(buttonSensitivity, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ + lv_btn_set_layout(buttonSensitivity, LV_LAYOUT_OFF); + labelSensitivity = lv_label_create(buttonSensitivity, NULL); /*Add a label to the button*/ + + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonSensitivity); + #endif + + buttonSensitivityNarrow = lv_imgbtn_create(scr, NULL); + lv_obj_set_pos(buttonSensitivityNarrow, PARA_UI_POS_X + PARA_UI_SIZE_X, PARA_UI_POS_Y * 2 + PARA_UI_ARROW_V); + lv_obj_set_event_cb_mks(buttonSensitivityNarrow, event_handler, ID_HOME_SENSE_ARROW, NULL, 0); + lv_imgbtn_set_src(buttonSensitivityNarrow, LV_BTN_STATE_REL, "F:/bmp_arrow.bin"); + lv_imgbtn_set_src(buttonSensitivityNarrow, LV_BTN_STATE_PR, "F:/bmp_arrow.bin"); + lv_imgbtn_set_style(buttonSensitivityNarrow, LV_BTN_STATE_PR, &tft_style_label_pre); + lv_imgbtn_set_style(buttonSensitivityNarrow, LV_BTN_STATE_REL, &tft_style_label_rel); + lv_btn_set_layout(buttonSensitivityNarrow, LV_LAYOUT_OFF); + + line2 = lv_line_create(scr, NULL); + lv_ex_line(line2, line_points[1]); + #endif + + #if HAS_TRINAMIC_CONFIG buttonTMCcurrent = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonTMCcurrent, PARA_UI_POS_X, PARA_UI_POS_Y * 2); /*Set its position*/ + lv_obj_set_pos(buttonTMCcurrent, PARA_UI_POS_X, TERN(USE_SENSORLESS, PARA_UI_POS_Y * 3, PARA_UI_POS_Y * 2)); lv_obj_set_size(buttonTMCcurrent, PARA_UI_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ //lv_obj_set_event_cb(buttonMachine, event_handler); lv_obj_set_event_cb_mks(buttonTMCcurrent, event_handler, ID_MOTOR_TMC_CURRENT, NULL, 0); @@ -175,61 +241,86 @@ void lv_draw_motor_settings(void) { lv_btn_set_style(buttonTMCcurrent, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ lv_btn_set_layout(buttonTMCcurrent, LV_LAYOUT_OFF); labelTMCcurrent = lv_label_create(buttonTMCcurrent, NULL); /*Add a label to the button*/ + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonTMCcurrent); + #endif buttonTMCcurrentNarrow = lv_imgbtn_create(scr, NULL); - lv_obj_set_pos(buttonTMCcurrentNarrow, PARA_UI_POS_X + PARA_UI_SIZE_X, PARA_UI_POS_Y * 2 + PARA_UI_ARROW_V); - lv_obj_set_event_cb_mks(buttonTMCcurrentNarrow, event_handler, ID_MOTOR_TMC_CURRENT_ARROW, "bmp_arrow.bin", 0); - lv_imgbtn_set_src(buttonTMCcurrentNarrow, LV_BTN_STATE_REL, &bmp_para_arrow); - lv_imgbtn_set_src(buttonTMCcurrentNarrow, LV_BTN_STATE_PR, &bmp_para_arrow); + lv_obj_set_pos(buttonTMCcurrentNarrow, PARA_UI_POS_X + PARA_UI_SIZE_X, TERN(USE_SENSORLESS, PARA_UI_POS_Y * 3, PARA_UI_POS_Y * 2) + PARA_UI_ARROW_V); + lv_obj_set_event_cb_mks(buttonTMCcurrentNarrow, event_handler, ID_MOTOR_TMC_CURRENT_ARROW, NULL, 0); + lv_imgbtn_set_src(buttonTMCcurrentNarrow, LV_BTN_STATE_REL, "F:/bmp_arrow.bin"); + lv_imgbtn_set_src(buttonTMCcurrentNarrow, LV_BTN_STATE_PR, "F:/bmp_arrow.bin"); lv_imgbtn_set_style(buttonTMCcurrentNarrow, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonTMCcurrentNarrow, LV_BTN_STATE_REL, &tft_style_label_rel); lv_btn_set_layout(buttonTMCcurrentNarrow, LV_LAYOUT_OFF); - - line2 = lv_line_create(lv_scr_act(), NULL); - lv_ex_line(line2, line_points[1]); + #if USE_SENSORLESS + line3 = lv_line_create(scr, NULL); + lv_ex_line(line3, line_points[2]); + #else + line2 = lv_line_create(scr, NULL); + lv_ex_line(line2, line_points[1]); + #endif #if HAS_STEALTHCHOP buttonStepMode = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonStepMode, PARA_UI_POS_X, PARA_UI_POS_Y * 3); /*Set its position*/ + lv_obj_set_pos(buttonStepMode, PARA_UI_POS_X, TERN(USE_SENSORLESS, PARA_UI_POS_Y * 4, PARA_UI_POS_Y * 3)); lv_obj_set_size(buttonStepMode, PARA_UI_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - //lv_obj_set_event_cb(buttonMachine, event_handler); lv_obj_set_event_cb_mks(buttonStepMode, event_handler, ID_MOTOR_STEP_MODE, NULL, 0); lv_btn_set_style(buttonStepMode, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ lv_btn_set_style(buttonStepMode, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ lv_btn_set_layout(buttonStepMode, LV_LAYOUT_OFF); labelStepMode = lv_label_create(buttonStepMode, NULL); /*Add a label to the button*/ + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonStepMode); + #endif + buttonStepModeNarrow = lv_imgbtn_create(scr, NULL); - lv_obj_set_pos(buttonStepModeNarrow, PARA_UI_POS_X + PARA_UI_SIZE_X, PARA_UI_POS_Y * 3 + PARA_UI_ARROW_V); - lv_obj_set_event_cb_mks(buttonStepModeNarrow, event_handler, ID_MOTOR_STEP_MODE_ARROW, "bmp_arrow.bin", 0); - lv_imgbtn_set_src(buttonStepModeNarrow, LV_BTN_STATE_REL, &bmp_para_arrow); - lv_imgbtn_set_src(buttonStepModeNarrow, LV_BTN_STATE_PR, &bmp_para_arrow); + lv_obj_set_pos(buttonStepModeNarrow, PARA_UI_POS_X + PARA_UI_SIZE_X, TERN(USE_SENSORLESS, PARA_UI_POS_Y * 4, PARA_UI_POS_Y * 3) + PARA_UI_ARROW_V); + lv_obj_set_event_cb_mks(buttonStepModeNarrow, event_handler, ID_MOTOR_STEP_MODE_ARROW, NULL, 0); + lv_imgbtn_set_src(buttonStepModeNarrow, LV_BTN_STATE_REL, "F:/bmp_arrow.bin"); + lv_imgbtn_set_src(buttonStepModeNarrow, LV_BTN_STATE_PR, "F:/bmp_arrow.bin"); lv_imgbtn_set_style(buttonStepModeNarrow, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonStepModeNarrow, LV_BTN_STATE_REL, &tft_style_label_rel); lv_btn_set_layout(buttonStepModeNarrow, LV_LAYOUT_OFF); - line3 = lv_line_create(lv_scr_act(), NULL); - lv_ex_line(line3, line_points[2]); - #endif + #if USE_SENSORLESS + line4 = lv_line_create(scr, NULL); + lv_ex_line(line4, line_points[3]); + #else + line3 = lv_line_create(scr, NULL); + lv_ex_line(line3, line_points[2]); + #endif + + #endif // HAS_STEALTHCHOP + #endif // HAS_TRINAMIC_CONFIG buttonBack = lv_imgbtn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_MOTOR_RETURN, "bmp_back70x40.bin", 0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, &bmp_para_back); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, &bmp_para_back); + lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_MOTOR_RETURN, NULL, 0); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_back70x40.bin"); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_back70x40.bin"); lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_set_pos(buttonBack, PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y); lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); label_Back = lv_label_create(buttonBack, NULL); + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonBack); + #endif + if (gCfgItems.multiple_language != 0) { lv_label_set_text(label_Back, common_menu.text_back); lv_obj_align(label_Back, buttonBack, LV_ALIGN_CENTER, 0, 0); lv_label_set_text(labelSteps, machine_menu.StepsConf); lv_obj_align(labelSteps, buttonSteps, LV_ALIGN_IN_LEFT_MID, 0, 0); + + #if USE_SENSORLESS + lv_label_set_text(labelSensitivity, machine_menu.HomingSensitivityConf); + lv_obj_align(labelSensitivity, buttonSensitivity, LV_ALIGN_IN_LEFT_MID, 0, 0); + #endif #if HAS_TRINAMIC_CONFIG lv_label_set_text(labelTMCcurrent, machine_menu.TMCcurrentConf); lv_obj_align(labelTMCcurrent, buttonTMCcurrent, LV_ALIGN_IN_LEFT_MID, 0, 0); @@ -242,6 +333,11 @@ void lv_draw_motor_settings(void) { } -void lv_clear_motor_settings() { lv_obj_del(scr); } +void lv_clear_motor_settings() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} #endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_motor_settings.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_motor_settings.h index bae1918ad5..9a1c7a4db5 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_motor_settings.h +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_motor_settings.h @@ -22,12 +22,12 @@ #pragma once #ifdef __cplusplus -extern "C" { /* C-declarations for C++ */ + extern "C" { /* C-declarations for C++ */ #endif extern void lv_draw_motor_settings(void); extern void lv_clear_motor_settings(); #ifdef __cplusplus -} /* C-declarations for C++ */ + } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_move_motor.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_move_motor.cpp index e0d29467e6..a6c0c0551a 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_move_motor.cpp +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_move_motor.cpp @@ -32,9 +32,10 @@ #include "draw_ui.h" #include "../../../../gcode/queue.h" +extern lv_group_t * g; static lv_obj_t * scr; -static lv_obj_t * labelV, *buttonV; +static lv_obj_t *labelV, *buttonV; #define ID_M_X_P 1 #define ID_M_X_N 2 @@ -179,9 +180,7 @@ void lv_draw_move_motor(void) { lv_refr_now(lv_refr_get_disp_refreshing()); - LV_IMG_DECLARE(bmp_pic); - - /*Create an Image button*/ + // Create an Image button buttonXI = lv_imgbtn_create(scr, NULL); buttonXD = lv_imgbtn_create(scr, NULL); buttonYI = lv_imgbtn_create(scr, NULL); @@ -191,55 +190,56 @@ void lv_draw_move_motor(void) { buttonV = lv_imgbtn_create(scr, NULL); buttonBack = lv_imgbtn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonXI, event_handler, ID_M_X_P, "bmp_xAdd.bin", 0); - lv_imgbtn_set_src(buttonXI, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonXI, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonXI, event_handler, ID_M_X_P, NULL, 0); + lv_imgbtn_set_src(buttonXI, LV_BTN_STATE_REL, "F:/bmp_xAdd.bin"); + lv_imgbtn_set_src(buttonXI, LV_BTN_STATE_PR, "F:/bmp_xAdd.bin"); lv_imgbtn_set_style(buttonXI, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonXI, LV_BTN_STATE_REL, &tft_style_label_rel); lv_obj_clear_protect(buttonXI, LV_PROTECT_FOLLOW); + #if 1 - lv_obj_set_event_cb_mks(buttonXD, event_handler, ID_M_X_N, "bmp_xDec.bin", 0); - lv_imgbtn_set_src(buttonXD, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonXD, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonXD, event_handler, ID_M_X_N, NULL, 0); + lv_imgbtn_set_src(buttonXD, LV_BTN_STATE_REL, "F:/bmp_xDec.bin"); + lv_imgbtn_set_src(buttonXD, LV_BTN_STATE_PR, "F:/bmp_xDec.bin"); lv_imgbtn_set_style(buttonXD, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonXD, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_set_event_cb_mks(buttonYI, event_handler, ID_M_Y_P, "bmp_yAdd.bin", 0); - lv_imgbtn_set_src(buttonYI, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonYI, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonYI, event_handler, ID_M_Y_P, NULL, 0); + lv_imgbtn_set_src(buttonYI, LV_BTN_STATE_REL, "F:/bmp_yAdd.bin"); + lv_imgbtn_set_src(buttonYI, LV_BTN_STATE_PR, "F:/bmp_yAdd.bin"); lv_imgbtn_set_style(buttonYI, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonYI, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_set_event_cb_mks(buttonYD, event_handler, ID_M_Y_N, "bmp_yDec.bin", 0); - lv_imgbtn_set_src(buttonYD, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonYD, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonYD, event_handler, ID_M_Y_N, NULL, 0); + lv_imgbtn_set_src(buttonYD, LV_BTN_STATE_REL, "F:/bmp_yDec.bin"); + lv_imgbtn_set_src(buttonYD, LV_BTN_STATE_PR, "F:/bmp_yDec.bin"); lv_imgbtn_set_style(buttonYD, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonYD, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_set_event_cb_mks(buttonZI, event_handler, ID_M_Z_P, "bmp_zAdd.bin", 0); - lv_imgbtn_set_src(buttonZI, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonZI, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonZI, event_handler, ID_M_Z_P, NULL, 0); + lv_imgbtn_set_src(buttonZI, LV_BTN_STATE_REL, "F:/bmp_zAdd.bin"); + lv_imgbtn_set_src(buttonZI, LV_BTN_STATE_PR, "F:/bmp_zAdd.bin"); lv_imgbtn_set_style(buttonZI, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonZI, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_set_event_cb_mks(buttonZD, event_handler, ID_M_Z_N, "bmp_zDec.bin", 0); - lv_imgbtn_set_src(buttonZD, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonZD, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonZD, event_handler, ID_M_Z_N, NULL, 0); + lv_imgbtn_set_src(buttonZD, LV_BTN_STATE_REL, "F:/bmp_zDec.bin"); + lv_imgbtn_set_src(buttonZD, LV_BTN_STATE_PR, "F:/bmp_zDec.bin"); lv_imgbtn_set_style(buttonZD, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonZD, LV_BTN_STATE_REL, &tft_style_label_rel); //lv_obj_set_event_cb_mks(buttonV, event_handler,ID_T_MORE,"bmp_More.bin",0); - lv_imgbtn_set_src(buttonV, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonV, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonV, event_handler, ID_M_STEP, NULL, 0); lv_imgbtn_set_style(buttonV, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonV, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_M_RETURN, "bmp_return.bin", 0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_M_RETURN, NULL, 0); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_return.bin"); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_return.bin"); lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); #endif // if 1 + lv_obj_set_pos(buttonXI, INTERVAL_V, titleHeight); lv_obj_set_pos(buttonYI, BTN_X_PIXEL + INTERVAL_V * 2, titleHeight); lv_obj_set_pos(buttonZI, BTN_X_PIXEL * 2 + INTERVAL_V * 3, titleHeight); @@ -249,7 +249,7 @@ void lv_draw_move_motor(void) { lv_obj_set_pos(buttonZD, BTN_X_PIXEL * 2 + INTERVAL_V * 3, BTN_Y_PIXEL + INTERVAL_H + titleHeight); lv_obj_set_pos(buttonBack, BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - /*Create a label on the Image button*/ + // Create labels on the image buttons lv_btn_set_layout(buttonXI, LV_LAYOUT_OFF); lv_btn_set_layout(buttonXD, LV_LAYOUT_OFF); lv_btn_set_layout(buttonYI, LV_LAYOUT_OFF); @@ -259,14 +259,14 @@ void lv_draw_move_motor(void) { lv_btn_set_layout(buttonV, LV_LAYOUT_OFF); lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); - lv_obj_t * labelXI = lv_label_create(buttonXI, NULL); - lv_obj_t * labelXD = lv_label_create(buttonXD, NULL); - lv_obj_t * labelYI = lv_label_create(buttonYI, NULL); - lv_obj_t * labelYD = lv_label_create(buttonYD, NULL); - lv_obj_t * labelZI = lv_label_create(buttonZI, NULL); - lv_obj_t * labelZD = lv_label_create(buttonZD, NULL); + lv_obj_t *labelXI = lv_label_create(buttonXI, NULL); + lv_obj_t *labelXD = lv_label_create(buttonXD, NULL); + lv_obj_t *labelYI = lv_label_create(buttonYI, NULL); + lv_obj_t *labelYD = lv_label_create(buttonYD, NULL); + lv_obj_t *labelZI = lv_label_create(buttonZI, NULL); + lv_obj_t *labelZD = lv_label_create(buttonZD, NULL); labelV = lv_label_create(buttonV, NULL); - lv_obj_t * label_Back = lv_label_create(buttonBack, NULL); + lv_obj_t *label_Back = lv_label_create(buttonBack, NULL); if (gCfgItems.multiple_language != 0) { lv_label_set_text(labelXI, move_menu.x_add); @@ -290,6 +290,18 @@ void lv_draw_move_motor(void) { lv_label_set_text(label_Back, common_menu.text_back); lv_obj_align(label_Back, buttonBack, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); } + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonXI); + lv_group_add_obj(g, buttonXD); + lv_group_add_obj(g, buttonYI); + lv_group_add_obj(g, buttonYD); + lv_group_add_obj(g, buttonZI); + lv_group_add_obj(g, buttonZD); + lv_group_add_obj(g, buttonV); + lv_group_add_obj(g, buttonBack); + } + #endif disp_move_dist(); } @@ -297,12 +309,18 @@ void lv_draw_move_motor(void) { void disp_move_dist() { // char buf[30] = {0}; - if ((int)(10 * uiCfg.move_dist) == 1) - lv_obj_set_event_cb_mks(buttonV, event_handler, ID_M_STEP, "bmp_step_move0_1.bin", 0); - else if ((int)(10 * uiCfg.move_dist) == 10) - lv_obj_set_event_cb_mks(buttonV, event_handler, ID_M_STEP, "bmp_step_move1.bin", 0); - else if ((int)(10 * uiCfg.move_dist) == 100) - lv_obj_set_event_cb_mks(buttonV, event_handler, ID_M_STEP, "bmp_step_move10.bin", 0); + if ((int)(10 * uiCfg.move_dist) == 1) { + lv_imgbtn_set_src(buttonV, LV_BTN_STATE_REL, "F:/bmp_step_move0_1.bin"); + lv_imgbtn_set_src(buttonV, LV_BTN_STATE_PR, "F:/bmp_step_move0_1.bin"); + } + else if ((int)(10 * uiCfg.move_dist) == 10) { + lv_imgbtn_set_src(buttonV, LV_BTN_STATE_REL, "F:/bmp_step_move1.bin"); + lv_imgbtn_set_src(buttonV, LV_BTN_STATE_PR, "F:/bmp_step_move1.bin"); + } + else if ((int)(10 * uiCfg.move_dist) == 100) { + lv_imgbtn_set_src(buttonV, LV_BTN_STATE_REL, "F:/bmp_step_move10.bin"); + lv_imgbtn_set_src(buttonV, LV_BTN_STATE_PR, "F:/bmp_step_move10.bin"); + } if (gCfgItems.multiple_language != 0) { if ((int)(10 * uiCfg.move_dist) == 1) { lv_label_set_text(labelV, move_menu.step_01mm); @@ -319,6 +337,11 @@ void disp_move_dist() { } } -void lv_clear_move_motor() { lv_obj_del(scr); } +void lv_clear_move_motor() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} #endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_move_motor.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_move_motor.h index c2583c7ef3..fdbb61f6f9 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_move_motor.h +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_move_motor.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus -extern "C" { /* C-declarations for C++ */ + extern "C" { /* C-declarations for C++ */ #endif extern void lv_draw_move_motor(void); @@ -31,5 +31,5 @@ extern void disp_move_dist(); //extern void disp_temp_ready_print(); #ifdef __cplusplus -} /* C-declarations for C++ */ + } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_number_key.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_number_key.cpp index 7a4e7257e2..4842776304 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_number_key.cpp +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_number_key.cpp @@ -34,8 +34,9 @@ #include "../../../../MarlinCore.h" #include "../../../../module/temperature.h" #include "../../../../gcode/queue.h" + #if ENABLED(POWER_LOSS_RECOVERY) - #include "../../../../../feature/powerloss.h" + #include "../../../../feature/powerloss.h" #endif #include "../../../../gcode/gcode.h" @@ -46,6 +47,11 @@ #include "../../../../feature/tmc_util.h" #endif +#if HAS_BED_PROBE + #include "../../../../module/probe.h" +#endif + +extern lv_group_t * g; static lv_obj_t * scr; static lv_obj_t *buttonValue = NULL; static lv_obj_t *labelValue = NULL; @@ -76,113 +82,92 @@ static void disp_key_value() { float milliamps; #endif + ZERO(public_buf_m); + switch (value) { case PrintAcceleration: - ZERO(public_buf_m); sprintf_P(public_buf_m, PSTR("%.1f"), planner.settings.acceleration); break; case RetractAcceleration: - ZERO(public_buf_m); sprintf_P(public_buf_m, PSTR("%.1f"), planner.settings.retract_acceleration); break; case TravelAcceleration: - ZERO(public_buf_m); sprintf_P(public_buf_m, PSTR("%.1f"), planner.settings.travel_acceleration); break; case XAcceleration: - ZERO(public_buf_m); sprintf_P(public_buf_m, PSTR("%d"), (int)planner.settings.max_acceleration_mm_per_s2[X_AXIS]); break; case YAcceleration: - ZERO(public_buf_m); sprintf_P(public_buf_m, PSTR("%d"), (int)planner.settings.max_acceleration_mm_per_s2[Y_AXIS]); break; case ZAcceleration: - ZERO(public_buf_m); sprintf_P(public_buf_m, PSTR("%d"), (int)planner.settings.max_acceleration_mm_per_s2[Z_AXIS]); break; case E0Acceleration: - ZERO(public_buf_m); sprintf_P(public_buf_m, PSTR("%d"), (int)planner.settings.max_acceleration_mm_per_s2[E_AXIS]); break; case E1Acceleration: - ZERO(public_buf_m); sprintf_P(public_buf_m, PSTR("%d"), (int)planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(1)]); break; case XMaxFeedRate: - ZERO(public_buf_m); sprintf_P(public_buf_m, PSTR("%.1f"), planner.settings.max_feedrate_mm_s[X_AXIS]); break; case YMaxFeedRate: - ZERO(public_buf_m); sprintf_P(public_buf_m, PSTR("%.1f"), planner.settings.max_feedrate_mm_s[Y_AXIS]); break; case ZMaxFeedRate: - ZERO(public_buf_m); sprintf_P(public_buf_m, PSTR("%.1f"), planner.settings.max_feedrate_mm_s[Z_AXIS]); break; case E0MaxFeedRate: - ZERO(public_buf_m); sprintf_P(public_buf_m, PSTR("%.1f"), planner.settings.max_feedrate_mm_s[E_AXIS]); break; case E1MaxFeedRate: - ZERO(public_buf_m); sprintf_P(public_buf_m, PSTR("%.1f"), planner.settings.max_feedrate_mm_s[E_AXIS_N(1)]); break; case XJerk: #if HAS_CLASSIC_JERK - ZERO(public_buf_m); sprintf_P(public_buf_m, PSTR("%.1f"), planner.max_jerk[X_AXIS]); #endif break; case YJerk: #if HAS_CLASSIC_JERK - ZERO(public_buf_m); sprintf_P(public_buf_m, PSTR("%.1f"), planner.max_jerk[Y_AXIS]); #endif break; case ZJerk: #if HAS_CLASSIC_JERK - ZERO(public_buf_m); sprintf_P(public_buf_m, PSTR("%.1f"), planner.max_jerk[Z_AXIS]); #endif break; case EJerk: #if HAS_CLASSIC_JERK - ZERO(public_buf_m); sprintf_P(public_buf_m, PSTR("%.1f"), planner.max_jerk[E_AXIS]); #endif break; case Xstep: - ZERO(public_buf_m); sprintf_P(public_buf_m, PSTR("%.1f"), planner.settings.axis_steps_per_mm[X_AXIS]); break; case Ystep: - ZERO(public_buf_m); sprintf_P(public_buf_m, PSTR("%.1f"), planner.settings.axis_steps_per_mm[Y_AXIS]); break; case Zstep: - ZERO(public_buf_m); sprintf_P(public_buf_m, PSTR("%.1f"), planner.settings.axis_steps_per_mm[Z_AXIS]); break; case E0step: - ZERO(public_buf_m); sprintf_P(public_buf_m, PSTR("%.1f"), planner.settings.axis_steps_per_mm[E_AXIS]); break; case E1step: - ZERO(public_buf_m); sprintf_P(public_buf_m, PSTR("%.1f"), planner.settings.axis_steps_per_mm[E_AXIS_N(1)]); break; case Xcurrent: #if AXIS_IS_TMC(X) - ZERO(public_buf_m); milliamps = stepperX.getMilliamps(); sprintf_P(public_buf_m, PSTR("%.1f"), milliamps); #endif @@ -190,7 +175,6 @@ static void disp_key_value() { case Ycurrent: #if AXIS_IS_TMC(Y) - ZERO(public_buf_m); milliamps = stepperY.getMilliamps(); sprintf_P(public_buf_m, PSTR("%.1f"), milliamps); #endif @@ -198,7 +182,6 @@ static void disp_key_value() { case Zcurrent: #if AXIS_IS_TMC(Z) - ZERO(public_buf_m); milliamps = stepperZ.getMilliamps(); sprintf_P(public_buf_m, PSTR("%.1f"), milliamps); #endif @@ -206,7 +189,6 @@ static void disp_key_value() { case E0current: #if AXIS_IS_TMC(E0) - ZERO(public_buf_m); milliamps = stepperE0.getMilliamps(); sprintf_P(public_buf_m, PSTR("%.1f"), milliamps); #endif @@ -214,24 +196,100 @@ static void disp_key_value() { case E1current: #if AXIS_IS_TMC(E1) - ZERO(public_buf_m); milliamps = stepperE1.getMilliamps(); sprintf_P(public_buf_m, PSTR("%.1f"), milliamps); #endif break; case pause_pos_x: - ZERO(public_buf_m); sprintf_P(public_buf_m, PSTR("%.1f"), gCfgItems.pausePosX); break; case pause_pos_y: - ZERO(public_buf_m); sprintf_P(public_buf_m, PSTR("%.1f"), gCfgItems.pausePosY); break; case pause_pos_z: - ZERO(public_buf_m); sprintf_P(public_buf_m, PSTR("%.1f"), gCfgItems.pausePosZ); break; + case level_pos_x1: + sprintf_P(public_buf_m, PSTR("%d"), (int)gCfgItems.levelingPos[0][0]); + break; + case level_pos_y1: + sprintf_P(public_buf_m, PSTR("%d"), (int)gCfgItems.levelingPos[0][1]); + break; + case level_pos_x2: + sprintf_P(public_buf_m, PSTR("%d"), (int)gCfgItems.levelingPos[1][0]); + break; + case level_pos_y2: + sprintf_P(public_buf_m, PSTR("%d"), (int)gCfgItems.levelingPos[1][1]); + break; + case level_pos_x3: + sprintf_P(public_buf_m, PSTR("%d"), (int)gCfgItems.levelingPos[2][0]); + break; + case level_pos_y3: + sprintf_P(public_buf_m, PSTR("%d"), (int)gCfgItems.levelingPos[2][1]); + break; + case level_pos_x4: + sprintf_P(public_buf_m, PSTR("%d"), (int)gCfgItems.levelingPos[3][0]); + break; + case level_pos_y4: + sprintf_P(public_buf_m, PSTR("%d"), (int)gCfgItems.levelingPos[3][1]); + break; + case level_pos_x5: + sprintf_P(public_buf_m, PSTR("%d"), (int)gCfgItems.levelingPos[4][0]); + break; + case level_pos_y5: + sprintf_P(public_buf_m, PSTR("%d"), (int)gCfgItems.levelingPos[4][1]); + break; + #if HAS_BED_PROBE + case x_offset: + #if HAS_PROBE_XY_OFFSET + sprintf_P(public_buf_m, PSTR("%.1f"), probe.offset.x); + #endif + break; + case y_offset: + #if HAS_PROBE_XY_OFFSET + sprintf_P(public_buf_m, PSTR("%.1f"), probe.offset.y); + #endif + break; + case z_offset: + sprintf_P(public_buf_m, PSTR("%.1f"), probe.offset.z); + break; + #endif + case load_length: + sprintf_P(public_buf_m, PSTR("%d"), gCfgItems.filamentchange_load_length); + break; + case load_speed: + sprintf_P(public_buf_m, PSTR("%d"), gCfgItems.filamentchange_load_speed); + break; + case unload_length: + sprintf_P(public_buf_m, PSTR("%d"), gCfgItems.filamentchange_unload_length); + break; + case unload_speed: + sprintf_P(public_buf_m, PSTR("%d"), gCfgItems.filamentchange_unload_speed); + break; + case filament_temp: + sprintf_P(public_buf_m, PSTR("%d"), gCfgItems.filament_limit_temper); + break; + case x_sensitivity: + #if X_SENSORLESS + sprintf_P(public_buf_m, PSTR("%d"), TERN(X_SENSORLESS, stepperX.homing_threshold(), 0)); + #endif + break; + case y_sensitivity: + #if Y_SENSORLESS + sprintf_P(public_buf_m, PSTR("%d"), TERN(Y_SENSORLESS, stepperY.homing_threshold(), 0)); + #endif + break; + case z_sensitivity: + #if Z_SENSORLESS + sprintf_P(public_buf_m, PSTR("%d"), TERN(Z_SENSORLESS, stepperZ.homing_threshold(), 0)); + #endif + break; + case z2_sensitivity: + #if Z2_SENSORLESS + sprintf_P(public_buf_m, PSTR("%d"), TERN(Z2_SENSORLESS, stepperZ2.homing_threshold(), 0)); + #endif + break; } ZERO(key_value); strcpy(key_value, public_buf_m); @@ -253,15 +311,12 @@ static void set_value_confirm() { switch (value) { case PrintAcceleration: planner.settings.acceleration = atof(key_value); - break; case RetractAcceleration: planner.settings.retract_acceleration = atof(key_value); - break; case TravelAcceleration: planner.settings.travel_acceleration = atof(key_value); - break; case XAcceleration: planner.settings.max_acceleration_mm_per_s2[X_AXIS] = atof(key_value); @@ -293,7 +348,6 @@ static void set_value_confirm() { case E1MaxFeedRate: planner.settings.max_feedrate_mm_s[E_AXIS_N(1)] = atof(key_value); break; - case XJerk: #if HAS_CLASSIC_JERK planner.max_jerk[X_AXIS] = atof(key_value); @@ -314,59 +368,56 @@ static void set_value_confirm() { planner.max_jerk[E_AXIS] = atof(key_value); #endif break; - case Xstep: planner.settings.axis_steps_per_mm[X_AXIS] = atof(key_value); + planner.refresh_positioning(); break; case Ystep: planner.settings.axis_steps_per_mm[Y_AXIS] = atof(key_value); + planner.refresh_positioning(); break; case Zstep: planner.settings.axis_steps_per_mm[Z_AXIS] = atof(key_value); + planner.refresh_positioning(); break; case E0step: planner.settings.axis_steps_per_mm[E_AXIS] = atof(key_value); + planner.refresh_positioning(); break; case E1step: planner.settings.axis_steps_per_mm[E_AXIS_N(1)] = atof(key_value); + planner.refresh_positioning(); break; - case Xcurrent: #if AXIS_IS_TMC(X) current_mA = atoi(key_value); stepperX.rms_current(current_mA); #endif break; - case Ycurrent: #if AXIS_IS_TMC(Y) current_mA = atoi(key_value); stepperY.rms_current(current_mA); #endif break; - case Zcurrent: #if AXIS_IS_TMC(Z) current_mA = atoi(key_value); stepperZ.rms_current(current_mA); #endif break; - case E0current: #if AXIS_IS_TMC(E0) current_mA = atoi(key_value); stepperE0.rms_current(current_mA); #endif break; - case E1current: #if AXIS_IS_TMC(E1) current_mA = atoi(key_value); stepperE1.rms_current(current_mA); #endif break; - - break; case pause_pos_x: gCfgItems.pausePosX = atof(key_value); update_spi_flash(); @@ -379,6 +430,114 @@ static void set_value_confirm() { gCfgItems.pausePosZ = atof(key_value); update_spi_flash(); break; + case level_pos_x1: + gCfgItems.levelingPos[0][0] = atoi(key_value); + update_spi_flash(); + break; + case level_pos_y1: + gCfgItems.levelingPos[0][1] = atoi(key_value); + update_spi_flash(); + break; + case level_pos_x2: + gCfgItems.levelingPos[1][0] = atoi(key_value); + update_spi_flash(); + break; + case level_pos_y2: + gCfgItems.levelingPos[1][1] = atoi(key_value); + update_spi_flash(); + break; + case level_pos_x3: + gCfgItems.levelingPos[2][0] = atoi(key_value); + update_spi_flash(); + break; + case level_pos_y3: + gCfgItems.levelingPos[2][1] = atoi(key_value); + update_spi_flash(); + break; + case level_pos_x4: + gCfgItems.levelingPos[3][0] = atoi(key_value); + update_spi_flash(); + break; + case level_pos_y4: + gCfgItems.levelingPos[3][1] = atoi(key_value); + update_spi_flash(); + break; + case level_pos_x5: + gCfgItems.levelingPos[4][0] = atoi(key_value); + update_spi_flash(); + break; + case level_pos_y5: + gCfgItems.levelingPos[4][1] = atoi(key_value); + update_spi_flash(); + break; + #if HAS_BED_PROBE + case x_offset: + #if HAS_PROBE_XY_OFFSET + float x; + x = atof(key_value); + if (WITHIN(x, -(X_BED_SIZE), X_BED_SIZE)) + probe.offset.x = x; + #endif + break; + case y_offset: + #if HAS_PROBE_XY_OFFSET + float y; + y = atof(key_value); + if (WITHIN(y, -(Y_BED_SIZE), Y_BED_SIZE)) + probe.offset.y = y; + #endif + break; + case z_offset: + float z; + z = atof(key_value); + if (WITHIN(z, Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX)) + probe.offset.z = z; + break; + #endif + case load_length: + gCfgItems.filamentchange_load_length = atoi(key_value); + uiCfg.filament_loading_time = (uint32_t)((gCfgItems.filamentchange_load_length*60.0/gCfgItems.filamentchange_load_speed)+0.5); + update_spi_flash(); + break; + case load_speed: + gCfgItems.filamentchange_load_speed = atoi(key_value); + uiCfg.filament_loading_time = (uint32_t)((gCfgItems.filamentchange_load_length*60.0/gCfgItems.filamentchange_load_speed)+0.5); + update_spi_flash(); + break; + case unload_length: + gCfgItems.filamentchange_unload_length = atoi(key_value); + uiCfg.filament_unloading_time = (uint32_t)((gCfgItems.filamentchange_unload_length*60.0/gCfgItems.filamentchange_unload_speed)+0.5); + update_spi_flash(); + break; + case unload_speed: + gCfgItems.filamentchange_unload_speed = atoi(key_value); + uiCfg.filament_unloading_time = (uint32_t)((gCfgItems.filamentchange_unload_length*60.0/gCfgItems.filamentchange_unload_speed)+0.5); + update_spi_flash(); + break; + case filament_temp: + gCfgItems.filament_limit_temper = atoi(key_value); + update_spi_flash(); + break; + case x_sensitivity: + #if X_SENSORLESS + stepperX.homing_threshold(atoi(key_value)); + #endif + break; + case y_sensitivity: + #if Y_SENSORLESS + stepperY.homing_threshold(atoi(key_value)); + #endif + break; + case z_sensitivity: + #if Z_SENSORLESS + stepperZ.homing_threshold(atoi(key_value)); + #endif + break; + case z2_sensitivity: + #if Z2_SENSORLESS + stepperZ2.homing_threshold(atoi(key_value)); + #endif + break; } gcode.process_subcommands_now_P(PSTR("M500")); } @@ -615,15 +774,13 @@ void lv_draw_number_key(void) { lv_refr_now(lv_refr_get_disp_refreshing()); - //LV_IMG_DECLARE(bmp_pic); - buttonValue = lv_btn_create(scr, NULL); /*Add a button the current screen*/ lv_obj_set_pos(buttonValue, 92, 40); /*Set its position*/ lv_obj_set_size(buttonValue, 296, 40); lv_obj_set_event_cb_mks(buttonValue, event_handler, ID_NUM_KEY1, NULL, 0); lv_btn_set_style(buttonValue, LV_BTN_STYLE_REL, &style_num_text); /*Set the button's released style*/ lv_btn_set_style(buttonValue, LV_BTN_STYLE_PR, &style_num_text); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonValue, LV_LAYOUT_OFF); + //lv_btn_set_layout(buttonValue, LV_LAYOUT_OFF); labelValue = lv_label_create(buttonValue, NULL); /*Add a label to the button*/ NumberKey_1 = lv_btn_create(scr, NULL); /*Add a button the current screen*/ @@ -632,7 +789,7 @@ void lv_draw_number_key(void) { lv_obj_set_event_cb_mks(NumberKey_1, event_handler, ID_NUM_KEY1, NULL, 0); lv_btn_set_style(NumberKey_1, LV_BTN_STYLE_REL, &style_num_key_pre); /*Set the button's released style*/ lv_btn_set_style(NumberKey_1, LV_BTN_STYLE_PR, &style_num_key_rel); /*Set the button's pressed style*/ - lv_btn_set_layout(NumberKey_1, LV_LAYOUT_OFF); + //lv_btn_set_layout(NumberKey_1, LV_LAYOUT_OFF); labelKey_1 = lv_label_create(NumberKey_1, NULL); /*Add a label to the button*/ lv_label_set_text(labelKey_1, machine_menu.key_1); lv_obj_align(labelKey_1, NumberKey_1, LV_ALIGN_CENTER, 0, 0); @@ -643,7 +800,7 @@ void lv_draw_number_key(void) { lv_obj_set_event_cb_mks(NumberKey_2, event_handler, ID_NUM_KEY2, NULL, 0); lv_btn_set_style(NumberKey_2, LV_BTN_STYLE_REL, &style_num_key_pre); /*Set the button's released style*/ lv_btn_set_style(NumberKey_2, LV_BTN_STYLE_PR, &style_num_key_rel); /*Set the button's pressed style*/ - lv_btn_set_layout(NumberKey_2, LV_LAYOUT_OFF); + //lv_btn_set_layout(NumberKey_2, LV_LAYOUT_OFF); labelKey_2 = lv_label_create(NumberKey_2, NULL); /*Add a label to the button*/ lv_label_set_text(labelKey_2, machine_menu.key_2); lv_obj_align(labelKey_2, NumberKey_2, LV_ALIGN_CENTER, 0, 0); @@ -654,7 +811,7 @@ void lv_draw_number_key(void) { lv_obj_set_event_cb_mks(NumberKey_3, event_handler, ID_NUM_KEY3, NULL, 0); lv_btn_set_style(NumberKey_3, LV_BTN_STYLE_REL, &style_num_key_pre); /*Set the button's released style*/ lv_btn_set_style(NumberKey_3, LV_BTN_STYLE_PR, &style_num_key_rel); /*Set the button's pressed style*/ - lv_btn_set_layout(NumberKey_3, LV_LAYOUT_OFF); + //lv_btn_set_layout(NumberKey_3, LV_LAYOUT_OFF); labelKey_3 = lv_label_create(NumberKey_3, NULL); /*Add a label to the button*/ lv_label_set_text(labelKey_3, machine_menu.key_3); lv_obj_align(labelKey_3, NumberKey_3, LV_ALIGN_CENTER, 0, 0); @@ -665,7 +822,7 @@ void lv_draw_number_key(void) { lv_obj_set_event_cb_mks(NumberKey_4, event_handler, ID_NUM_KEY4, NULL, 0); lv_btn_set_style(NumberKey_4, LV_BTN_STYLE_REL, &style_num_key_pre); /*Set the button's released style*/ lv_btn_set_style(NumberKey_4, LV_BTN_STYLE_PR, &style_num_key_rel); /*Set the button's pressed style*/ - lv_btn_set_layout(NumberKey_4, LV_LAYOUT_OFF); + //lv_btn_set_layout(NumberKey_4, LV_LAYOUT_OFF); labelKey_4 = lv_label_create(NumberKey_4, NULL); /*Add a label to the button*/ lv_label_set_text(labelKey_4, machine_menu.key_4); lv_obj_align(labelKey_4, NumberKey_4, LV_ALIGN_CENTER, 0, 0); @@ -676,7 +833,7 @@ void lv_draw_number_key(void) { lv_obj_set_event_cb_mks(NumberKey_5, event_handler, ID_NUM_KEY5, NULL, 0); lv_btn_set_style(NumberKey_5, LV_BTN_STYLE_REL, &style_num_key_pre); /*Set the button's released style*/ lv_btn_set_style(NumberKey_5, LV_BTN_STYLE_PR, &style_num_key_rel); /*Set the button's pressed style*/ - lv_btn_set_layout(NumberKey_5, LV_LAYOUT_OFF); + //lv_btn_set_layout(NumberKey_5, LV_LAYOUT_OFF); labelKey_5 = lv_label_create(NumberKey_5, NULL); /*Add a label to the button*/ lv_label_set_text(labelKey_5, machine_menu.key_5); lv_obj_align(labelKey_5, NumberKey_5, LV_ALIGN_CENTER, 0, 0); @@ -687,7 +844,7 @@ void lv_draw_number_key(void) { lv_obj_set_event_cb_mks(NumberKey_6, event_handler, ID_NUM_KEY6, NULL, 0); lv_btn_set_style(NumberKey_6, LV_BTN_STYLE_REL, &style_num_key_pre); /*Set the button's released style*/ lv_btn_set_style(NumberKey_6, LV_BTN_STYLE_PR, &style_num_key_rel); /*Set the button's pressed style*/ - lv_btn_set_layout(NumberKey_6, LV_LAYOUT_OFF); + //lv_btn_set_layout(NumberKey_6, LV_LAYOUT_OFF); labelKey_6 = lv_label_create(NumberKey_6, NULL); /*Add a label to the button*/ lv_label_set_text(labelKey_6, machine_menu.key_6); lv_obj_align(labelKey_6, NumberKey_6, LV_ALIGN_CENTER, 0, 0); @@ -698,7 +855,7 @@ void lv_draw_number_key(void) { lv_obj_set_event_cb_mks(NumberKey_7, event_handler, ID_NUM_KEY7, NULL, 0); lv_btn_set_style(NumberKey_7, LV_BTN_STYLE_REL, &style_num_key_pre); /*Set the button's released style*/ lv_btn_set_style(NumberKey_7, LV_BTN_STYLE_PR, &style_num_key_rel); /*Set the button's pressed style*/ - lv_btn_set_layout(NumberKey_7, LV_LAYOUT_OFF); + //lv_btn_set_layout(NumberKey_7, LV_LAYOUT_OFF); labelKey_7 = lv_label_create(NumberKey_7, NULL); /*Add a label to the button*/ lv_label_set_text(labelKey_7, machine_menu.key_7); lv_obj_align(labelKey_7, NumberKey_7, LV_ALIGN_CENTER, 0, 0); @@ -709,7 +866,7 @@ void lv_draw_number_key(void) { lv_obj_set_event_cb_mks(NumberKey_8, event_handler, ID_NUM_KEY8, NULL, 0); lv_btn_set_style(NumberKey_8, LV_BTN_STYLE_REL, &style_num_key_pre); /*Set the button's released style*/ lv_btn_set_style(NumberKey_8, LV_BTN_STYLE_PR, &style_num_key_rel); /*Set the button's pressed style*/ - lv_btn_set_layout(NumberKey_8, LV_LAYOUT_OFF); + //lv_btn_set_layout(NumberKey_8, LV_LAYOUT_OFF); labelKey_8 = lv_label_create(NumberKey_8, NULL); /*Add a label to the button*/ lv_label_set_text(labelKey_8, machine_menu.key_8); lv_obj_align(labelKey_8, NumberKey_8, LV_ALIGN_CENTER, 0, 0); @@ -720,7 +877,7 @@ void lv_draw_number_key(void) { lv_obj_set_event_cb_mks(NumberKey_9, event_handler, ID_NUM_KEY9, NULL, 0); lv_btn_set_style(NumberKey_9, LV_BTN_STYLE_REL, &style_num_key_pre); /*Set the button's released style*/ lv_btn_set_style(NumberKey_9, LV_BTN_STYLE_PR, &style_num_key_rel); /*Set the button's pressed style*/ - lv_btn_set_layout(NumberKey_9, LV_LAYOUT_OFF); + //lv_btn_set_layout(NumberKey_9, LV_LAYOUT_OFF); labelKey_9 = lv_label_create(NumberKey_9, NULL); /*Add a label to the button*/ lv_label_set_text(labelKey_9, machine_menu.key_9); lv_obj_align(labelKey_9, NumberKey_9, LV_ALIGN_CENTER, 0, 0); @@ -731,7 +888,7 @@ void lv_draw_number_key(void) { lv_obj_set_event_cb_mks(NumberKey_0, event_handler, ID_NUM_KEY0, NULL, 0); lv_btn_set_style(NumberKey_0, LV_BTN_STYLE_REL, &style_num_key_pre); /*Set the button's released style*/ lv_btn_set_style(NumberKey_0, LV_BTN_STYLE_PR, &style_num_key_rel); /*Set the button's pressed style*/ - lv_btn_set_layout(NumberKey_0, LV_LAYOUT_OFF); + //lv_btn_set_layout(NumberKey_0, LV_LAYOUT_OFF); labelKey_0 = lv_label_create(NumberKey_0, NULL); /*Add a label to the button*/ lv_label_set_text(labelKey_0, machine_menu.key_0); lv_obj_align(labelKey_0, NumberKey_0, LV_ALIGN_CENTER, 0, 0); @@ -742,7 +899,7 @@ void lv_draw_number_key(void) { lv_obj_set_event_cb_mks(KeyBack, event_handler, ID_NUM_BACK, NULL, 0); lv_btn_set_style(KeyBack, LV_BTN_STYLE_REL, &style_num_key_pre); /*Set the button's released style*/ lv_btn_set_style(KeyBack, LV_BTN_STYLE_PR, &style_num_key_rel); /*Set the button's pressed style*/ - lv_btn_set_layout(KeyBack, LV_LAYOUT_OFF); + //lv_btn_set_layout(KeyBack, LV_LAYOUT_OFF); labelKeyBack = lv_label_create(KeyBack, NULL); /*Add a label to the button*/ lv_label_set_text(labelKeyBack, machine_menu.key_back); lv_obj_align(labelKeyBack, KeyBack, LV_ALIGN_CENTER, 0, 0); @@ -753,7 +910,7 @@ void lv_draw_number_key(void) { lv_obj_set_event_cb_mks(KeyReset, event_handler, ID_NUM_RESET, NULL, 0); lv_btn_set_style(KeyReset, LV_BTN_STYLE_REL, &style_num_key_pre); /*Set the button's released style*/ lv_btn_set_style(KeyReset, LV_BTN_STYLE_PR, &style_num_key_rel); /*Set the button's pressed style*/ - lv_btn_set_layout(KeyReset, LV_LAYOUT_OFF); + //lv_btn_set_layout(KeyReset, LV_LAYOUT_OFF); labelKeyReset = lv_label_create(KeyReset, NULL); /*Add a label to the button*/ lv_label_set_text(labelKeyReset, machine_menu.key_reset); lv_obj_align(labelKeyReset, KeyReset, LV_ALIGN_CENTER, 0, 0); @@ -764,7 +921,7 @@ void lv_draw_number_key(void) { lv_obj_set_event_cb_mks(KeyConfirm, event_handler, ID_NUM_CONFIRM, NULL, 0); lv_btn_set_style(KeyConfirm, LV_BTN_STYLE_REL, &style_num_key_pre); /*Set the button's released style*/ lv_btn_set_style(KeyConfirm, LV_BTN_STYLE_PR, &style_num_key_rel); /*Set the button's pressed style*/ - lv_btn_set_layout(KeyConfirm, LV_LAYOUT_OFF); + //lv_btn_set_layout(KeyConfirm, LV_LAYOUT_OFF); labelKeyConfirm = lv_label_create(KeyConfirm, NULL); /*Add a label to the button*/ lv_label_set_text(labelKeyConfirm, machine_menu.key_confirm); lv_obj_align(labelKeyConfirm, KeyConfirm, LV_ALIGN_CENTER, 0, 0); @@ -775,7 +932,7 @@ void lv_draw_number_key(void) { lv_obj_set_event_cb_mks(KeyPoint, event_handler, ID_NUM_POINT, NULL, 0); lv_btn_set_style(KeyPoint, LV_BTN_STYLE_REL, &style_num_key_pre); /*Set the button's released style*/ lv_btn_set_style(KeyPoint, LV_BTN_STYLE_PR, &style_num_key_rel); /*Set the button's pressed style*/ - lv_btn_set_layout(KeyPoint, LV_LAYOUT_OFF); + //lv_btn_set_layout(KeyPoint, LV_LAYOUT_OFF); labelKeyPoint = lv_label_create(KeyPoint, NULL); /*Add a label to the button*/ lv_label_set_text(labelKeyPoint, machine_menu.key_point); lv_obj_align(labelKeyPoint, KeyPoint, LV_ALIGN_CENTER, 0, 0); @@ -786,14 +943,39 @@ void lv_draw_number_key(void) { lv_obj_set_event_cb_mks(Minus, event_handler, ID_NUM_NAGETIVE, NULL, 0); lv_btn_set_style(Minus, LV_BTN_STYLE_REL, &style_num_key_pre); /*Set the button's released style*/ lv_btn_set_style(Minus, LV_BTN_STYLE_PR, &style_num_key_rel); /*Set the button's pressed style*/ - lv_btn_set_layout(Minus, LV_LAYOUT_OFF); + //lv_btn_set_layout(Minus, LV_LAYOUT_OFF); labelMinus = lv_label_create(Minus, NULL); /*Add a label to the button*/ lv_label_set_text(labelMinus, machine_menu.negative); lv_obj_align(labelMinus, Minus, LV_ALIGN_CENTER, 0, 0); + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, NumberKey_1); + lv_group_add_obj(g, NumberKey_2); + lv_group_add_obj(g, NumberKey_3); + lv_group_add_obj(g, KeyBack); + lv_group_add_obj(g, NumberKey_4); + lv_group_add_obj(g, NumberKey_5); + lv_group_add_obj(g, NumberKey_6); + lv_group_add_obj(g, KeyReset); + lv_group_add_obj(g, NumberKey_7); + lv_group_add_obj(g, NumberKey_8); + lv_group_add_obj(g, NumberKey_9); + lv_group_add_obj(g, NumberKey_0); + lv_group_add_obj(g, Minus); + lv_group_add_obj(g, KeyPoint); + lv_group_add_obj(g, KeyConfirm); + } + #endif + disp_key_value(); } -void lv_clear_number_key() { lv_obj_del(scr); } +void lv_clear_number_key() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} #endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_number_key.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_number_key.h index d35cee6343..7902da3649 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_number_key.h +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_number_key.h @@ -22,12 +22,12 @@ #pragma once #ifdef __cplusplus -extern "C" { /* C-declarations for C++ */ + extern "C" { /* C-declarations for C++ */ #endif extern void lv_draw_number_key(void); extern void lv_clear_number_key(); #ifdef __cplusplus -} /* C-declarations for C++ */ + } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_operation.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_operation.cpp index ad8cad03e0..4a4a0ee130 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_operation.cpp +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_operation.cpp @@ -31,7 +31,11 @@ //#include "../lvgl/src/lv_core/lv_refr.h" #include "../../../../MarlinCore.h" +#include "../../../../module/temperature.h" +#include "../../../../module/motion.h" +#include "../../../../sd/cardreader.h" +extern lv_group_t * g; static lv_obj_t * scr; #define ID_O_PRE_HEAT 1 @@ -42,10 +46,13 @@ static lv_obj_t * scr; #define ID_O_RETURN 6 #define ID_O_FAN 7 #define ID_O_POWER_OFF 8 +#define ID_O_BABY_STEP 9 static lv_obj_t *label_PowerOff; static lv_obj_t *buttonPowerOff; +extern feedRate_t feedrate_mm_s; + static void event_handler(lv_obj_t * obj, lv_event_t event) { switch (obj->mks_obj_id) { case ID_O_PRE_HEAT: @@ -80,6 +87,20 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { // nothing to do } else if (event == LV_EVENT_RELEASED) { + #if HAS_MULTI_EXTRUDER + uiCfg.curSprayerChoose_bak = active_extruder; + #endif + if (uiCfg.print_state == WORKING) { + #if ENABLED(SDSUPPORT) + card.pauseSDPrint(); + stop_print_time(); + uiCfg.print_state = PAUSING; + #endif + } + uiCfg.moveSpeed_bak = (uint16_t)feedrate_mm_s; + uiCfg.desireSprayerTempBak = thermalManager.temp_hotend[active_extruder].target; + lv_clear_operation(); + lv_draw_filament_change(); } break; case ID_O_FAN: @@ -116,7 +137,8 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { else if (event == LV_EVENT_RELEASED) { if (gCfgItems.finish_power_off == 1) { gCfgItems.finish_power_off = 0; - lv_obj_set_event_cb_mks(obj, event_handler, ID_O_POWER_OFF, "bmp_manual_off.bin", 0); // didn't find bmp_Mamual... + lv_imgbtn_set_src(buttonPowerOff, LV_BTN_STATE_REL, "F:/bmp_manual_off.bin"); + lv_imgbtn_set_src(buttonPowerOff, LV_BTN_STATE_PR, "F:/bmp_manual_off.bin"); lv_label_set_text(label_PowerOff, printing_more_menu.manual); lv_obj_align(label_PowerOff, buttonPowerOff, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); lv_obj_refresh_ext_draw_pad(label_PowerOff); @@ -124,7 +146,8 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { } else { gCfgItems.finish_power_off = 1; - lv_obj_set_event_cb_mks(obj, event_handler, ID_O_POWER_OFF, "bmp_auto_off.bin", 0); + lv_imgbtn_set_src(buttonPowerOff, LV_BTN_STATE_REL, "F:/bmp_auto_off.bin"); + lv_imgbtn_set_src(buttonPowerOff, LV_BTN_STATE_PR, "F:/bmp_auto_off.bin"); lv_label_set_text(label_PowerOff, printing_more_menu.auto_close); lv_obj_align(label_PowerOff, buttonPowerOff, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); lv_obj_refresh_ext_draw_pad(label_PowerOff); @@ -132,16 +155,26 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { } } break; - + case ID_O_BABY_STEP: + if (event == LV_EVENT_CLICKED) { + // nothing to do + } + else if (event == LV_EVENT_RELEASED) { + lv_clear_operation(); + lv_draw_baby_stepping(); + } + break; } } void lv_draw_operation(void) { - lv_obj_t *buttonPreHeat, *buttonExtrusion, *buttonSpeed; - lv_obj_t *buttonBack, *buttonFan; - lv_obj_t *labelPreHeat, *labelExtrusion; - lv_obj_t *label_Back, *label_Speed, *label_Fan; + lv_obj_t *buttonPreHeat = NULL, *buttonExtrusion = NULL, *buttonSpeed = NULL; + lv_obj_t *buttonBack = NULL, *buttonFan = NULL; + lv_obj_t *labelPreHeat = NULL, *labelExtrusion = NULL; + lv_obj_t *label_Back = NULL, *label_Speed = NULL, *label_Fan = NULL; lv_obj_t *buttonMove = NULL, *label_Move = NULL; + lv_obj_t *buttonBabyStep = NULL, *label_BabyStep = NULL; + lv_obj_t *buttonFilament = NULL, *label_Filament = NULL; if (disp_state_stack._disp_state[disp_state_stack._disp_index] != OPERATE_UI) { disp_state_stack._disp_index++; @@ -162,143 +195,188 @@ void lv_draw_operation(void) { lv_refr_now(lv_refr_get_disp_refreshing()); - LV_IMG_DECLARE(bmp_pic); - - /*Create an Image button*/ - buttonPreHeat = lv_imgbtn_create(scr, NULL); - buttonExtrusion = lv_imgbtn_create(scr, NULL); - buttonFan = lv_imgbtn_create(scr, NULL); - buttonSpeed = lv_imgbtn_create(scr, NULL); - + // Create image buttons + buttonPreHeat = lv_imgbtn_create(scr, NULL); + buttonFilament = lv_imgbtn_create(scr, NULL); + buttonFan = lv_imgbtn_create(scr, NULL); + buttonPowerOff = lv_imgbtn_create(scr, NULL); if (uiCfg.print_state != WORKING) { - //buttonFilament = lv_imgbtn_create(scr, NULL); - //} else { - buttonMove = lv_imgbtn_create(scr, NULL); + buttonExtrusion = lv_imgbtn_create(scr, NULL); + buttonMove = lv_imgbtn_create(scr, NULL); } + else { + buttonSpeed = lv_imgbtn_create(scr, NULL); + buttonBabyStep = lv_imgbtn_create(scr, NULL); + } + buttonBack = lv_imgbtn_create(scr, NULL); - buttonPowerOff = lv_imgbtn_create(scr, NULL); - buttonBack = lv_imgbtn_create(scr, NULL); - - lv_obj_set_event_cb_mks(buttonPreHeat, event_handler, ID_O_PRE_HEAT, "bmp_temp.bin", 0); - lv_imgbtn_set_src(buttonPreHeat, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonPreHeat, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonPreHeat, event_handler, ID_O_PRE_HEAT, NULL, 0); + lv_imgbtn_set_src(buttonPreHeat, LV_BTN_STATE_REL, "F:/bmp_temp.bin"); + lv_imgbtn_set_src(buttonPreHeat, LV_BTN_STATE_PR, "F:/bmp_temp.bin"); lv_imgbtn_set_style(buttonPreHeat, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonPreHeat, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_clear_protect(buttonPreHeat, LV_PROTECT_FOLLOW); + + lv_obj_set_event_cb_mks(buttonFilament, event_handler, ID_O_FILAMENT, NULL, 0); + lv_imgbtn_set_src(buttonFilament, LV_BTN_STATE_REL, "F:/bmp_filamentchange.bin"); + lv_imgbtn_set_src(buttonFilament, LV_BTN_STATE_PR, "F:/bmp_filamentchange.bin"); + lv_imgbtn_set_style(buttonFilament, LV_BTN_STATE_PR, &tft_style_label_pre); + lv_imgbtn_set_style(buttonFilament, LV_BTN_STATE_REL, &tft_style_label_rel); + #if 1 - lv_obj_set_event_cb_mks(buttonExtrusion, event_handler, ID_O_EXTRUCT, "bmp_extrude_opr.bin", 0); - lv_imgbtn_set_src(buttonExtrusion, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonExtrusion, LV_BTN_STATE_PR, &bmp_pic); - lv_imgbtn_set_style(buttonExtrusion, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonExtrusion, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonFan, event_handler, ID_O_FAN, "bmp_fan.bin", 0); - lv_imgbtn_set_src(buttonFan, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonFan, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonFan, event_handler, ID_O_FAN, NULL, 0); + lv_imgbtn_set_src(buttonFan, LV_BTN_STATE_REL, "F:/bmp_fan.bin"); + lv_imgbtn_set_src(buttonFan, LV_BTN_STATE_PR, "F:/bmp_fan.bin"); lv_imgbtn_set_style(buttonFan, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonFan, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_set_event_cb_mks(buttonSpeed, event_handler, ID_O_SPEED, "bmp_speed.bin", 0); - lv_imgbtn_set_src(buttonSpeed, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonSpeed, LV_BTN_STATE_PR, &bmp_pic); - lv_imgbtn_set_style(buttonSpeed, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonSpeed, LV_BTN_STATE_REL, &tft_style_label_rel); + if (gCfgItems.finish_power_off == 1) { + lv_imgbtn_set_src(buttonPowerOff, LV_BTN_STATE_REL, "F:/bmp_auto_off.bin"); + lv_imgbtn_set_src(buttonPowerOff, LV_BTN_STATE_PR, "F:/bmp_auto_off.bin"); + } + else { + lv_imgbtn_set_src(buttonPowerOff, LV_BTN_STATE_REL, "F:/bmp_manual_off.bin"); + lv_imgbtn_set_src(buttonPowerOff, LV_BTN_STATE_PR, "F:/bmp_manual_off.bin"); + } + lv_obj_set_event_cb_mks(buttonPowerOff, event_handler, ID_O_POWER_OFF, NULL, 0); + lv_imgbtn_set_style(buttonPowerOff, LV_BTN_STATE_PR, &tft_style_label_pre); + lv_imgbtn_set_style(buttonPowerOff, LV_BTN_STATE_REL, &tft_style_label_rel); + + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonPreHeat); + lv_group_add_obj(g, buttonFilament); + lv_group_add_obj(g, buttonFan); + lv_group_add_obj(g, buttonPowerOff); + } + #endif if (uiCfg.print_state != WORKING) { - /* - lv_obj_set_event_cb_mks(buttonFilament, event_handler,ID_O_FILAMENT,"bmp_Filamentchange.bin",0); - lv_imgbtn_set_src(buttonFilament, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonFilament, LV_BTN_STATE_PR, &bmp_pic); - lv_imgbtn_set_style(buttonFilament, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonFilament, LV_BTN_STATE_REL, &tft_style_label_rel); - } else { - */ - lv_obj_set_event_cb_mks(buttonMove, event_handler, ID_O_MOV, "bmp_move_opr.bin", 0); - lv_imgbtn_set_src(buttonMove, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonMove, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonExtrusion, event_handler, ID_O_EXTRUCT, NULL, 0); + lv_imgbtn_set_src(buttonExtrusion, LV_BTN_STATE_REL, "F:/bmp_extrude_opr.bin"); + lv_imgbtn_set_src(buttonExtrusion, LV_BTN_STATE_PR, "F:/bmp_extrude_opr.bin"); + lv_imgbtn_set_style(buttonExtrusion, LV_BTN_STATE_PR, &tft_style_label_pre); + lv_imgbtn_set_style(buttonExtrusion, LV_BTN_STATE_REL, &tft_style_label_rel); + + lv_obj_set_event_cb_mks(buttonMove, event_handler, ID_O_MOV, NULL, 0); + lv_imgbtn_set_src(buttonMove, LV_BTN_STATE_REL, "F:/bmp_move_opr.bin"); + lv_imgbtn_set_src(buttonMove, LV_BTN_STATE_PR, "F:/bmp_move_opr.bin"); lv_imgbtn_set_style(buttonMove, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonMove, LV_BTN_STATE_REL, &tft_style_label_rel); + + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonExtrusion); + lv_group_add_obj(g, buttonMove); + } + #endif + } + else { + lv_obj_set_event_cb_mks(buttonSpeed, event_handler, ID_O_SPEED, NULL, 0); + lv_imgbtn_set_src(buttonSpeed, LV_BTN_STATE_REL, "F:/bmp_speed.bin"); + lv_imgbtn_set_src(buttonSpeed, LV_BTN_STATE_PR, "F:/bmp_speed.bin"); + lv_imgbtn_set_style(buttonSpeed, LV_BTN_STATE_PR, &tft_style_label_pre); + lv_imgbtn_set_style(buttonSpeed, LV_BTN_STATE_REL, &tft_style_label_rel); + + lv_obj_set_event_cb_mks(buttonBabyStep, event_handler, ID_O_BABY_STEP, NULL, 0); + lv_imgbtn_set_src(buttonBabyStep, LV_BTN_STATE_REL, "F:/bmp_mov.bin"); + lv_imgbtn_set_src(buttonBabyStep, LV_BTN_STATE_PR, "F:/bmp_mov.bin"); + lv_imgbtn_set_style(buttonBabyStep, LV_BTN_STATE_PR, &tft_style_label_pre); + lv_imgbtn_set_style(buttonBabyStep, LV_BTN_STATE_REL, &tft_style_label_rel); + + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonSpeed); + lv_group_add_obj(g, buttonBabyStep); + } + #endif } - if (gCfgItems.finish_power_off == 1) - lv_obj_set_event_cb_mks(buttonPowerOff, event_handler, ID_O_POWER_OFF, "bmp_auto_off.bin", 0); - else - lv_obj_set_event_cb_mks(buttonPowerOff, event_handler, ID_O_POWER_OFF, "bmp_manual_off.bin", 0); - lv_imgbtn_set_src(buttonPowerOff, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonPowerOff, LV_BTN_STATE_PR, &bmp_pic); - lv_imgbtn_set_style(buttonPowerOff, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonPowerOff, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_O_RETURN, "bmp_return.bin", 0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_O_RETURN, NULL, 0); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_return.bin"); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_return.bin"); lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); #endif // if 1 - lv_obj_set_pos(buttonPreHeat, INTERVAL_V, titleHeight); - lv_obj_set_pos(buttonExtrusion, BTN_X_PIXEL + INTERVAL_V * 2, titleHeight); + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonBack); + #endif + lv_obj_set_pos(buttonPreHeat, INTERVAL_V, titleHeight); + lv_obj_set_pos(buttonFilament, BTN_X_PIXEL + INTERVAL_V * 2, titleHeight); lv_obj_set_pos(buttonFan, BTN_X_PIXEL * 2 + INTERVAL_V * 3, titleHeight); - lv_obj_set_pos(buttonSpeed, BTN_X_PIXEL * 3 + INTERVAL_V * 4, titleHeight); + lv_obj_set_pos(buttonPowerOff, BTN_X_PIXEL * 3 + INTERVAL_V * 4, titleHeight); if (uiCfg.print_state != WORKING) { /* lv_obj_set_pos(buttonFilament,INTERVAL_V,BTN_Y_PIXEL+INTERVAL_H+titleHeight); } else { */ - lv_obj_set_pos(buttonMove, INTERVAL_V, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - lv_obj_set_pos(buttonPowerOff, BTN_X_PIXEL + INTERVAL_V * 2, BTN_Y_PIXEL + INTERVAL_H + titleHeight); + lv_obj_set_pos(buttonExtrusion, INTERVAL_V, BTN_Y_PIXEL + INTERVAL_H + titleHeight); + lv_obj_set_pos(buttonMove, BTN_X_PIXEL + INTERVAL_V * 2, BTN_Y_PIXEL + INTERVAL_H + titleHeight); } else { - lv_obj_set_pos(buttonPowerOff, INTERVAL_V, BTN_Y_PIXEL + INTERVAL_H + titleHeight); + lv_obj_set_pos(buttonSpeed, INTERVAL_V, BTN_Y_PIXEL + INTERVAL_H + titleHeight); + lv_obj_set_pos(buttonBabyStep, BTN_X_PIXEL + INTERVAL_V * 2, BTN_Y_PIXEL + INTERVAL_H + titleHeight); } + lv_obj_set_pos(buttonBack, BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - /*Create a label on the Image button*/ + // Create labels on the image buttons lv_btn_set_layout(buttonPreHeat, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonExtrusion, LV_LAYOUT_OFF); + lv_btn_set_layout(buttonFilament, LV_LAYOUT_OFF); lv_btn_set_layout(buttonFan, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonSpeed, LV_LAYOUT_OFF); + lv_btn_set_layout(buttonPowerOff, LV_LAYOUT_OFF); if (uiCfg.print_state != WORKING) { /* lv_btn_set_layout(buttonFilament, LV_LAYOUT_OFF); } else { */ + lv_btn_set_layout(buttonExtrusion, LV_LAYOUT_OFF); lv_btn_set_layout(buttonMove, LV_LAYOUT_OFF); } - lv_btn_set_layout(buttonPowerOff, LV_LAYOUT_OFF); + else { + lv_btn_set_layout(buttonSpeed, LV_LAYOUT_OFF); + lv_btn_set_layout(buttonBabyStep, LV_LAYOUT_OFF); + } + lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); labelPreHeat = lv_label_create(buttonPreHeat, NULL); - labelExtrusion = lv_label_create(buttonExtrusion, NULL); - + label_Filament = lv_label_create(buttonFilament, NULL); label_Fan = lv_label_create(buttonFan, NULL); - label_Speed = lv_label_create(buttonSpeed, NULL); + label_PowerOff = lv_label_create(buttonPowerOff, NULL); if (uiCfg.print_state != WORKING) { /* label_Filament = lv_label_create(buttonFilament, NULL); } else { */ - label_Move = lv_label_create(buttonMove, NULL); + labelExtrusion = lv_label_create(buttonExtrusion, NULL); + label_Move = lv_label_create(buttonMove, NULL); + } + else { + label_Speed = lv_label_create(buttonSpeed, NULL); + label_BabyStep = lv_label_create(buttonBabyStep, NULL); } - label_PowerOff = lv_label_create(buttonPowerOff, NULL); - label_Back = lv_label_create(buttonBack, NULL); if (gCfgItems.multiple_language != 0) { lv_label_set_text(labelPreHeat, operation_menu.temp); lv_obj_align(labelPreHeat, buttonPreHeat, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - lv_label_set_text(labelExtrusion, operation_menu.extr); - lv_obj_align(labelExtrusion, buttonExtrusion, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + lv_label_set_text(label_Filament, operation_menu.filament); + lv_obj_align(label_Filament, buttonFilament, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); lv_label_set_text(label_Fan, operation_menu.fan); lv_obj_align(label_Fan, buttonFan, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - lv_label_set_text(label_Speed, operation_menu.speed); - lv_obj_align(label_Speed, buttonSpeed, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + if (gCfgItems.finish_power_off == 1) + lv_label_set_text(label_PowerOff, printing_more_menu.auto_close); + else + lv_label_set_text(label_PowerOff, printing_more_menu.manual); + lv_obj_align(label_PowerOff, buttonPowerOff, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); if (uiCfg.print_state != WORKING) { /* @@ -306,21 +384,30 @@ void lv_draw_operation(void) { lv_obj_align(label_Filament, buttonFilament, LV_ALIGN_IN_BOTTOM_MID,0, BUTTON_TEXT_Y_OFFSET); } else { */ + lv_label_set_text(labelExtrusion, operation_menu.extr); + lv_obj_align(labelExtrusion, buttonExtrusion, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + lv_label_set_text(label_Move, operation_menu.move); lv_obj_align(label_Move, buttonMove, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); } + else { + lv_label_set_text(label_Speed, operation_menu.speed); + lv_obj_align(label_Speed, buttonSpeed, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - if (gCfgItems.finish_power_off == 1) - lv_label_set_text(label_PowerOff, printing_more_menu.auto_close); - else - lv_label_set_text(label_PowerOff, printing_more_menu.manual); - lv_obj_align(label_PowerOff, buttonPowerOff, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + lv_label_set_text(label_BabyStep, operation_menu.babystep); + lv_obj_align(label_BabyStep, buttonBabyStep, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + } lv_label_set_text(label_Back, common_menu.text_back); lv_obj_align(label_Back, buttonBack, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); } } -void lv_clear_operation() { lv_obj_del(scr); } +void lv_clear_operation() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} #endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_operation.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_operation.h index e2eaaf06a4..cca1f6a2a5 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_operation.h +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_operation.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus -extern "C" { /* C-declarations for C++ */ + extern "C" { /* C-declarations for C++ */ #endif extern void lv_draw_operation(void); @@ -30,5 +30,5 @@ extern void lv_clear_operation(); //extern void disp_temp_ready_print(); #ifdef __cplusplus -} /* C-declarations for C++ */ + } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_pause_message.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_pause_message.h index ce541ee68b..7d55d83756 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_pause_message.h +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_pause_message.h @@ -22,12 +22,12 @@ #pragma once #ifdef __cplusplus -extern "C" { /* C-declarations for C++ */ + extern "C" { /* C-declarations for C++ */ #endif extern void lv_draw_pause_message(const PauseMessage msg); //extern void disp_temp_ready_print(); #ifdef __cplusplus -} /* C-declarations for C++ */ + } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_pause_position.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_pause_position.cpp index 56caf812b1..9b99971f4f 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_pause_position.cpp +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_pause_position.cpp @@ -29,6 +29,7 @@ #include "../../../../MarlinCore.h" #include "../../../../module/planner.h" +extern lv_group_t * g; static lv_obj_t * scr; #define ID_PAUSE_RETURN 1 @@ -82,9 +83,9 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { void lv_draw_pause_position(void) { lv_obj_t *buttonBack = NULL, *label_Back = NULL; - lv_obj_t *buttonXText = NULL, *labelXText = NULL, *buttonXValue = NULL, *labelXValue = NULL; - lv_obj_t *buttonYText = NULL, *labelYText = NULL, *buttonYValue = NULL, *labelYValue = NULL; - lv_obj_t *buttonZText = NULL, *labelZText = NULL, *buttonZValue = NULL, *labelZValue = NULL; + lv_obj_t *labelXText = NULL, *buttonXValue = NULL, *labelXValue = NULL; + lv_obj_t *labelYText = NULL, *buttonYValue = NULL, *labelYValue = NULL; + lv_obj_t *labelZText = NULL, *buttonZValue = NULL, *labelZValue = NULL; lv_obj_t * line1 = NULL, * line2 = NULL, * line3 = NULL; if (disp_state_stack._disp_state[disp_state_stack._disp_index] != PAUSE_POS_UI) { @@ -106,85 +107,60 @@ void lv_draw_pause_position(void) { lv_refr_now(lv_refr_get_disp_refreshing()); - LV_IMG_DECLARE(bmp_para_back); - // LV_IMG_DECLARE(bmp_para_arrow); - LV_IMG_DECLARE(bmp_para_bank); + labelXText = lv_label_create(scr, NULL); + lv_obj_set_style(labelXText, &tft_style_label_rel); + lv_obj_set_pos(labelXText, PARA_UI_POS_X, PARA_UI_POS_Y + 10); + lv_label_set_text(labelXText, machine_menu.xPos); - buttonXText = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonXText, PARA_UI_POS_X, PARA_UI_POS_Y); /*Set its position*/ - lv_obj_set_size(buttonXText, PARA_UI_VALUE_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - lv_obj_set_event_cb(buttonXText, event_handler); - lv_btn_set_style(buttonXText, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonXText, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonXText, LV_LAYOUT_OFF); - labelXText = lv_label_create(buttonXText, NULL); /*Add a label to the button*/ - - buttonXValue = lv_imgbtn_create(scr, NULL); + buttonXValue = lv_btn_create(scr, NULL); lv_obj_set_pos(buttonXValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y + PARA_UI_VALUE_V); - lv_obj_set_event_cb_mks(buttonXValue, event_handler, ID_PAUSE_X, "bmp_value_blank.bin", 0); - lv_imgbtn_set_src(buttonXValue, LV_BTN_STATE_REL, &bmp_para_bank); - lv_imgbtn_set_src(buttonXValue, LV_BTN_STATE_PR, &bmp_para_bank); - lv_imgbtn_set_style(buttonXValue, LV_BTN_STATE_PR, &style_para_value_pre); - lv_imgbtn_set_style(buttonXValue, LV_BTN_STATE_REL, &style_para_value_rel); - lv_btn_set_layout(buttonXValue, LV_LAYOUT_OFF); + lv_obj_set_size(buttonXValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_btn_set_style(buttonXValue, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonXValue, LV_BTN_STYLE_PR, &style_para_value); + lv_obj_set_event_cb_mks(buttonXValue, event_handler, ID_PAUSE_X, NULL, 0); labelXValue = lv_label_create(buttonXValue, NULL); line1 = lv_line_create(scr, NULL); lv_ex_line(line1, line_points[0]); - buttonYText = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonYText, PARA_UI_POS_X, PARA_UI_POS_Y * 2); /*Set its position*/ - lv_obj_set_size(buttonYText, PARA_UI_VALUE_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - lv_obj_set_event_cb(buttonYText, event_handler); - lv_btn_set_style(buttonYText, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonYText, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonYText, LV_LAYOUT_OFF); - labelYText = lv_label_create(buttonYText, NULL); /*Add a label to the button*/ + labelYText = lv_label_create(scr, NULL); + lv_obj_set_style(labelYText, &tft_style_label_rel); + lv_obj_set_pos(labelYText, PARA_UI_POS_X, PARA_UI_POS_Y * 2 + 10); + lv_label_set_text(labelYText, machine_menu.yPos); - buttonYValue = lv_imgbtn_create(scr, NULL); + buttonYValue = lv_btn_create(scr, NULL); lv_obj_set_pos(buttonYValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 2 + PARA_UI_VALUE_V); - lv_obj_set_event_cb_mks(buttonYValue, event_handler, ID_PAUSE_Y, "bmp_value_blank.bin", 0); - lv_imgbtn_set_src(buttonYValue, LV_BTN_STATE_REL, &bmp_para_bank); - lv_imgbtn_set_src(buttonYValue, LV_BTN_STATE_PR, &bmp_para_bank); - lv_imgbtn_set_style(buttonYValue, LV_BTN_STATE_PR, &style_para_value_pre); - lv_imgbtn_set_style(buttonYValue, LV_BTN_STATE_REL, &style_para_value_rel); - lv_btn_set_layout(buttonYValue, LV_LAYOUT_OFF); + lv_obj_set_size(buttonYValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonYValue, event_handler, ID_PAUSE_Y, NULL, 0); + lv_btn_set_style(buttonYValue, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonYValue, LV_BTN_STYLE_PR, &style_para_value); labelYValue = lv_label_create(buttonYValue, NULL); line2 = lv_line_create(scr, NULL); lv_ex_line(line2, line_points[1]); - buttonZText = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonZText, PARA_UI_POS_X, PARA_UI_POS_Y * 3); /*Set its position*/ - lv_obj_set_size(buttonZText, PARA_UI_VALUE_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - lv_obj_set_event_cb(buttonZText, event_handler); - lv_btn_set_style(buttonZText, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonZText, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonZText, LV_LAYOUT_OFF); - labelZText = lv_label_create(buttonZText, NULL); /*Add a label to the button*/ + labelZText = lv_label_create(scr, NULL); + lv_obj_set_style(labelZText, &tft_style_label_rel); + lv_obj_set_pos(labelZText, PARA_UI_POS_X, PARA_UI_POS_Y * 3 + 10); + lv_label_set_text(labelZText, machine_menu.zPos); - buttonZValue = lv_imgbtn_create(scr, NULL); + buttonZValue = lv_btn_create(scr, NULL); lv_obj_set_pos(buttonZValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 3 + PARA_UI_VALUE_V); - lv_obj_set_event_cb_mks(buttonZValue, event_handler, ID_PAUSE_Z, "bmp_value_blank.bin", 0); - lv_imgbtn_set_src(buttonZValue, LV_BTN_STATE_REL, &bmp_para_bank); - lv_imgbtn_set_src(buttonZValue, LV_BTN_STATE_PR, &bmp_para_bank); - lv_imgbtn_set_style(buttonZValue, LV_BTN_STATE_PR, &style_para_value_pre); - lv_imgbtn_set_style(buttonZValue, LV_BTN_STATE_REL, &style_para_value_rel); - lv_btn_set_layout(buttonZValue, LV_LAYOUT_OFF); + lv_obj_set_size(buttonZValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonZValue, event_handler, ID_PAUSE_Z, NULL, 0); + lv_btn_set_style(buttonZValue, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonZValue, LV_BTN_STYLE_PR, &style_para_value); labelZValue = lv_label_create(buttonZValue, NULL); line3 = lv_line_create(scr, NULL); lv_ex_line(line3, line_points[2]); - buttonBack = lv_imgbtn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_PAUSE_RETURN, "bmp_back70x40.bin", 0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, &bmp_para_back); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, &bmp_para_back); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); - + buttonBack = lv_btn_create(scr, NULL); lv_obj_set_pos(buttonBack, PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y); - lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); + lv_obj_set_size(buttonBack, PARA_UI_BACK_BTN_X_SIZE, PARA_UI_BACK_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_PAUSE_RETURN, NULL, 0); + lv_btn_set_style(buttonBack, LV_BTN_STYLE_REL, &style_para_back); + lv_btn_set_style(buttonBack, LV_BTN_STYLE_PR, &style_para_back); label_Back = lv_label_create(buttonBack, NULL); if (gCfgItems.multiple_language != 0) { @@ -203,20 +179,24 @@ void lv_draw_pause_position(void) { lv_label_set_text(labelZValue, public_buf_l); lv_obj_align(labelZValue, buttonZValue, LV_ALIGN_CENTER, 0, 0); - lv_label_set_text(labelXText, machine_menu.xPos); - lv_obj_align(labelXText, buttonXText, LV_ALIGN_IN_LEFT_MID, 0, 0); - - lv_label_set_text(labelYText, machine_menu.yPos); - lv_obj_align(labelYText, buttonYText, LV_ALIGN_IN_LEFT_MID, 0, 0); - - lv_label_set_text(labelZText, machine_menu.zPos); - lv_obj_align(labelZText, buttonZText, LV_ALIGN_IN_LEFT_MID, 0, 0); - lv_label_set_text(label_Back, common_menu.text_back); lv_obj_align(label_Back, buttonBack, LV_ALIGN_CENTER, 0, 0); } + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonXValue); + lv_group_add_obj(g, buttonYValue); + lv_group_add_obj(g, buttonZValue); + lv_group_add_obj(g, buttonBack); + } + #endif } -void lv_clear_pause_position() { lv_obj_del(scr); } +void lv_clear_pause_position() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} #endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_pause_position.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_pause_position.h index 5f1b4dc960..3e9e079827 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_pause_position.h +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_pause_position.h @@ -22,12 +22,12 @@ #pragma once #ifdef __cplusplus -extern "C" { /* C-declarations for C++ */ + extern "C" { /* C-declarations for C++ */ #endif extern void lv_draw_pause_position(void); extern void lv_clear_pause_position(); #ifdef __cplusplus -} /* C-declarations for C++ */ + } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_preHeat.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_preHeat.cpp index 801114e6b2..f58a47b341 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_preHeat.cpp +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_preHeat.cpp @@ -34,9 +34,10 @@ #include "../../../../module/temperature.h" static lv_obj_t * scr; +extern lv_group_t* g; static lv_obj_t *buttoType, *buttonStep; -static lv_obj_t * labelType; -static lv_obj_t * labelStep; +static lv_obj_t *labelType; +static lv_obj_t *labelStep; static lv_obj_t * tempText1; #define ID_P_ADD 1 @@ -58,23 +59,22 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { if (uiCfg.curSprayerChoose == 0) { if ((int)thermalManager.temp_hotend[uiCfg.curSprayerChoose].target > (HEATER_0_MAXTEMP - (WATCH_TEMP_INCREASE + TEMP_HYSTERESIS + 1))) { thermalManager.temp_hotend[uiCfg.curSprayerChoose].target = (float)HEATER_0_MAXTEMP - (WATCH_TEMP_INCREASE + TEMP_HYSTERESIS + 1); - thermalManager.start_watching_hotend(uiCfg.curSprayerChoose); } } - #if !defined(SINGLENOZZLE) && EXTRUDERS >= 2 + #if !defined(SINGLENOZZLE) && HAS_MULTI_EXTRUDER else if ((int)thermalManager.temp_hotend[uiCfg.curSprayerChoose].target > (HEATER_1_MAXTEMP - (WATCH_TEMP_INCREASE + TEMP_HYSTERESIS + 1))) { thermalManager.temp_hotend[uiCfg.curSprayerChoose].target = (float)HEATER_1_MAXTEMP - (WATCH_TEMP_INCREASE + TEMP_HYSTERESIS + 1); - thermalManager.start_watching_hotend(uiCfg.curSprayerChoose); } #endif + thermalManager.start_watching_hotend(uiCfg.curSprayerChoose); } #if HAS_HEATED_BED else { thermalManager.temp_bed.target += uiCfg.stepHeat; if ((int)thermalManager.temp_bed.target > BED_MAXTEMP - (WATCH_BED_TEMP_INCREASE + TEMP_BED_HYSTERESIS + 1)) { thermalManager.temp_bed.target = (float)BED_MAXTEMP - (WATCH_BED_TEMP_INCREASE + TEMP_BED_HYSTERESIS + 1); - thermalManager.start_watching_bed(); } + thermalManager.start_watching_bed(); } #endif disp_desire_temp(); @@ -88,23 +88,21 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { if (uiCfg.curTempType == 0) { if ((int)thermalManager.temp_hotend[uiCfg.curSprayerChoose].target > uiCfg.stepHeat) { thermalManager.temp_hotend[uiCfg.curSprayerChoose].target -= uiCfg.stepHeat; - thermalManager.start_watching_hotend(uiCfg.curSprayerChoose); } else { thermalManager.temp_hotend[uiCfg.curSprayerChoose].target = (float)0; - thermalManager.start_watching_hotend(uiCfg.curSprayerChoose); } + thermalManager.start_watching_hotend(uiCfg.curSprayerChoose); } #if HAS_HEATED_BED else { if ((int)thermalManager.temp_bed.target > uiCfg.stepHeat) { thermalManager.temp_bed.target -= uiCfg.stepHeat; - thermalManager.start_watching_bed(); } else { thermalManager.temp_bed.target = (float)0; - thermalManager.start_watching_bed(); } + thermalManager.start_watching_bed(); } #endif disp_desire_temp(); @@ -117,7 +115,7 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { } else if (event == LV_EVENT_RELEASED) { if (uiCfg.curTempType == 0) { - if (EXTRUDERS == 2) { + if (ENABLED(HAS_MULTI_EXTRUDER)) { if (uiCfg.curSprayerChoose == 0) { uiCfg.curSprayerChoose = 1; } @@ -212,9 +210,7 @@ void lv_draw_preHeat(void) { lv_refr_now(lv_refr_get_disp_refreshing()); - LV_IMG_DECLARE(bmp_pic); - - /*Create an Image button*/ + // Create image buttons buttonAdd = lv_imgbtn_create(scr, NULL); buttonDec = lv_imgbtn_create(scr, NULL); buttoType = lv_imgbtn_create(scr, NULL); @@ -222,40 +218,37 @@ void lv_draw_preHeat(void) { buttonOff = lv_imgbtn_create(scr, NULL); buttonBack = lv_imgbtn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonAdd, event_handler, ID_P_ADD, "bmp_Add.bin", 0); - lv_imgbtn_set_src(buttonAdd, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonAdd, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonAdd, event_handler, ID_P_ADD, NULL, 0); + lv_imgbtn_set_src(buttonAdd, LV_BTN_STATE_REL, "F:/bmp_Add.bin"); + lv_imgbtn_set_src(buttonAdd, LV_BTN_STATE_PR, "F:/bmp_Add.bin"); lv_imgbtn_set_style(buttonAdd, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonAdd, LV_BTN_STATE_REL, &tft_style_label_rel); lv_obj_clear_protect(buttonAdd, LV_PROTECT_FOLLOW); + #if 1 - lv_obj_set_event_cb_mks(buttonDec, event_handler, ID_P_DEC, "bmp_Dec.bin", 0); - lv_imgbtn_set_src(buttonDec, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonDec, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonDec, event_handler, ID_P_DEC, NULL, 0); + lv_imgbtn_set_src(buttonDec, LV_BTN_STATE_REL, "F:/bmp_Dec.bin"); + lv_imgbtn_set_src(buttonDec, LV_BTN_STATE_PR, "F:/bmp_Dec.bin"); lv_imgbtn_set_style(buttonDec, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonDec, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_imgbtn_set_src(buttoType, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttoType, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttoType, event_handler, ID_P_TYPE, NULL, 0); lv_imgbtn_set_style(buttoType, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttoType, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_imgbtn_set_src(buttonStep, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonStep, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonStep, event_handler, ID_P_STEP, NULL, 0); lv_imgbtn_set_style(buttonStep, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonStep, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_set_event_cb_mks(buttonOff, event_handler, ID_P_OFF, "bmp_speed0.bin", 0); - lv_imgbtn_set_src(buttonOff, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonOff, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonOff, event_handler, ID_P_OFF, NULL, 0); + lv_imgbtn_set_src(buttonOff, LV_BTN_STATE_REL, "F:/bmp_speed0.bin"); + lv_imgbtn_set_src(buttonOff, LV_BTN_STATE_PR, "F:/bmp_speed0.bin"); lv_imgbtn_set_style(buttonOff, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonOff, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_P_RETURN, "bmp_return.bin", 0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_P_RETURN, NULL, 0); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_return.bin"); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_return.bin"); lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); #endif @@ -267,7 +260,7 @@ void lv_draw_preHeat(void) { lv_obj_set_pos(buttonOff, BTN_X_PIXEL * 2 + INTERVAL_V * 3, BTN_Y_PIXEL + INTERVAL_H + titleHeight); lv_obj_set_pos(buttonBack, BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - /*Create a label on the Image button*/ + // Create labels on the image buttons lv_btn_set_layout(buttonAdd, LV_LAYOUT_OFF); lv_btn_set_layout(buttonDec, LV_LAYOUT_OFF); lv_btn_set_layout(buttoType, LV_LAYOUT_OFF); @@ -275,13 +268,12 @@ void lv_draw_preHeat(void) { lv_btn_set_layout(buttonOff, LV_LAYOUT_OFF); lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); - lv_obj_t * labelAdd = lv_label_create(buttonAdd, NULL); - lv_obj_t * labelDec = lv_label_create(buttonDec, NULL); + lv_obj_t *labelAdd = lv_label_create(buttonAdd, NULL); + lv_obj_t *labelDec = lv_label_create(buttonDec, NULL); labelType = lv_label_create(buttoType, NULL); labelStep = lv_label_create(buttonStep, NULL); - lv_obj_t * labelOff = lv_label_create(buttonOff, NULL); - lv_obj_t * label_Back = lv_label_create(buttonBack, NULL); - + lv_obj_t *labelOff = lv_label_create(buttonOff, NULL); + lv_obj_t *label_Back = lv_label_create(buttonBack, NULL); if (gCfgItems.multiple_language != 0) { lv_label_set_text(labelAdd, preheat_menu.add); @@ -296,6 +288,16 @@ void lv_draw_preHeat(void) { lv_label_set_text(label_Back, common_menu.text_back); lv_obj_align(label_Back, buttonBack, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); } + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonAdd); + lv_group_add_obj(g, buttonDec); + lv_group_add_obj(g, buttoType); + lv_group_add_obj(g, buttonStep); + lv_group_add_obj(g, buttonOff); + lv_group_add_obj(g, buttonBack); + } + #endif disp_temp_type(); disp_step_heat(); @@ -306,17 +308,18 @@ void lv_draw_preHeat(void) { } void disp_temp_type() { - if (uiCfg.curTempType == 0) { if (uiCfg.curSprayerChoose == 1) { - lv_obj_set_event_cb_mks(buttoType, event_handler, ID_P_TYPE, "bmp_extru2.bin", 0); + lv_imgbtn_set_src(buttoType, LV_BTN_STATE_REL, "F:/bmp_extru2.bin"); + lv_imgbtn_set_src(buttoType, LV_BTN_STATE_PR, "F:/bmp_extru2.bin"); if (gCfgItems.multiple_language != 0) { lv_label_set_text(labelType, preheat_menu.ext2); lv_obj_align(labelType, buttoType, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); } } else { - lv_obj_set_event_cb_mks(buttoType, event_handler, ID_P_TYPE, "bmp_extru1.bin", 0); + lv_imgbtn_set_src(buttoType, LV_BTN_STATE_REL, "F:/bmp_extru1.bin"); + lv_imgbtn_set_src(buttoType, LV_BTN_STATE_PR, "F:/bmp_extru1.bin"); if (gCfgItems.multiple_language != 0) { lv_label_set_text(labelType, preheat_menu.ext1); lv_obj_align(labelType, buttoType, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); @@ -325,13 +328,13 @@ void disp_temp_type() { } else { - lv_obj_set_event_cb_mks(buttoType, event_handler, ID_P_TYPE, "bmp_bed.bin", 0); + lv_imgbtn_set_src(buttoType, LV_BTN_STATE_REL, "F:/bmp_bed.bin"); + lv_imgbtn_set_src(buttoType, LV_BTN_STATE_PR, "F:/bmp_bed.bin"); if (gCfgItems.multiple_language != 0) { lv_label_set_text(labelType, preheat_menu.hotbed); lv_obj_align(labelType, buttoType, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); } } - } void disp_desire_temp() { @@ -359,12 +362,18 @@ void disp_desire_temp() { } void disp_step_heat() { - if (uiCfg.stepHeat == 1) - lv_obj_set_event_cb_mks(buttonStep, event_handler, ID_P_STEP, "bmp_step1_degree.bin", 0); - else if (uiCfg.stepHeat == 5) - lv_obj_set_event_cb_mks(buttonStep, event_handler, ID_P_STEP, "bmp_step5_degree.bin", 0); - else if (uiCfg.stepHeat == 10) - lv_obj_set_event_cb_mks(buttonStep, event_handler, ID_P_STEP, "bmp_step10_degree.bin", 0); + if (uiCfg.stepHeat == 1) { + lv_imgbtn_set_src(buttonStep, LV_BTN_STATE_REL, "F:/bmp_step1_degree.bin"); + lv_imgbtn_set_src(buttonStep, LV_BTN_STATE_PR, "F:/bmp_step1_degree.bin"); + } + else if (uiCfg.stepHeat == 5) { + lv_imgbtn_set_src(buttonStep, LV_BTN_STATE_REL, "F:/bmp_step5_degree.bin"); + lv_imgbtn_set_src(buttonStep, LV_BTN_STATE_PR, "F:/bmp_step5_degree.bin"); + } + else if (uiCfg.stepHeat == 10) { + lv_imgbtn_set_src(buttonStep, LV_BTN_STATE_REL, "F:/bmp_step10_degree.bin"); + lv_imgbtn_set_src(buttonStep, LV_BTN_STATE_PR, "F:/bmp_step10_degree.bin"); + } if (gCfgItems.multiple_language != 0) { if (uiCfg.stepHeat == 1) { @@ -382,6 +391,11 @@ void disp_step_heat() { } } -void lv_clear_preHeat() { lv_obj_del(scr); } +void lv_clear_preHeat() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} #endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_preHeat.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_preHeat.h index db0e361764..c8de942f3f 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_preHeat.h +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_preHeat.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus -extern "C" { /* C-declarations for C++ */ + extern "C" { /* C-declarations for C++ */ #endif extern void lv_draw_preHeat(void); @@ -33,5 +33,5 @@ extern void disp_desire_temp(); //extern void disp_temp_ready_print(); #ifdef __cplusplus -} /* C-declarations for C++ */ + } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_print_file.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_print_file.cpp index 33405a905f..add0f0394b 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_print_file.cpp +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_print_file.cpp @@ -33,6 +33,7 @@ #include "../../../../sd/cardreader.h" static lv_obj_t * scr; +extern lv_group_t* g; static lv_obj_t *buttonPageUp, *buttonPageDown, *buttonBack, *buttonGcode[FILE_BTN_CNT], *labelPageUp[FILE_BTN_CNT], *buttonText[FILE_BTN_CNT]; @@ -132,11 +133,6 @@ uint8_t have_pre_pic(char *path) { return 0; } -LV_IMG_DECLARE(bmp_pic_117x92); -LV_IMG_DECLARE(bmp_pic_100x100); -LV_IMG_DECLARE(bmp_pic); -LV_IMG_DECLARE(bmp_pic_100x40); - static void event_handler(lv_obj_t * obj, lv_event_t event) { uint8_t i, file_count = 0; //switch (obj->mks_obj_id) @@ -157,7 +153,7 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { #endif if (file_count != 0) { dir_offset[curDirLever].curPage--; - lv_obj_del(scr); + lv_clear_print_file(); disp_gcode_icon(file_count); } } @@ -175,7 +171,7 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { #endif if (file_count != 0) { dir_offset[curDirLever].curPage++; - lv_obj_del(scr); + lv_clear_print_file(); disp_gcode_icon(file_count); } if (file_count < FILE_NUM) @@ -202,12 +198,12 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { #if ENABLED(SDSUPPORT) file_count = search_file(); #endif - lv_obj_del(scr); + lv_clear_print_file(); disp_gcode_icon(file_count); } } else { - lv_obj_del(scr); + lv_clear_print_file(); lv_draw_ready_print(); } } @@ -227,12 +223,12 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { #if ENABLED(SDSUPPORT) file_count = search_file(); #endif - lv_obj_del(scr); + lv_clear_print_file(); disp_gcode_icon(file_count); } else { sel_id = i; - lv_obj_del(scr); + lv_clear_print_file(); lv_draw_dialog(DIALOG_TYPE_PRINT_FILE); } break; @@ -269,9 +265,9 @@ void lv_draw_print_file(void) { #endif disp_gcode_icon(file_count); - //lv_obj_t * labelPageUp = lv_label_create(buttonPageUp, NULL); - //lv_obj_t * labelPageDown = lv_label_create(buttonPageDown, NULL); - //lv_obj_t * label_Back = lv_label_create(buttonBack, NULL); + //lv_obj_t *labelPageUp = lv_label_create(buttonPageUp, NULL); + //lv_obj_t *labelPageDown = lv_label_create(buttonPageDown, NULL); + //lv_obj_t *label_Back = lv_label_create(buttonBack, NULL); /* if (gCfgItems.multiple_language != 0) { @@ -286,7 +282,7 @@ void lv_draw_print_file(void) { } */ } - +static char test_public_buf_l[40]; void disp_gcode_icon(uint8_t file_num) { uint8_t i; @@ -305,27 +301,27 @@ void disp_gcode_icon(uint8_t file_num) { lv_refr_now(lv_refr_get_disp_refreshing()); + // Create image buttons buttonPageUp = lv_imgbtn_create(scr, NULL); buttonPageDown = lv_imgbtn_create(scr, NULL); buttonBack = lv_imgbtn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonPageUp, event_handler, ID_P_UP, "bmp_pageUp.bin", 0); - lv_imgbtn_set_src(buttonPageUp, LV_BTN_STATE_REL, &bmp_pic_117x92); - lv_imgbtn_set_src(buttonPageUp, LV_BTN_STATE_PR, &bmp_pic_117x92); + lv_obj_set_event_cb_mks(buttonPageUp, event_handler, ID_P_UP, NULL, 0); + lv_imgbtn_set_src(buttonPageUp, LV_BTN_STATE_REL, "F:/bmp_pageUp.bin"); + lv_imgbtn_set_src(buttonPageUp, LV_BTN_STATE_PR, "F:/bmp_pageUp.bin"); lv_imgbtn_set_style(buttonPageUp, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonPageUp, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_clear_protect(buttonPageUp, LV_PROTECT_FOLLOW); #if 1 - lv_obj_set_event_cb_mks(buttonPageDown, event_handler, ID_P_DOWN, "bmp_pageDown.bin", 0); - lv_imgbtn_set_src(buttonPageDown, LV_BTN_STATE_REL, &bmp_pic_117x92); - lv_imgbtn_set_src(buttonPageDown, LV_BTN_STATE_PR, &bmp_pic_117x92); + lv_obj_set_event_cb_mks(buttonPageDown, event_handler, ID_P_DOWN, NULL, 0); + lv_imgbtn_set_src(buttonPageDown, LV_BTN_STATE_REL, "F:/bmp_pageDown.bin"); + lv_imgbtn_set_src(buttonPageDown, LV_BTN_STATE_PR, "F:/bmp_pageDown.bin"); lv_imgbtn_set_style(buttonPageDown, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonPageDown, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_P_RETURN, "bmp_back.bin", 0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, &bmp_pic_117x92); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, &bmp_pic_117x92); + lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_P_RETURN, NULL, 0); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_back.bin"); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_back.bin"); lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); #endif @@ -334,8 +330,7 @@ void disp_gcode_icon(uint8_t file_num) { lv_obj_set_pos(buttonPageDown, OTHER_BTN_XPIEL * 3 + INTERVAL_V * 4, titleHeight + OTHER_BTN_YPIEL + INTERVAL_H); lv_obj_set_pos(buttonBack, OTHER_BTN_XPIEL * 3 + INTERVAL_V * 4, titleHeight + OTHER_BTN_YPIEL * 2 + INTERVAL_H * 2); - /*Create a label on the Image button*/ - + // Create labels on the image buttons lv_btn_set_layout(buttonPageUp, LV_LAYOUT_OFF); lv_btn_set_layout(buttonPageDown, LV_LAYOUT_OFF); lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); @@ -365,9 +360,9 @@ void disp_gcode_icon(uint8_t file_num) { cutFileName((char *)list_file.long_name[i], 16, 8, (char *)public_buf_m); if (list_file.IsFolder[i] == 1) { - lv_obj_set_event_cb_mks(buttonGcode[i], event_handler, (i + 1), "bmp_dir.bin", 0); - lv_imgbtn_set_src(buttonGcode[i], LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonGcode[i], LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonGcode[i], event_handler, (i + 1), NULL, 0); + lv_imgbtn_set_src(buttonGcode[i], LV_BTN_STATE_REL, "F:/bmp_dir.bin"); + lv_imgbtn_set_src(buttonGcode[i], LV_BTN_STATE_PR, "F:/bmp_dir.bin"); if (i < 3) lv_obj_set_pos(buttonGcode[i], BTN_X_PIXEL * i + INTERVAL_V * (i + 1), titleHeight); else @@ -380,9 +375,17 @@ void disp_gcode_icon(uint8_t file_num) { } else { if (have_pre_pic((char *)list_file.file_name[i])) { - lv_obj_set_event_cb_mks(buttonGcode[i], event_handler, (i + 1), list_file.file_name[i], 1); - lv_imgbtn_set_src(buttonGcode[i], LV_BTN_STATE_REL, &bmp_pic_100x100); - lv_imgbtn_set_src(buttonGcode[i], LV_BTN_STATE_PR, &bmp_pic_100x100); + + //lv_obj_set_event_cb_mks(buttonGcode[i], event_handler, (i + 1), list_file.file_name[i], 1); + + ZERO(test_public_buf_l); + strcat(test_public_buf_l,"S:"); + strcat(test_public_buf_l,list_file.file_name[i]); + char *temp = strstr(test_public_buf_l,".GCO"); + if (temp) { strcpy(temp,".bin"); } + lv_obj_set_event_cb_mks(buttonGcode[i], event_handler, (i + 1), NULL, 0); + lv_imgbtn_set_src(buttonGcode[i], LV_BTN_STATE_REL, test_public_buf_l); + lv_imgbtn_set_src(buttonGcode[i], LV_BTN_STATE_PR, test_public_buf_l); if (i < 3) { lv_obj_set_pos(buttonGcode[i], BTN_X_PIXEL * i + INTERVAL_V * (i + 1) + FILE_PRE_PIC_X_OFFSET, titleHeight + FILE_PRE_PIC_Y_OFFSET); buttonText[i] = lv_btn_create(scr, NULL); @@ -395,8 +398,6 @@ void disp_gcode_icon(uint8_t file_num) { lv_obj_clear_protect(buttonText[i], LV_PROTECT_FOLLOW); lv_btn_set_layout(buttonText[i], LV_LAYOUT_OFF); //lv_obj_set_event_cb_mks(buttonText[i], event_handler,(i+10),NULL,0); - //lv_imgbtn_set_src(buttonText[i], LV_BTN_STATE_REL, &bmp_pic_100x40); - //lv_imgbtn_set_src(buttonText[i], LV_BTN_STATE_PR, &bmp_pic_100x40); lv_obj_set_pos(buttonText[i], BTN_X_PIXEL * i + INTERVAL_V * (i + 1) + FILE_PRE_PIC_X_OFFSET, titleHeight + FILE_PRE_PIC_Y_OFFSET + 100); lv_obj_set_size(buttonText[i], 100, 40); } @@ -412,8 +413,6 @@ void disp_gcode_icon(uint8_t file_num) { lv_obj_clear_protect(buttonText[i], LV_PROTECT_FOLLOW); lv_btn_set_layout(buttonText[i], LV_LAYOUT_OFF); //lv_obj_set_event_cb_mks(buttonText[i], event_handler,(i+10),NULL,0); - //lv_imgbtn_set_src(buttonText[i], LV_BTN_STATE_REL, &bmp_pic_100x40); - //lv_imgbtn_set_src(buttonText[i], LV_BTN_STATE_PR, &bmp_pic_100x40); lv_obj_set_pos(buttonText[i], BTN_X_PIXEL * (i - 3) + INTERVAL_V * ((i - 3) + 1) + FILE_PRE_PIC_X_OFFSET, BTN_Y_PIXEL + INTERVAL_H + titleHeight + FILE_PRE_PIC_Y_OFFSET + 100); lv_obj_set_size(buttonText[i], 100, 40); } @@ -423,9 +422,9 @@ void disp_gcode_icon(uint8_t file_num) { lv_obj_align(labelPageUp[i], buttonText[i], LV_ALIGN_IN_BOTTOM_MID, 0, 0); } else { - lv_obj_set_event_cb_mks(buttonGcode[i], event_handler, (i + 1), "bmp_file.bin", 0); - lv_imgbtn_set_src(buttonGcode[i], LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonGcode[i], LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonGcode[i], event_handler, (i + 1), NULL, 0); + lv_imgbtn_set_src(buttonGcode[i], LV_BTN_STATE_REL, "F:/bmp_file.bin"); + lv_imgbtn_set_src(buttonGcode[i], LV_BTN_STATE_PR, "F:/bmp_file.bin"); if (i < 3) lv_obj_set_pos(buttonGcode[i], BTN_X_PIXEL * i + INTERVAL_V * (i + 1), titleHeight); else @@ -437,15 +436,26 @@ void disp_gcode_icon(uint8_t file_num) { lv_obj_align(labelPageUp[i], buttonGcode[i], LV_ALIGN_IN_BOTTOM_MID, 0, -5); } } + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonGcode[i]); + #endif + #else // !TFT35 #endif // !TFT35 } + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonPageUp); + lv_group_add_obj(g, buttonPageDown); + lv_group_add_obj(g, buttonBack); + } + #endif } -void lv_open_gcode_file(char *path) { +uint32_t lv_open_gcode_file(char *path) { #if ENABLED(SDSUPPORT) uint32_t *ps4; - int pre_sread_cnt; + uint32_t pre_sread_cnt = 0; char *cur_name; cur_name = strrchr(path, '/'); @@ -458,10 +468,10 @@ void lv_open_gcode_file(char *path) { pre_sread_cnt = (uint32_t)ps4 - (uint32_t)((uint32_t *)(&public_buf[0])); card.setIndex(pre_sread_cnt); } + return pre_sread_cnt; #endif // SDSUPPORT } - int ascii2dec_test(char *ascii) { int result = 0; if (ascii == 0) return 0; @@ -534,6 +544,10 @@ void lv_gcode_file_read(uint8_t *data_buf) { void lv_close_gcode_file() {TERN_(SDSUPPORT, card.closefile());} +void lv_gcode_file_seek(uint32_t pos) { + card.setIndex(pos); +} + void cutFileName(char *path, int len, int bytePerLine, char *outStr) { #if _LFN_UNICODE TCHAR *tmpFile; @@ -616,6 +630,11 @@ void cutFileName(char *path, int len, int bytePerLine, char *outStr) { #endif } -void lv_clear_print_file() { lv_obj_del(scr); } +void lv_clear_print_file() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} #endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_print_file.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_print_file.h index 987282c079..083b3d9acf 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_print_file.h +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_print_file.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus -extern "C" { /* C-declarations for C++ */ + extern "C" { /* C-declarations for C++ */ #endif typedef struct { @@ -52,14 +52,15 @@ extern LIST_FILE list_file; extern void disp_gcode_icon(uint8_t file_num); extern void lv_draw_print_file(void); -extern void lv_open_gcode_file(char *path); +extern uint32_t lv_open_gcode_file(char *path); extern void lv_gcode_file_read(uint8_t *data_buf); extern void lv_close_gcode_file(); extern void cutFileName(char *path, int len, int bytePerLine, char *outStr); extern int ascii2dec_test(char *ascii); extern void lv_clear_print_file(); +extern void lv_gcode_file_seek(uint32_t pos); //extern void disp_temp_ready_print(); #ifdef __cplusplus -} /* C-declarations for C++ */ + } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_printing.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_printing.cpp index 2079ed8245..a81b5b851b 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_printing.cpp +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_printing.cpp @@ -35,6 +35,7 @@ #include "../../../../module/motion.h" #include "../../../../sd/cardreader.h" #include "../../../../gcode/queue.h" +#include "../../../../gcode/gcode.h" #if ENABLED(POWER_LOSS_RECOVERY) #include "../../../../feature/powerloss.h" @@ -43,10 +44,11 @@ #include "../../../ultralcd.h" #endif +extern lv_group_t * g; static lv_obj_t * scr; -static lv_obj_t * labelExt1, * labelExt2, * labelFan, * labelZpos, * labelTime; -static lv_obj_t * labelPause, * labelStop, * labelOperat; -static lv_obj_t * bar1; +static lv_obj_t *labelExt1, * labelExt2, * labelFan, * labelZpos, * labelTime; +static lv_obj_t *labelPause, * labelStop, * labelOperat; +static lv_obj_t * bar1, *bar1ValueText; static lv_obj_t * buttonPause, *buttonOperat, *buttonStop; #if HAS_HEATED_BED @@ -57,8 +59,6 @@ static lv_obj_t * buttonPause, *buttonOperat, *buttonStop; #define ID_STOP 2 #define ID_OPTION 3 -lv_style_t lv_bar_style_indic; - uint8_t once_flag = 0; extern uint32_t To_pre_view; extern uint8_t flash_preview_begin; @@ -82,21 +82,23 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { stop_print_time(); uiCfg.print_state = PAUSING; #endif - lv_obj_set_event_cb_mks(buttonPause, event_handler, ID_PAUSE, "bmp_resume.bin", 0); + lv_imgbtn_set_src(buttonPause, LV_BTN_STATE_REL, "F:/bmp_resume.bin"); + lv_imgbtn_set_src(buttonPause, LV_BTN_STATE_PR, "F:/bmp_resume.bin"); lv_label_set_text(labelPause, printing_menu.resume); lv_obj_align(labelPause, buttonPause, LV_ALIGN_CENTER, 30, 0); } else if (uiCfg.print_state == PAUSED) { uiCfg.print_state = RESUMING; - // if (IS_SD_PAUSED())queue.inject_P(PSTR("M24"));// queue.inject_P(M24_STR); - lv_obj_set_event_cb_mks(obj, event_handler, ID_PAUSE, "bmp_pause.bin", 0); + lv_imgbtn_set_src(obj, LV_BTN_STATE_REL, "F:/bmp_pause.bin"); + lv_imgbtn_set_src(obj, LV_BTN_STATE_PR, "F:/bmp_pause.bin"); lv_label_set_text(labelPause, printing_menu.pause); lv_obj_align(labelPause, buttonPause, LV_ALIGN_CENTER, 30, 0); } #if ENABLED(POWER_LOSS_RECOVERY) else if (uiCfg.print_state == REPRINTING) { uiCfg.print_state = REPRINTED; - lv_obj_set_event_cb_mks(obj, event_handler, ID_PAUSE, "bmp_pause.bin", 0); + lv_imgbtn_set_src(obj, LV_BTN_STATE_REL, "F:/bmp_pause.bin"); + lv_imgbtn_set_src(obj, LV_BTN_STATE_PR, "F:/bmp_pause.bin"); lv_label_set_text(labelPause, printing_menu.pause); lv_obj_align(labelPause, buttonPause, LV_ALIGN_CENTER, 30, 0); // recovery.resume(); @@ -115,7 +117,7 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { } else if (event == LV_EVENT_RELEASED) { if (gcode_preview_over != 1) { - lv_obj_del(scr); + lv_clear_printing(); lv_draw_dialog(DIALOG_TYPE_STOP); } } @@ -126,7 +128,7 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { } else if (event == LV_EVENT_RELEASED) { if (gcode_preview_over != 1) { - lv_obj_del(scr); + lv_clear_printing(); lv_draw_operation(); } } @@ -159,91 +161,76 @@ void lv_draw_printing(void) { lv_refr_now(lv_refr_get_disp_refreshing()); - LV_IMG_DECLARE(bmp_pic_150x80); - LV_IMG_DECLARE(bmp_pic_45x45); - - /*Create an Image button*/ - buttonExt1 = lv_imgbtn_create(scr, NULL); - if (EXTRUDERS == 2) - buttonExt2 = lv_imgbtn_create(scr, NULL); - + // Create image buttons + buttonExt1 = lv_img_create(scr, NULL); + #if HAS_MULTI_EXTRUDER + buttonExt2 = lv_img_create(scr, NULL); + #endif #if HAS_HEATED_BED - buttonBedstate = lv_imgbtn_create(scr, NULL); + buttonBedstate = lv_img_create(scr, NULL); #endif - - buttonFanstate = lv_imgbtn_create(scr, NULL); - buttonZpos = lv_imgbtn_create(scr, NULL); + buttonFanstate = lv_img_create(scr, NULL); + buttonTime = lv_img_create(scr, NULL); + buttonZpos = lv_img_create(scr, NULL); buttonPause = lv_imgbtn_create(scr, NULL); buttonStop = lv_imgbtn_create(scr, NULL); buttonOperat = lv_imgbtn_create(scr, NULL); - buttonTime = lv_imgbtn_create(scr, NULL); - - lv_obj_set_event_cb_mks(buttonExt1, event_handler, 0, "bmp_ext1_state.bin", 0); - lv_imgbtn_set_src(buttonExt1, LV_BTN_STATE_REL, &bmp_pic_45x45); - lv_imgbtn_set_src(buttonExt1, LV_BTN_STATE_PR, &bmp_pic_45x45); - lv_imgbtn_set_style(buttonExt1, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonExt1, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_clear_protect(buttonExt1, LV_PROTECT_FOLLOW); + + lv_img_set_src(buttonExt1, "F:/bmp_ext1_state.bin"); #if 1 - if (EXTRUDERS == 2) { - lv_obj_set_event_cb_mks(buttonExt2, event_handler, 0, "bmp_ext2_state.bin", 0); - lv_imgbtn_set_src(buttonExt2, LV_BTN_STATE_REL, &bmp_pic_45x45); - lv_imgbtn_set_src(buttonExt2, LV_BTN_STATE_PR, &bmp_pic_45x45); - lv_imgbtn_set_style(buttonExt2, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonExt2, LV_BTN_STATE_REL, &tft_style_label_rel); - } + #if HAS_MULTI_EXTRUDER + lv_img_set_src(buttonExt2, "F:/bmp_ext2_state.bin"); + #endif #if HAS_HEATED_BED - lv_obj_set_event_cb_mks(buttonBedstate, event_handler, 0, "bmp_bed_state.bin", 0); - lv_imgbtn_set_src(buttonBedstate, LV_BTN_STATE_REL, &bmp_pic_45x45); - lv_imgbtn_set_src(buttonBedstate, LV_BTN_STATE_PR, &bmp_pic_45x45); - lv_imgbtn_set_style(buttonBedstate, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonBedstate, LV_BTN_STATE_REL, &tft_style_label_rel); + lv_img_set_src(buttonBedstate, "F:/bmp_bed_state.bin"); #endif - lv_obj_set_event_cb_mks(buttonFanstate, event_handler, 0, "bmp_fan_state.bin", 0); - lv_imgbtn_set_src(buttonFanstate, LV_BTN_STATE_REL, &bmp_pic_45x45); - lv_imgbtn_set_src(buttonFanstate, LV_BTN_STATE_PR, &bmp_pic_45x45); - lv_imgbtn_set_style(buttonFanstate, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonFanstate, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonTime, event_handler, 0, "bmp_time_state.bin", 0); - lv_imgbtn_set_src(buttonTime, LV_BTN_STATE_REL, &bmp_pic_45x45); - lv_imgbtn_set_src(buttonTime, LV_BTN_STATE_PR, &bmp_pic_45x45); - lv_imgbtn_set_style(buttonTime, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonTime, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonZpos, event_handler, 0, "bmp_zpos_state.bin", 0); - lv_imgbtn_set_src(buttonZpos, LV_BTN_STATE_REL, &bmp_pic_45x45); - lv_imgbtn_set_src(buttonZpos, LV_BTN_STATE_PR, &bmp_pic_45x45); - lv_imgbtn_set_style(buttonZpos, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonZpos, LV_BTN_STATE_REL, &tft_style_label_rel); - - if (uiCfg.print_state == WORKING) - lv_obj_set_event_cb_mks(buttonPause, event_handler, ID_PAUSE, "bmp_pause.bin", 0); - else - lv_obj_set_event_cb_mks(buttonPause, event_handler, ID_PAUSE, "bmp_resume.bin", 0); - - lv_imgbtn_set_src(buttonPause, LV_BTN_STATE_REL, &bmp_pic_150x80); - lv_imgbtn_set_src(buttonPause, LV_BTN_STATE_PR, &bmp_pic_150x80); + lv_img_set_src(buttonFanstate, "F:/bmp_fan_state.bin"); + + lv_img_set_src(buttonTime, "F:/bmp_time_state.bin"); + + lv_img_set_src(buttonZpos, "F:/bmp_zpos_state.bin"); + + if (uiCfg.print_state == WORKING) { + lv_imgbtn_set_src(buttonPause, LV_BTN_STATE_REL, "F:/bmp_pause.bin"); + lv_imgbtn_set_src(buttonPause, LV_BTN_STATE_PR, "F:/bmp_pause.bin"); + } + else { + lv_imgbtn_set_src(buttonPause, LV_BTN_STATE_REL, "F:/bmp_resume.bin"); + lv_imgbtn_set_src(buttonPause, LV_BTN_STATE_PR, "F:/bmp_resume.bin"); + } + + lv_obj_set_event_cb_mks(buttonPause, event_handler, ID_PAUSE, NULL, 0); lv_imgbtn_set_style(buttonPause, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonPause, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_set_event_cb_mks(buttonStop, event_handler, ID_STOP, "bmp_stop.bin", 0); - lv_imgbtn_set_src(buttonStop, LV_BTN_STATE_REL, &bmp_pic_150x80); - lv_imgbtn_set_src(buttonStop, LV_BTN_STATE_PR, &bmp_pic_150x80); + lv_obj_set_event_cb_mks(buttonStop, event_handler, ID_STOP, NULL, 0); + lv_imgbtn_set_src(buttonStop, LV_BTN_STATE_REL, "F:/bmp_stop.bin"); + lv_imgbtn_set_src(buttonStop, LV_BTN_STATE_PR, "F:/bmp_stop.bin"); lv_imgbtn_set_style(buttonStop, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonStop, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_set_event_cb_mks(buttonOperat, event_handler, ID_OPTION, "bmp_operate.bin", 0); - lv_imgbtn_set_src(buttonOperat, LV_BTN_STATE_REL, &bmp_pic_150x80); - lv_imgbtn_set_src(buttonOperat, LV_BTN_STATE_PR, &bmp_pic_150x80); + lv_obj_set_event_cb_mks(buttonOperat, event_handler, ID_OPTION, NULL, 0); + lv_imgbtn_set_src(buttonOperat, LV_BTN_STATE_REL, "F:/bmp_operate.bin"); + lv_imgbtn_set_src(buttonOperat, LV_BTN_STATE_PR, "F:/bmp_operate.bin"); lv_imgbtn_set_style(buttonOperat, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonOperat, LV_BTN_STATE_REL, &tft_style_label_rel); + #endif // if 1 + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonPause); + lv_group_add_obj(g, buttonStop); + lv_group_add_obj(g, buttonOperat); + } + #endif + lv_obj_set_pos(buttonExt1, 205, 136); - if (EXTRUDERS == 2) + + #if HAS_MULTI_EXTRUDER lv_obj_set_pos(buttonExt2, 350, 136); + #endif #if HAS_HEATED_BED lv_obj_set_pos(buttonBedstate, 205, 186); @@ -256,17 +243,19 @@ void lv_draw_printing(void) { lv_obj_set_pos(buttonStop, 165, 240); lv_obj_set_pos(buttonOperat, 325, 240); - /*Create a label on the Image button*/ - lv_btn_set_layout(buttonExt1, LV_LAYOUT_OFF); - if (EXTRUDERS == 2) - lv_btn_set_layout(buttonExt2, LV_LAYOUT_OFF); + // Create labels on the image buttons + //lv_btn_set_layout(buttonExt1, LV_LAYOUT_OFF); + //#if HAS_MULTI_EXTRUDER + //lv_btn_set_layout(buttonExt2, LV_LAYOUT_OFF); + //#endif - #if HAS_HEATED_BED - lv_btn_set_layout(buttonBedstate, LV_LAYOUT_OFF); - #endif + //#if HAS_HEATED_BED + //lv_btn_set_layout(buttonBedstate, LV_LAYOUT_OFF); + //#endif - lv_btn_set_layout(buttonFanstate, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonZpos, LV_LAYOUT_OFF); + //lv_btn_set_layout(buttonFanstate, LV_LAYOUT_OFF); + //lv_btn_set_layout(buttonTime, LV_LAYOUT_OFF); + //lv_btn_set_layout(buttonZpos, LV_LAYOUT_OFF); lv_btn_set_layout(buttonPause, LV_LAYOUT_OFF); lv_btn_set_layout(buttonStop, LV_LAYOUT_OFF); lv_btn_set_layout(buttonOperat, LV_LAYOUT_OFF); @@ -275,11 +264,11 @@ void lv_draw_printing(void) { lv_obj_set_style(labelExt1, &tft_style_label_rel); lv_obj_set_pos(labelExt1, 250, 146); - if (EXTRUDERS == 2) { + #if HAS_MULTI_EXTRUDER labelExt2 = lv_label_create(scr, NULL); lv_obj_set_style(labelExt2, &tft_style_label_rel); lv_obj_set_pos(labelExt2, 395, 146); - } + #endif #if HAS_HEATED_BED labelBed = lv_label_create(scr, NULL); @@ -291,23 +280,20 @@ void lv_draw_printing(void) { lv_obj_set_style(labelFan, &tft_style_label_rel); lv_obj_set_pos(labelFan, 395, 196); - labelZpos = lv_label_create(scr, NULL); - lv_obj_set_style(labelZpos, &tft_style_label_rel); - lv_obj_set_pos(labelZpos, 395, 96); - labelTime = lv_label_create(scr, NULL); lv_obj_set_style(labelTime, &tft_style_label_rel); lv_obj_set_pos(labelTime, 250, 96); + labelZpos = lv_label_create(scr, NULL); + lv_obj_set_style(labelZpos, &tft_style_label_rel); + lv_obj_set_pos(labelZpos, 395, 96); + labelPause = lv_label_create(buttonPause, NULL); labelStop = lv_label_create(buttonStop, NULL); labelOperat = lv_label_create(buttonOperat, NULL); if (gCfgItems.multiple_language != 0) { - if (uiCfg.print_state == WORKING) - lv_label_set_text(labelPause, printing_menu.pause); - else - lv_label_set_text(labelPause, printing_menu.resume); + lv_label_set_text(labelPause, uiCfg.print_state == WORKING ? printing_menu.pause : printing_menu.resume); lv_obj_align(labelPause, buttonPause, LV_ALIGN_CENTER, 20, 0); lv_label_set_text(labelStop, printing_menu.stop); @@ -317,20 +303,15 @@ void lv_draw_printing(void) { lv_obj_align(labelOperat, buttonOperat, LV_ALIGN_CENTER, 20, 0); } - lv_style_copy(&lv_bar_style_indic, &lv_style_pretty_color); - lv_bar_style_indic.text.color = lv_color_hex3(0xADF); - lv_bar_style_indic.image.color = lv_color_hex3(0xADF); - lv_bar_style_indic.line.color = lv_color_hex3(0xADF); - lv_bar_style_indic.body.main_color = lv_color_hex3(0xADF); - lv_bar_style_indic.body.grad_color = lv_color_hex3(0xADF); - lv_bar_style_indic.body.border.color = lv_color_hex3(0xADF); - bar1 = lv_bar_create(scr, NULL); lv_obj_set_pos(bar1, 205, 36); lv_obj_set_size(bar1, 270, 40); lv_bar_set_style(bar1, LV_BAR_STYLE_INDIC, &lv_bar_style_indic); lv_bar_set_anim_time(bar1, 1000); lv_bar_set_value(bar1, 0, LV_ANIM_ON); + bar1ValueText = lv_label_create(bar1, NULL); + lv_label_set_text(bar1ValueText,"0%"); + lv_obj_align(bar1ValueText, bar1, LV_ALIGN_CENTER, 0, 0); disp_ext_temp(); disp_bed_temp(); @@ -344,11 +325,11 @@ void disp_ext_temp() { sprintf(public_buf_l, printing_menu.temp1, (int)thermalManager.temp_hotend[0].celsius, (int)thermalManager.temp_hotend[0].target); lv_label_set_text(labelExt1, public_buf_l); - if (EXTRUDERS == 2) { + #if HAS_MULTI_EXTRUDER ZERO(public_buf_l); sprintf(public_buf_l, printing_menu.temp1, (int)thermalManager.temp_hotend[1].celsius, (int)thermalManager.temp_hotend[1].target); lv_label_set_text(labelExt2, public_buf_l); - } + #endif } void disp_bed_temp() { @@ -417,6 +398,10 @@ void setProBarRate() { if (disp_state == PRINTING_UI) { lv_bar_set_value(bar1, rate, LV_ANIM_ON); + ZERO(public_buf_l); + sprintf_P(public_buf_l, "%d%%", rate); + lv_label_set_text(bar1ValueText,public_buf_l); + lv_obj_align(bar1ValueText, bar1, LV_ALIGN_CENTER, 0, 0); if (marlin_state == MF_SD_COMPLETE) { if (once_flag == 0) { @@ -430,14 +415,22 @@ void setProBarRate() { once_flag = 1; #if HAS_SUICIDE - if (gCfgItems.finish_power_off == 1) - suicide(); + if (gCfgItems.finish_power_off == 1) { + gcode.process_subcommands_now_P(PSTR("M1001")); + queue.inject_P(PSTR("M81")); + marlin_state = MF_RUNNING; + } #endif } } } } -void lv_clear_printing() { lv_obj_del(scr); } +void lv_clear_printing() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} #endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_printing.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_printing.h index 1f7d9f909d..b7d464e4f0 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_printing.h +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_printing.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus -extern "C" { /* C-declarations for C++ */ + extern "C" { /* C-declarations for C++ */ #endif #define IDLE 0 @@ -48,5 +48,5 @@ extern void setProBarRate(); //extern void disp_temp_ready_print(); #ifdef __cplusplus -} /* C-declarations for C++ */ + } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_ready_print.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_ready_print.cpp index c987ddb084..54ffdca64a 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_ready_print.cpp +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_ready_print.cpp @@ -42,6 +42,7 @@ #include //static lv_obj_t *buttonPrint,*buttonTool,*buttonSet; +extern lv_group_t* g; static lv_obj_t * scr; #if ENABLED(MKS_TEST) uint8_t curent_disp_ui = 0; @@ -59,7 +60,7 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { } else if (event == LV_EVENT_RELEASED) { - lv_obj_del(scr); + lv_clear_ready_print(); lv_draw_tool(); } break; @@ -68,7 +69,7 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { // nothing to do } else if (event == LV_EVENT_RELEASED) { - lv_obj_del(scr); + lv_clear_ready_print(); lv_draw_set(); } break; @@ -77,7 +78,7 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { // nothing to do } else if (event == LV_EVENT_RELEASED) { - lv_obj_del(scr); + lv_clear_ready_print(); lv_draw_print_file(); } break; @@ -111,7 +112,7 @@ void disp_det_error() { lv_obj_t *e1, *e2, *e3, *bed; void mks_disp_test() { char buf[30] = {0}; - //lv_obj_t * label_tool2 = lv_label_create(scr, NULL); + //lv_obj_t *label_tool2 = lv_label_create(scr, NULL); //lv_obj_set_pos(label_tool,20,50); ZERO(buf); sprintf_P(buf, PSTR("e1:%d"), (int)thermalManager.temp_hotend[0].celsius); @@ -132,7 +133,6 @@ void mks_disp_test() { #endif } -extern unsigned char bmp_public_buf[17 * 1024]; void lv_draw_ready_print(void) { char buf[30] = {0}; lv_obj_t *buttonPrint, *buttonTool, *buttonSet; @@ -151,39 +151,21 @@ void lv_draw_ready_print(void) { //lv_obj_set_hidden(scr,true); lv_refr_now(lv_refr_get_disp_refreshing()); - LV_IMG_DECLARE(bmp_pic); - - if (mks_test_flag == 0x1e) { + if (mks_test_flag == 0x1E) { //lv_obj_t * title = lv_label_create(scr, NULL); //lv_obj_set_style(title, &tft_style_label_rel); //lv_obj_set_pos(title,TITLE_XPOS,TITLE_YPOS); //lv_label_set_text(title, creat_title_text()); - /*Create an Image button*/ + // Create image buttons //buttonPrint = lv_imgbtn_create(scr, NULL); buttonTool = lv_imgbtn_create(scr, NULL); //buttonSet = lv_imgbtn_create(scr, NULL); - //lv_obj_set_event_cb_mks(buttonPrint, event_handler,ID_PRINT,"bmp_printing.bin",0); - //lv_imgbtn_set_src_mks(buttonPrint, LV_BTN_STATE_REL, &bmp_pic,(uint8_t *)"bmp_printing.bin"); - //lv_imgbtn_set_src(buttonPrint, LV_BTN_STATE_REL, &bmp_pic); - //lv_imgbtn_set_src(buttonPrint, LV_BTN_STATE_PR, &bmp_pic); - //lv_imgbtn_set_style(buttonPrint, LV_BTN_STATE_PR, &tft_style_label_pre); - //lv_imgbtn_set_style(buttonPrint, LV_BTN_STATE_REL, &tft_style_label_rel); - //lv_obj_clear_protect(buttonPrint, LV_PROTECT_FOLLOW); - #if 1 - //lv_obj_set_event_cb_mks(buttonSet, event_handler,ID_SET,"bmp_set.bin",0); - //lv_imgbtn_set_src_mks(buttonSet, LV_BTN_STATE_REL, &bmp_pic,(uint8_t *)"bmp_set.bin"); - //lv_imgbtn_set_src(buttonSet, LV_BTN_STATE_REL, &bmp_pic); - //lv_imgbtn_set_src(buttonSet, LV_BTN_STATE_PR, &bmp_pic); - //lv_imgbtn_set_style(buttonSet, LV_BTN_STATE_PR, &tft_style_label_pre); - //lv_imgbtn_set_style(buttonSet, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonTool, event_handler, ID_TOOL, "bmp_tool.bin", 0); - //lv_imgbtn_set_src_mks(buttonTool, LV_BTN_STATE_REL, &bmp_pic,(uint8_t *)"bmp_tool.bin"); - lv_imgbtn_set_src(buttonTool, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonTool, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonTool, event_handler, ID_TOOL, NULL, 0); + lv_imgbtn_set_src(buttonTool, LV_BTN_STATE_REL, "F:/bmp_tool.bin"); + lv_imgbtn_set_src(buttonTool, LV_BTN_STATE_PR, "F:/bmp_tool.bin"); lv_imgbtn_set_style(buttonTool, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonTool, LV_BTN_STATE_REL, &tft_style_label_rel); #endif @@ -196,14 +178,14 @@ void lv_draw_ready_print(void) { //lv_obj_set_pos(buttonSet,BTN_X_PIXEL+SIMPLE_FIRST_PAGE_GRAP*2+1,(TFT_HEIGHT-BTN_Y_PIXEL)/2+2); //lv_obj_set_pos(buttonPrint,BTN_X_PIXEL*2+SIMPLE_FIRST_PAGE_GRAP*3+1,(TFT_HEIGHT-BTN_Y_PIXEL)/2+2); - /*Create a label on the Image button*/ + // Create labels on the image buttons //lv_btn_set_layout(buttonPrint, LV_LAYOUT_OFF); //lv_btn_set_layout(buttonSet, LV_LAYOUT_OFF); lv_btn_set_layout(buttonTool, LV_LAYOUT_OFF); - //lv_obj_t * label_print = lv_label_create(buttonPrint, NULL); - //lv_obj_t * label_set = lv_label_create(buttonSet, NULL); - lv_obj_t * label_tool = lv_label_create(buttonTool, NULL); + //lv_obj_t *label_print = lv_label_create(buttonPrint, NULL); + //lv_obj_t *label_set = lv_label_create(buttonSet, NULL); + lv_obj_t *label_tool = lv_label_create(buttonTool, NULL); if (gCfgItems.multiple_language != 0) { //lv_label_set_text(label_print, main_menu.print); //lv_obj_align(label_print, buttonPrint, LV_ALIGN_IN_BOTTOM_MID,0, BUTTON_TEXT_Y_OFFSET); @@ -266,56 +248,37 @@ void lv_draw_ready_print(void) { } else { - //lv_obj_t * title = lv_label_create(scr, NULL); - //lv_obj_set_style(title, &tft_style_label_rel); - //lv_obj_set_pos(title,TITLE_XPOS,TITLE_YPOS); - //lv_label_set_text(title, creat_title_text()); + // Create an Image button + buttonTool = lv_imgbtn_create(scr, NULL); + lv_obj_set_pos(buttonTool, 20, 90); + lv_obj_set_event_cb_mks(buttonTool, event_handler, ID_TOOL, NULL, 0); + lv_imgbtn_set_src(buttonTool, LV_BTN_STATE_REL, "F:/bmp_tool.bin"); + lv_imgbtn_set_src(buttonTool, LV_BTN_STATE_PR, "F:/bmp_tool.bin"); + lv_imgbtn_set_style(buttonTool, LV_BTN_STATE_PR, &tft_style_label_pre); + lv_imgbtn_set_style(buttonTool, LV_BTN_STATE_REL, &tft_style_label_rel); + lv_obj_t *label_tool = lv_label_create(buttonTool, NULL); + lv_btn_set_layout(buttonTool, LV_LAYOUT_OFF); - /*Create an Image button*/ - buttonPrint = lv_imgbtn_create(scr, NULL); - buttonTool = lv_imgbtn_create(scr, NULL); - buttonSet = lv_imgbtn_create(scr, NULL); + buttonSet = lv_imgbtn_create(scr, NULL); + lv_obj_set_pos(buttonSet, 180, 90); + lv_obj_set_event_cb_mks(buttonSet, event_handler, ID_SET, NULL, 0); + lv_imgbtn_set_src(buttonSet, LV_BTN_STATE_REL, "F:/bmp_set.bin"); + lv_imgbtn_set_src(buttonSet, LV_BTN_STATE_PR, "F:/bmp_set.bin"); + lv_imgbtn_set_style(buttonSet, LV_BTN_STATE_PR, &tft_style_label_pre); + lv_imgbtn_set_style(buttonSet, LV_BTN_STATE_REL, &tft_style_label_rel); + lv_obj_t *label_set = lv_label_create(buttonSet, NULL); + lv_btn_set_layout(buttonSet, LV_LAYOUT_OFF); - lv_obj_set_event_cb_mks(buttonPrint, event_handler, ID_PRINT, "bmp_printing.bin", 0); - //lv_imgbtn_set_src_mks(buttonPrint, LV_BTN_STATE_REL, &bmp_pic,(uint8_t *)"bmp_printing.bin"); - lv_imgbtn_set_src(buttonPrint, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonPrint, LV_BTN_STATE_PR, &bmp_pic); + buttonPrint = lv_imgbtn_create(scr, NULL); + lv_obj_set_pos(buttonPrint, 340, 90); + lv_obj_set_event_cb_mks(buttonPrint, event_handler, ID_PRINT, NULL, 0); + lv_imgbtn_set_src(buttonPrint, LV_BTN_STATE_REL, "F:/bmp_printing.bin"); + lv_imgbtn_set_src(buttonPrint, LV_BTN_STATE_PR, "F:/bmp_printing.bin"); lv_imgbtn_set_style(buttonPrint, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonPrint, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_clear_protect(buttonPrint, LV_PROTECT_FOLLOW); - - #if 1 - lv_obj_set_event_cb_mks(buttonSet, event_handler, ID_SET, "bmp_set.bin", 0); - //lv_imgbtn_set_src_mks(buttonSet, LV_BTN_STATE_REL, &bmp_pic,(uint8_t *)"bmp_set.bin"); - lv_imgbtn_set_src(buttonSet, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonSet, LV_BTN_STATE_PR, &bmp_pic); - lv_imgbtn_set_style(buttonSet, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonSet, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonTool, event_handler, ID_TOOL, "bmp_tool.bin", 0); - //lv_imgbtn_set_src_mks(buttonTool, LV_BTN_STATE_REL, &bmp_pic,(uint8_t *)"bmp_tool.bin"); - lv_imgbtn_set_src(buttonTool, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonTool, LV_BTN_STATE_PR, &bmp_pic); - lv_imgbtn_set_style(buttonTool, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonTool, LV_BTN_STATE_REL, &tft_style_label_rel); - #endif - - lv_obj_set_pos(buttonTool, 20, 90); - lv_obj_set_pos(buttonSet, 180, 90); - lv_obj_set_pos(buttonPrint, 340, 90); - - //lv_obj_set_pos(buttonTool,SIMPLE_FIRST_PAGE_GRAP+1,(TFT_HEIGHT-BTN_Y_PIXEL)/2+2); - //lv_obj_set_pos(buttonSet,BTN_X_PIXEL+SIMPLE_FIRST_PAGE_GRAP*2+1,(TFT_HEIGHT-BTN_Y_PIXEL)/2+2); - //lv_obj_set_pos(buttonPrint,BTN_X_PIXEL*2+SIMPLE_FIRST_PAGE_GRAP*3+1,(TFT_HEIGHT-BTN_Y_PIXEL)/2+2); - - /*Create a label on the Image button*/ + lv_obj_t *label_print = lv_label_create(buttonPrint, NULL); lv_btn_set_layout(buttonPrint, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonSet, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonTool, LV_LAYOUT_OFF); - lv_obj_t * label_print = lv_label_create(buttonPrint, NULL); - lv_obj_t * label_set = lv_label_create(buttonSet, NULL); - lv_obj_t * label_tool = lv_label_create(buttonTool, NULL); if (gCfgItems.multiple_language != 0) { lv_label_set_text(label_print, main_menu.print); lv_obj_align(label_print, buttonPrint, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); @@ -323,14 +286,25 @@ void lv_draw_ready_print(void) { lv_label_set_text(label_set, main_menu.set); lv_obj_align(label_set, buttonSet, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - //lv_label_set_style(label_tool,LV_BTN_STATE_PR,&tft_style_label_pre); - //lv_label_set_style(label_tool,LV_BTN_STATE_REL,&tft_style_label_rel); lv_label_set_text(label_tool, main_menu.tool); lv_obj_align(label_tool, buttonTool, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); } + + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable == true) { + lv_group_add_obj(g, buttonTool); + lv_group_add_obj(g, buttonSet); + lv_group_add_obj(g, buttonPrint); + } + #endif } } -void lv_clear_ready_print() { lv_obj_del(scr); } +void lv_clear_ready_print() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable == true) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} #endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_ready_print.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_ready_print.h index 9951beaa41..5cefe8b59b 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_ready_print.h +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_ready_print.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus -extern "C" { /* C-declarations for C++ */ + extern "C" { /* C-declarations for C++ */ #endif extern void lv_draw_ready_print(void); @@ -35,5 +35,5 @@ extern void lv_clear_ready_print(); //extern void disp_temp_ready_print(); #ifdef __cplusplus -} /* C-declarations for C++ */ + } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_set.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_set.cpp index eebb9fcf1c..6c10713d8a 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_set.cpp +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_set.cpp @@ -36,6 +36,7 @@ #include "pic_manager.h" static lv_obj_t * scr; +extern lv_group_t* g; #define ID_S_WIFI 1 #define ID_S_FAN 2 @@ -48,20 +49,17 @@ static lv_obj_t * scr; #define ID_S_RETURN 9 static void event_handler(lv_obj_t * obj, lv_event_t event) { + #if ENABLED(USE_WIFI_FUNCTION) + char buf[6] = { 0 }; + #endif switch (obj->mks_obj_id) { - case ID_S_WIFI: - if (event == LV_EVENT_CLICKED) { - // nothing to do - } - else if (event == LV_EVENT_RELEASED) { - } - break; + case ID_S_FAN: if (event == LV_EVENT_CLICKED) { // nothing to do } else if (event == LV_EVENT_RELEASED) { - lv_obj_del(scr); + lv_clear_set(); lv_draw_fan(); } break; @@ -70,7 +68,7 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { // nothing to do } else if (event == LV_EVENT_RELEASED) { - lv_obj_del(scr); + lv_clear_set(); lv_draw_about(); } break; @@ -94,7 +92,7 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { // nothing to do } else if (event == LV_EVENT_RELEASED) { - lv_obj_del(scr); + lv_clear_set(); lv_draw_language(); } break; @@ -103,7 +101,7 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { } else if (event == LV_EVENT_RELEASED) { - lv_obj_del(scr); + lv_clear_set(); lv_draw_machine_para(); } break; @@ -112,7 +110,7 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { } else if (event == LV_EVENT_RELEASED) { - lv_obj_del(scr); + lv_clear_set(); lv_draw_eeprom_settings(); } break; @@ -121,11 +119,50 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { // nothing to do } else if (event == LV_EVENT_RELEASED) { - lv_obj_del(scr); + lv_clear_set(); lv_draw_ready_print(); } break; - + #if ENABLED(USE_WIFI_FUNCTION) + case ID_S_WIFI: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + if (gCfgItems.wifi_mode_sel == STA_MODEL) { + if (wifi_link_state == WIFI_CONNECTED) { + last_disp_state = SET_UI; + lv_clear_set(); + lv_draw_wifi(); + } + else { + if (uiCfg.command_send == 1) { + buf[0] = 0xA5; + buf[1] = 0x07; + buf[2] = 0x00; + buf[3] = 0x00; + buf[4] = 0xFC; + raw_send_to_wifi(buf, 5); + + last_disp_state = SET_UI; + lv_clear_set(); + lv_draw_wifi_list(); + } + else { + last_disp_state = SET_UI; + lv_clear_set(); + lv_draw_dialog(WIFI_ENABLE_TIPS); + } + } + } + else { + last_disp_state = SET_UI; + lv_clear_set(); + lv_draw_wifi(); + } + } + break; + #endif } } @@ -137,6 +174,9 @@ void lv_draw_set(void) { #endif lv_obj_t *buttonMachinePara; lv_obj_t *buttonEepromSet; + #if ENABLED(USE_WIFI_FUNCTION) + lv_obj_t *buttonWifi; + #endif if (disp_state_stack._disp_state[disp_state_stack._disp_index] != SET_UI) { disp_state_stack._disp_index++; @@ -159,79 +199,81 @@ void lv_draw_set(void) { lv_refr_now(lv_refr_get_disp_refreshing()); - LV_IMG_DECLARE(bmp_pic); - - /*Create an Image button*/ - //buttonWifi = lv_imgbtn_create(scr, NULL); - buttonFan = lv_imgbtn_create(scr, NULL); - buttonAbout = lv_imgbtn_create(scr, NULL); - //buttonContinue = lv_imgbtn_create(scr, NULL); - buMotorOff = lv_imgbtn_create(scr, NULL); + // Create image buttons + buttonEepromSet = lv_imgbtn_create(scr, NULL); + //buttonWifi = lv_imgbtn_create(scr, NULL); + buttonFan = lv_imgbtn_create(scr, NULL); + buttonAbout = lv_imgbtn_create(scr, NULL); + //buttonContinue = lv_imgbtn_create(scr, NULL); + buMotorOff = lv_imgbtn_create(scr, NULL); + buttonMachinePara = lv_imgbtn_create(scr, NULL); #if HAS_LANG_SELECT_SCREEN - buttonLanguage = lv_imgbtn_create(scr, NULL); + buttonLanguage = lv_imgbtn_create(scr, NULL); + #endif + #if ENABLED(USE_WIFI_FUNCTION) + buttonWifi = lv_imgbtn_create(scr, NULL); #endif - buttonMachinePara = lv_imgbtn_create(scr, NULL); - buttonEepromSet = lv_imgbtn_create(scr, NULL); buttonBack = lv_imgbtn_create(scr, NULL); + lv_obj_set_event_cb_mks(buttonEepromSet, event_handler, ID_S_EEPROM_SET, NULL, 0); + lv_imgbtn_set_src(buttonEepromSet, LV_BTN_STATE_REL, "F:/bmp_eeprom_settings.bin"); + lv_imgbtn_set_src(buttonEepromSet, LV_BTN_STATE_PR, "F:/bmp_eeprom_settings.bin"); + lv_imgbtn_set_style(buttonEepromSet, LV_BTN_STATE_PR, &tft_style_label_pre); + lv_imgbtn_set_style(buttonEepromSet, LV_BTN_STATE_REL, &tft_style_label_rel); - //lv_obj_set_event_cb_mks(buttonWifi, event_handler,ID_S_WIFI,"bmp_Wifi.bin",0); - //lv_imgbtn_set_src(buttonWifi, LV_BTN_STATE_REL, &bmp_pic); - //lv_imgbtn_set_src(buttonWifi, LV_BTN_STATE_PR, &bmp_pic); - //lv_imgbtn_set_style(buttonWifi, LV_BTN_STATE_PR, &tft_style_label_pre); - //lv_imgbtn_set_style(buttonWifi, LV_BTN_STATE_REL, &tft_style_label_rel); - //lv_obj_clear_protect(buttonWifi, LV_PROTECT_FOLLOW); #if 1 - lv_obj_set_event_cb_mks(buttonFan, event_handler, ID_S_FAN, "bmp_fan.bin", 0); - lv_imgbtn_set_src(buttonFan, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonFan, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonFan, event_handler, ID_S_FAN, NULL, 0); + lv_imgbtn_set_src(buttonFan, LV_BTN_STATE_REL, "F:/bmp_fan.bin"); + lv_imgbtn_set_src(buttonFan, LV_BTN_STATE_PR, "F:/bmp_fan.bin"); lv_imgbtn_set_style(buttonFan, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonFan, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_set_event_cb_mks(buttonAbout, event_handler, ID_S_ABOUT, "bmp_about.bin", 0); - lv_imgbtn_set_src(buttonAbout, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonAbout, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonAbout, event_handler, ID_S_ABOUT, NULL, 0); + lv_imgbtn_set_src(buttonAbout, LV_BTN_STATE_REL, "F:/bmp_about.bin"); + lv_imgbtn_set_src(buttonAbout, LV_BTN_STATE_PR, "F:/bmp_about.bin"); lv_imgbtn_set_style(buttonAbout, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonAbout, LV_BTN_STATE_REL, &tft_style_label_rel); - //lv_obj_set_event_cb_mks(buttonContinue, event_handler,ID_S_CONTINUE,"bmp_Breakpoint.bin",0); - //lv_imgbtn_set_src(buttonContinue, LV_BTN_STATE_REL, &bmp_pic); - //lv_imgbtn_set_src(buttonContinue, LV_BTN_STATE_PR, &bmp_pic); - //lv_imgbtn_set_style(buttonContinue, LV_BTN_STATE_PR, &tft_style_label_pre); - //lv_imgbtn_set_style(buttonContinue, LV_BTN_STATE_REL, &tft_style_label_rel); + lv_obj_set_event_cb_mks(buMotorOff, event_handler, ID_S_MOTOR_OFF, NULL, 0); + #if HAS_SUICIDE - lv_obj_set_event_cb_mks(buMotorOff, event_handler, ID_S_MOTOR_OFF, "bmp_Mamual.bin", 0); + lv_imgbtn_set_src(buMotorOff, LV_BTN_STATE_REL, "F:/bmp_manual_off.bin"); + lv_imgbtn_set_src(buMotorOff, LV_BTN_STATE_PR, "F:/bmp_manual_off.bin"); #else - lv_obj_set_event_cb_mks(buMotorOff, event_handler, ID_S_MOTOR_OFF, "bmp_function1.bin", 0); + lv_imgbtn_set_src(buMotorOff, LV_BTN_STATE_REL, "F:/bmp_function1.bin"); + lv_imgbtn_set_src(buMotorOff, LV_BTN_STATE_PR, "F:/bmp_function1.bin"); #endif - lv_imgbtn_set_src(buMotorOff, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buMotorOff, LV_BTN_STATE_PR, &bmp_pic); lv_imgbtn_set_style(buMotorOff, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buMotorOff, LV_BTN_STATE_REL, &tft_style_label_rel); + lv_obj_set_event_cb_mks(buttonMachinePara, event_handler, ID_S_MACHINE_PARA, NULL, 0); + lv_imgbtn_set_src(buttonMachinePara, LV_BTN_STATE_REL, "F:/bmp_machine_para.bin"); + lv_imgbtn_set_src(buttonMachinePara, LV_BTN_STATE_PR, "F:/bmp_machine_para.bin"); + lv_imgbtn_set_style(buttonMachinePara, LV_BTN_STATE_PR, &tft_style_label_pre); + lv_imgbtn_set_style(buttonMachinePara, LV_BTN_STATE_REL, &tft_style_label_rel); + #if HAS_LANG_SELECT_SCREEN - lv_obj_set_event_cb_mks(buttonLanguage, event_handler, ID_S_LANGUAGE, "bmp_language.bin", 0); - lv_imgbtn_set_src(buttonLanguage, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonLanguage, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonLanguage, event_handler, ID_S_LANGUAGE, NULL, 0); + lv_imgbtn_set_src(buttonLanguage, LV_BTN_STATE_REL, "F:/bmp_language.bin"); + lv_imgbtn_set_src(buttonLanguage, LV_BTN_STATE_PR, "F:/bmp_language.bin"); lv_imgbtn_set_style(buttonLanguage, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonLanguage, LV_BTN_STATE_REL, &tft_style_label_rel); #endif - lv_obj_set_event_cb_mks(buttonMachinePara, event_handler, ID_S_MACHINE_PARA, "bmp_machine_para.bin", 0); - lv_imgbtn_set_src(buttonMachinePara, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonMachinePara, LV_BTN_STATE_PR, &bmp_pic); - lv_imgbtn_set_style(buttonMachinePara, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonMachinePara, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_set_event_cb_mks(buttonEepromSet, event_handler, ID_S_EEPROM_SET, "bmp_eeprom_settings.bin", 0); - lv_imgbtn_set_src(buttonEepromSet, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonEepromSet, LV_BTN_STATE_PR, &bmp_pic); - lv_imgbtn_set_style(buttonEepromSet, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonEepromSet, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_S_RETURN, "bmp_return.bin", 0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, &bmp_pic); + #if ENABLED(USE_WIFI_FUNCTION) + lv_obj_set_event_cb_mks(buttonWifi, event_handler,ID_S_WIFI,NULL,0); + lv_imgbtn_set_src(buttonWifi, LV_BTN_STATE_REL, "F:/bmp_wifi.bin"); + lv_imgbtn_set_src(buttonWifi, LV_BTN_STATE_PR, "F:/bmp_wifi.bin"); + lv_imgbtn_set_style(buttonWifi, LV_BTN_STATE_PR, &tft_style_label_pre); + lv_imgbtn_set_style(buttonWifi, LV_BTN_STATE_REL, &tft_style_label_rel); + #endif + + lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_S_RETURN,NULL , 0); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_return.bin"); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_return.bin"); lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); + #endif // if 1 /*lv_obj_set_pos(buttonWifi,INTERVAL_V,titleHeight); @@ -243,45 +285,56 @@ void lv_draw_set(void) { lv_obj_set_pos(buttonBack,BTN_X_PIXEL*3+INTERVAL_V*4, BTN_Y_PIXEL+INTERVAL_H+titleHeight);*/ //lv_obj_set_pos(buttonWifi,INTERVAL_V,titleHeight); + lv_obj_set_pos(buttonEepromSet, INTERVAL_V, titleHeight); lv_obj_set_pos(buttonFan, BTN_X_PIXEL + INTERVAL_V * 2, titleHeight); lv_obj_set_pos(buttonAbout, BTN_X_PIXEL * 2 + INTERVAL_V * 3, titleHeight); //lv_obj_set_pos(buttonContinue,BTN_X_PIXEL*3+INTERVAL_V*4,titleHeight); lv_obj_set_pos(buMotorOff, BTN_X_PIXEL * 3 + INTERVAL_V * 4, titleHeight); + + lv_obj_set_pos(buttonMachinePara, INTERVAL_V, BTN_Y_PIXEL + INTERVAL_H + titleHeight); #if HAS_LANG_SELECT_SCREEN - lv_obj_set_pos(buttonLanguage, INTERVAL_V, titleHeight); + lv_obj_set_pos(buttonLanguage, BTN_X_PIXEL + INTERVAL_V * 2, BTN_Y_PIXEL + INTERVAL_H + titleHeight); + #endif + #if ENABLED(USE_WIFI_FUNCTION) + lv_obj_set_pos(buttonWifi,BTN_X_PIXEL*2+INTERVAL_V*3,BTN_Y_PIXEL+INTERVAL_H+titleHeight); #endif - lv_obj_set_pos(buttonMachinePara, INTERVAL_V, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - lv_obj_set_pos(buttonEepromSet, BTN_X_PIXEL + INTERVAL_V * 2, BTN_Y_PIXEL + INTERVAL_H + titleHeight); lv_obj_set_pos(buttonBack, BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - /*Create a label on the Image button*/ + /// Create labels on the buttons //lv_btn_set_layout(buttonWifi, LV_LAYOUT_OFF); + lv_btn_set_layout(buttonEepromSet, LV_LAYOUT_OFF); lv_btn_set_layout(buttonFan, LV_LAYOUT_OFF); lv_btn_set_layout(buttonAbout, LV_LAYOUT_OFF); //lv_btn_set_layout(buttonContinue, LV_LAYOUT_OFF); lv_btn_set_layout(buMotorOff, LV_LAYOUT_OFF); + lv_btn_set_layout(buttonMachinePara, LV_LAYOUT_OFF); #if HAS_LANG_SELECT_SCREEN lv_btn_set_layout(buttonLanguage, LV_LAYOUT_OFF); #endif - lv_btn_set_layout(buttonMachinePara, LV_LAYOUT_OFF); - lv_btn_set_layout(buttonEepromSet, LV_LAYOUT_OFF); + #if ENABLED(USE_WIFI_FUNCTION) + lv_btn_set_layout(buttonWifi, LV_LAYOUT_OFF); + #endif lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); - //lv_obj_t * labelWifi= lv_label_create(buttonWifi, NULL); - lv_obj_t * labelFan = lv_label_create(buttonFan, NULL); - lv_obj_t * label_About = lv_label_create(buttonAbout, NULL); - //lv_obj_t * label_Continue = lv_label_create(buttonContinue, NULL); - lv_obj_t * label_MotorOff = lv_label_create(buMotorOff, NULL); + //lv_obj_t *labelWifi= lv_label_create(buttonWifi, NULL); + lv_obj_t *label_EepromSet = lv_label_create(buttonEepromSet, NULL); + lv_obj_t *labelFan = lv_label_create(buttonFan, NULL); + lv_obj_t *label_About = lv_label_create(buttonAbout, NULL); + //lv_obj_t *label_Continue = lv_label_create(buttonContinue, NULL); + lv_obj_t *label_MotorOff = lv_label_create(buMotorOff, NULL); + lv_obj_t *label_MachinePara = lv_label_create(buttonMachinePara, NULL); #if HAS_LANG_SELECT_SCREEN - lv_obj_t * label_Language = lv_label_create(buttonLanguage, NULL); + lv_obj_t *label_Language = lv_label_create(buttonLanguage, NULL); #endif - lv_obj_t * label_MachinePara = lv_label_create(buttonMachinePara, NULL); - lv_obj_t * label_EepromSet = lv_label_create(buttonEepromSet, NULL); - lv_obj_t * label_Back = lv_label_create(buttonBack, NULL); + #if ENABLED(USE_WIFI_FUNCTION) + lv_obj_t *label_Wifi = lv_label_create(buttonWifi, NULL); + #endif + lv_obj_t *label_Back = lv_label_create(buttonBack, NULL); if (gCfgItems.multiple_language != 0) { - //lv_label_set_text(labelWifi, set_menu.wifi); - //lv_obj_align(labelWifi, buttonWifi, LV_ALIGN_IN_BOTTOM_MID,0, BUTTON_TEXT_Y_OFFSET); + + lv_label_set_text(label_EepromSet, set_menu.eepromSet); + lv_obj_align(label_EepromSet, buttonEepromSet, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); lv_label_set_text(labelFan, set_menu.fan); lv_obj_align(labelFan, buttonFan, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); @@ -291,28 +344,46 @@ void lv_draw_set(void) { //lv_label_set_text(label_Continue, set_menu.breakpoint); //lv_obj_align(label_Continue, buttonContinue, LV_ALIGN_IN_BOTTOM_MID,0, BUTTON_TEXT_Y_OFFSET); - #if HAS_SUICIDE - lv_label_set_text(label_MotorOff, set_menu.shutdown); - #else - lv_label_set_text(label_MotorOff, set_menu.motoroff); - #endif + lv_label_set_text(label_MotorOff, set_menu.TERN(HAS_SUICIDE, shutdown, motoroff)); lv_obj_align(label_MotorOff, buMotorOff, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + lv_label_set_text(label_MachinePara, set_menu.machine_para); + lv_obj_align(label_MachinePara, buttonMachinePara, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + #if HAS_LANG_SELECT_SCREEN lv_label_set_text(label_Language, set_menu.language); lv_obj_align(label_Language, buttonLanguage, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); #endif - lv_label_set_text(label_MachinePara, set_menu.machine_para); - lv_obj_align(label_MachinePara, buttonMachinePara, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - lv_label_set_text(label_EepromSet, set_menu.eepromSet); - lv_obj_align(label_EepromSet, buttonEepromSet, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + #if ENABLED(USE_WIFI_FUNCTION) + lv_label_set_text(label_Wifi, set_menu.wifi); + lv_obj_align(label_Wifi, buttonWifi, LV_ALIGN_IN_BOTTOM_MID,0, BUTTON_TEXT_Y_OFFSET); + #endif lv_label_set_text(label_Back, common_menu.text_back); lv_obj_align(label_Back, buttonBack, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); } + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonEepromSet); + lv_group_add_obj(g, buttonFan); + lv_group_add_obj(g, buttonAbout); + lv_group_add_obj(g, buMotorOff); + lv_group_add_obj(g, buttonMachinePara); + lv_group_add_obj(g, buttonLanguage); + #if ENABLED(USE_WIFI_FUNCTION) + lv_group_add_obj(g, buttonWifi); + #endif + lv_group_add_obj(g, buttonBack); + } + #endif } -void lv_clear_set() { lv_obj_del(scr); } +void lv_clear_set() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} #endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_set.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_set.h index 1cb60b5681..b243bca296 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_set.h +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_set.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus -extern "C" { /* C-declarations for C++ */ + extern "C" { /* C-declarations for C++ */ #endif extern void lv_draw_set(void); @@ -30,5 +30,5 @@ extern void lv_clear_set(); //extern void disp_temp_ready_print(); #ifdef __cplusplus -} /* C-declarations for C++ */ + } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_step_settings.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_step_settings.cpp index 434c2f8579..baad23f9ae 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_step_settings.cpp +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_step_settings.cpp @@ -29,6 +29,7 @@ #include "../../../../MarlinCore.h" #include "../../../../module/planner.h" +extern lv_group_t * g; static lv_obj_t * scr; #define ID_STEP_RETURN 1 @@ -127,11 +128,11 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { void lv_draw_step_settings(void) { lv_obj_t *buttonBack = NULL, *label_Back = NULL, *buttonTurnPage = NULL, *labelTurnPage = NULL; - lv_obj_t *buttonXText = NULL, *labelXText = NULL, *buttonXValue = NULL, *labelXValue = NULL; - lv_obj_t *buttonYText = NULL, *labelYText = NULL, *buttonYValue = NULL, *labelYValue = NULL; - lv_obj_t *buttonZText = NULL, *labelZText = NULL, *buttonZValue = NULL, *labelZValue = NULL; - lv_obj_t *buttonE0Text = NULL, *labelE0Text = NULL, *buttonE0Value = NULL, *labelE0Value = NULL; - lv_obj_t *buttonE1Text = NULL, *labelE1Text = NULL, *buttonE1Value = NULL, *labelE1Value = NULL; + lv_obj_t *labelXText = NULL, *buttonXValue = NULL, *labelXValue = NULL; + lv_obj_t *labelYText = NULL, *buttonYValue = NULL, *labelYValue = NULL; + lv_obj_t *labelZText = NULL, *buttonZValue = NULL, *labelZValue = NULL; + lv_obj_t *labelE0Text = NULL, *buttonE0Value = NULL, *labelE0Value = NULL; + lv_obj_t *labelE1Text = NULL, *buttonE1Value = NULL, *labelE1Value = NULL; lv_obj_t * line1 = NULL, * line2 = NULL, * line3 = NULL, * line4 = NULL; if (disp_state_stack._disp_state[disp_state_stack._disp_index] != STEPS_UI) { disp_state_stack._disp_index++; @@ -152,166 +153,133 @@ void lv_draw_step_settings(void) { lv_refr_now(lv_refr_get_disp_refreshing()); - LV_IMG_DECLARE(bmp_para_back); - // LV_IMG_DECLARE(bmp_para_arrow); - LV_IMG_DECLARE(bmp_para_bank); - if (uiCfg.para_ui_page != 1) { - buttonXText = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonXText, PARA_UI_POS_X, PARA_UI_POS_Y); /*Set its position*/ - lv_obj_set_size(buttonXText, PARA_UI_VALUE_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - lv_obj_set_event_cb(buttonXText, event_handler); - lv_btn_set_style(buttonXText, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonXText, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonXText, LV_LAYOUT_OFF); - labelXText = lv_label_create(buttonXText, NULL); /*Add a label to the button*/ - - buttonXValue = lv_imgbtn_create(scr, NULL); + labelXText = lv_label_create(scr, NULL); + lv_obj_set_style(labelXText, &tft_style_label_rel); + lv_obj_set_pos(labelXText, PARA_UI_POS_X, PARA_UI_POS_Y + 10); + lv_label_set_text(labelXText, machine_menu.X_Steps); + + buttonXValue = lv_btn_create(scr, NULL); lv_obj_set_pos(buttonXValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y + PARA_UI_VALUE_V); - lv_obj_set_event_cb_mks(buttonXValue, event_handler, ID_STEP_X, "bmp_value_blank.bin", 0); - lv_imgbtn_set_src(buttonXValue, LV_BTN_STATE_REL, &bmp_para_bank); - lv_imgbtn_set_src(buttonXValue, LV_BTN_STATE_PR, &bmp_para_bank); - lv_imgbtn_set_style(buttonXValue, LV_BTN_STATE_PR, &style_para_value_pre); - lv_imgbtn_set_style(buttonXValue, LV_BTN_STATE_REL, &style_para_value_rel); - lv_btn_set_layout(buttonXValue, LV_LAYOUT_OFF); + lv_obj_set_size(buttonXValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonXValue, event_handler, ID_STEP_X, NULL, 0); + lv_btn_set_style(buttonXValue, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonXValue, LV_BTN_STYLE_PR, &style_para_value); labelXValue = lv_label_create(buttonXValue, NULL); line1 = lv_line_create(scr, NULL); lv_ex_line(line1, line_points[0]); - buttonYText = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonYText, PARA_UI_POS_X, PARA_UI_POS_Y * 2); /*Set its position*/ - lv_obj_set_size(buttonYText, PARA_UI_VALUE_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - lv_obj_set_event_cb(buttonYText, event_handler); - lv_btn_set_style(buttonYText, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonYText, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonYText, LV_LAYOUT_OFF); - labelYText = lv_label_create(buttonYText, NULL); /*Add a label to the button*/ + labelYText = lv_label_create(scr, NULL); + lv_obj_set_style(labelYText, &tft_style_label_rel); + lv_obj_set_pos(labelYText, PARA_UI_POS_X, PARA_UI_POS_Y * 2 + 10); + lv_label_set_text(labelYText, machine_menu.Y_Steps); - buttonYValue = lv_imgbtn_create(scr, NULL); + buttonYValue = lv_btn_create(scr, NULL); lv_obj_set_pos(buttonYValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 2 + PARA_UI_VALUE_V); - lv_obj_set_event_cb_mks(buttonYValue, event_handler, ID_STEP_Y, "bmp_value_blank.bin", 0); - lv_imgbtn_set_src(buttonYValue, LV_BTN_STATE_REL, &bmp_para_bank); - lv_imgbtn_set_src(buttonYValue, LV_BTN_STATE_PR, &bmp_para_bank); - lv_imgbtn_set_style(buttonYValue, LV_BTN_STATE_PR, &style_para_value_pre); - lv_imgbtn_set_style(buttonYValue, LV_BTN_STATE_REL, &style_para_value_rel); - lv_btn_set_layout(buttonYValue, LV_LAYOUT_OFF); + lv_obj_set_size(buttonYValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonYValue, event_handler, ID_STEP_Y, NULL, 0); + lv_btn_set_style(buttonYValue, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonYValue, LV_BTN_STYLE_PR, &style_para_value); labelYValue = lv_label_create(buttonYValue, NULL); line2 = lv_line_create(scr, NULL); lv_ex_line(line2, line_points[1]); - buttonZText = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonZText, PARA_UI_POS_X, PARA_UI_POS_Y * 3); /*Set its position*/ - lv_obj_set_size(buttonZText, PARA_UI_VALUE_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - lv_obj_set_event_cb(buttonZText, event_handler); - lv_btn_set_style(buttonZText, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonZText, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonZText, LV_LAYOUT_OFF); - labelZText = lv_label_create(buttonZText, NULL); /*Add a label to the button*/ + labelZText = lv_label_create(scr, NULL); + lv_obj_set_style(labelZText, &tft_style_label_rel); + lv_obj_set_pos(labelZText, PARA_UI_POS_X, PARA_UI_POS_Y * 3 + 10); + lv_label_set_text(labelZText, machine_menu.Z_Steps); - buttonZValue = lv_imgbtn_create(scr, NULL); + buttonZValue = lv_btn_create(scr, NULL); lv_obj_set_pos(buttonZValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 3 + PARA_UI_VALUE_V); - lv_obj_set_event_cb_mks(buttonZValue, event_handler, ID_STEP_Z, "bmp_value_blank.bin", 0); - lv_imgbtn_set_src(buttonZValue, LV_BTN_STATE_REL, &bmp_para_bank); - lv_imgbtn_set_src(buttonZValue, LV_BTN_STATE_PR, &bmp_para_bank); - lv_imgbtn_set_style(buttonZValue, LV_BTN_STATE_PR, &style_para_value_pre); - lv_imgbtn_set_style(buttonZValue, LV_BTN_STATE_REL, &style_para_value_rel); - lv_btn_set_layout(buttonZValue, LV_LAYOUT_OFF); + lv_obj_set_size(buttonZValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonZValue, event_handler, ID_STEP_Z, NULL, 0); + lv_btn_set_style(buttonZValue, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonZValue, LV_BTN_STYLE_PR, &style_para_value); labelZValue = lv_label_create(buttonZValue, NULL); line3 = lv_line_create(scr, NULL); lv_ex_line(line3, line_points[2]); - buttonE0Text = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonE0Text, PARA_UI_POS_X, PARA_UI_POS_Y * 4); /*Set its position*/ - lv_obj_set_size(buttonE0Text, PARA_UI_VALUE_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - lv_obj_set_event_cb(buttonE0Text, event_handler); - lv_btn_set_style(buttonE0Text, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonE0Text, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonE0Text, LV_LAYOUT_OFF); - labelE0Text = lv_label_create(buttonE0Text, NULL); /*Add a label to the button*/ + labelE0Text = lv_label_create(scr, NULL); + lv_obj_set_style(labelE0Text, &tft_style_label_rel); + lv_obj_set_pos(labelE0Text, PARA_UI_POS_X, PARA_UI_POS_Y * 4 + 10); + lv_label_set_text(labelE0Text, machine_menu.E0_Steps); - buttonE0Value = lv_imgbtn_create(scr, NULL); + buttonE0Value = lv_btn_create(scr, NULL); lv_obj_set_pos(buttonE0Value, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 4 + PARA_UI_VALUE_V); - lv_obj_set_event_cb_mks(buttonE0Value, event_handler, ID_STEP_E0, "bmp_value_blank.bin", 0); - lv_imgbtn_set_src(buttonE0Value, LV_BTN_STATE_REL, &bmp_para_bank); - lv_imgbtn_set_src(buttonE0Value, LV_BTN_STATE_PR, &bmp_para_bank); - lv_imgbtn_set_style(buttonE0Value, LV_BTN_STATE_PR, &style_para_value_pre); - lv_imgbtn_set_style(buttonE0Value, LV_BTN_STATE_REL, &style_para_value_rel); - lv_btn_set_layout(buttonE0Value, LV_LAYOUT_OFF); + lv_obj_set_size(buttonE0Value, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonE0Value, event_handler, ID_STEP_E0, NULL, 0); + lv_btn_set_style(buttonE0Value, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonE0Value, LV_BTN_STYLE_PR, &style_para_value); labelE0Value = lv_label_create(buttonE0Value, NULL); line4 = lv_line_create(scr, NULL); lv_ex_line(line4, line_points[3]); - buttonTurnPage = lv_imgbtn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonTurnPage, event_handler, ID_STEP_DOWN, "bmp_back70x40.bin", 0); - lv_imgbtn_set_src(buttonTurnPage, LV_BTN_STATE_REL, &bmp_para_back); - lv_imgbtn_set_src(buttonTurnPage, LV_BTN_STATE_PR, &bmp_para_back); - lv_imgbtn_set_style(buttonTurnPage, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonTurnPage, LV_BTN_STATE_REL, &tft_style_label_rel); + buttonTurnPage = lv_btn_create(scr, NULL); + lv_obj_set_event_cb_mks(buttonTurnPage, event_handler, ID_STEP_DOWN, NULL, 0); + lv_btn_set_style(buttonTurnPage, LV_BTN_STYLE_REL, &style_para_back); + lv_btn_set_style(buttonTurnPage, LV_BTN_STYLE_PR, &style_para_back); + + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonXValue); + lv_group_add_obj(g, buttonYValue); + lv_group_add_obj(g, buttonZValue); + lv_group_add_obj(g, buttonE0Value); + lv_group_add_obj(g, buttonTurnPage); + } + #endif } else { - buttonE1Text = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonE1Text, PARA_UI_POS_X, PARA_UI_POS_Y); /*Set its position*/ - lv_obj_set_size(buttonE1Text, PARA_UI_VALUE_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - lv_obj_set_event_cb(buttonE1Text, event_handler); - lv_btn_set_style(buttonE1Text, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonE1Text, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonE1Text, LV_LAYOUT_OFF); - labelE1Text = lv_label_create(buttonE1Text, NULL); /*Add a label to the button*/ - - buttonE1Value = lv_imgbtn_create(scr, NULL); + labelE1Text = lv_label_create(scr, NULL); + lv_obj_set_style(labelE1Text, &tft_style_label_rel); + lv_obj_set_pos(labelE1Text, PARA_UI_POS_X, PARA_UI_POS_Y + 10); + lv_label_set_text(labelE1Text, machine_menu.E1_Steps); + + buttonE1Value = lv_btn_create(scr, NULL); lv_obj_set_pos(buttonE1Value, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y + PARA_UI_VALUE_V); - lv_obj_set_event_cb_mks(buttonE1Value, event_handler, ID_STEP_E1, "bmp_value_blank.bin", 0); - lv_imgbtn_set_src(buttonE1Value, LV_BTN_STATE_REL, &bmp_para_bank); - lv_imgbtn_set_src(buttonE1Value, LV_BTN_STATE_PR, &bmp_para_bank); - lv_imgbtn_set_style(buttonE1Value, LV_BTN_STATE_PR, &style_para_value_pre); - lv_imgbtn_set_style(buttonE1Value, LV_BTN_STATE_REL, &style_para_value_rel); - lv_btn_set_layout(buttonE1Value, LV_LAYOUT_OFF); + lv_obj_set_size(buttonE1Value, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonE1Value, event_handler, ID_STEP_E1, NULL, 0); + lv_btn_set_style(buttonE1Value, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonE1Value, LV_BTN_STYLE_PR, &style_para_value); labelE1Value = lv_label_create(buttonE1Value, NULL); line1 = lv_line_create(scr, NULL); lv_ex_line(line1, line_points[0]); - buttonTurnPage = lv_imgbtn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonTurnPage, event_handler, ID_STEP_UP, "bmp_back70x40.bin", 0); - lv_imgbtn_set_src(buttonTurnPage, LV_BTN_STATE_REL, &bmp_para_back); - lv_imgbtn_set_src(buttonTurnPage, LV_BTN_STATE_PR, &bmp_para_back); - lv_imgbtn_set_style(buttonTurnPage, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonTurnPage, LV_BTN_STATE_REL, &tft_style_label_rel); + buttonTurnPage = lv_btn_create(scr, NULL); + lv_obj_set_event_cb_mks(buttonTurnPage, event_handler, ID_STEP_UP, NULL, 0); + lv_btn_set_style(buttonTurnPage, LV_BTN_STYLE_REL, &style_para_back); + lv_btn_set_style(buttonTurnPage, LV_BTN_STYLE_PR, &style_para_back); + + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonE1Value); + lv_group_add_obj(g, buttonTurnPage); + } + #endif } lv_obj_set_pos(buttonTurnPage, PARA_UI_TURN_PAGE_POS_X, PARA_UI_TURN_PAGE_POS_Y); - lv_btn_set_layout(buttonTurnPage, LV_LAYOUT_OFF); + lv_obj_set_size(buttonTurnPage, PARA_UI_BACK_BTN_X_SIZE, PARA_UI_BACK_BTN_Y_SIZE); labelTurnPage = lv_label_create(buttonTurnPage, NULL); - buttonBack = lv_imgbtn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_STEP_RETURN, "bmp_back70x40.bin", 0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, &bmp_para_back); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, &bmp_para_back); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); - + buttonBack = lv_btn_create(scr, NULL); + lv_btn_set_style(buttonBack, LV_BTN_STYLE_REL, &style_para_back); + lv_btn_set_style(buttonBack, LV_BTN_STYLE_PR, &style_para_back); lv_obj_set_pos(buttonBack, PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y); - lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); + lv_obj_set_size(buttonBack, PARA_UI_BACK_BTN_X_SIZE, PARA_UI_BACK_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_STEP_RETURN, NULL, 0); label_Back = lv_label_create(buttonBack, NULL); + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonBack); + #endif if (gCfgItems.multiple_language != 0) { if (uiCfg.para_ui_page != 1) { - lv_label_set_text(labelXText, machine_menu.X_Steps); - lv_obj_align(labelXText, buttonXText, LV_ALIGN_IN_LEFT_MID, 0, 0); - - lv_label_set_text(labelYText, machine_menu.Y_Steps); - lv_obj_align(labelYText, buttonYText, LV_ALIGN_IN_LEFT_MID, 0, 0); - - lv_label_set_text(labelZText, machine_menu.Z_Steps); - lv_obj_align(labelZText, buttonZText, LV_ALIGN_IN_LEFT_MID, 0, 0); - - lv_label_set_text(labelE0Text, machine_menu.E0_Steps); - lv_obj_align(labelE0Text, buttonE0Text, LV_ALIGN_IN_LEFT_MID, 0, 0); - lv_label_set_text(labelTurnPage, machine_menu.next); lv_obj_align(labelTurnPage, buttonTurnPage, LV_ALIGN_CENTER, 0, 0); @@ -336,9 +304,6 @@ void lv_draw_step_settings(void) { lv_obj_align(labelE0Value, buttonE0Value, LV_ALIGN_CENTER, 0, 0); } else { - lv_label_set_text(labelE1Text, machine_menu.E1_Steps); - lv_obj_align(labelE1Text, buttonE1Text, LV_ALIGN_IN_LEFT_MID, 0, 0); - lv_label_set_text(labelTurnPage, machine_menu.previous); lv_obj_align(labelTurnPage, buttonTurnPage, LV_ALIGN_CENTER, 0, 0); @@ -353,6 +318,11 @@ void lv_draw_step_settings(void) { } } -void lv_clear_step_settings() { lv_obj_del(scr); } +void lv_clear_step_settings() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} #endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_step_settings.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_step_settings.h index 1a5efda408..b7eaeb4c61 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_step_settings.h +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_step_settings.h @@ -22,12 +22,12 @@ #pragma once #ifdef __cplusplus -extern "C" { /* C-declarations for C++ */ + extern "C" { /* C-declarations for C++ */ #endif extern void lv_draw_step_settings(void); extern void lv_clear_step_settings(); #ifdef __cplusplus -} /* C-declarations for C++ */ + } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_tmc_current_settings.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_tmc_current_settings.cpp index f1559e0f55..10aa7badff 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_tmc_current_settings.cpp +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_tmc_current_settings.cpp @@ -25,11 +25,13 @@ #include "lv_conf.h" #include "draw_ui.h" + #include "../../../../MarlinCore.h" #include "../../../../module/planner.h" #include "../../../../module/stepper/indirection.h" #include "../../../../feature/tmc_util.h" +extern lv_group_t * g; static lv_obj_t * scr; #define ID_TMC_CURRENT_RETURN 1 @@ -53,94 +55,105 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { draw_return_ui(); } break; - case ID_TMC_CURRENT_X: + #if AXIS_IS_TMC(X) + case ID_TMC_CURRENT_X: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + value = Xcurrent; + lv_clear_tmc_current_settings(); + lv_draw_number_key(); + } + break; + #endif + + #if AXIS_IS_TMC(Y) + case ID_TMC_CURRENT_Y: if (event == LV_EVENT_CLICKED) { } else if (event == LV_EVENT_RELEASED) { - value = Xcurrent; + value = Ycurrent; lv_clear_tmc_current_settings(); lv_draw_number_key(); } break; - case ID_TMC_CURRENT_Y: + #endif + + #if AXIS_IS_TMC(Z) + case ID_TMC_CURRENT_Z: if (event == LV_EVENT_CLICKED) { } else if (event == LV_EVENT_RELEASED) { - value = Ycurrent; + value = Zcurrent; lv_clear_tmc_current_settings(); lv_draw_number_key(); } break; - case ID_TMC_CURRENT_Z: + #endif + + #if AXIS_IS_TMC(E0) + case ID_TMC_CURRENT_E0: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + value = E0current; + lv_clear_tmc_current_settings(); + lv_draw_number_key(); + } + break; + #endif + + #if AXIS_IS_TMC(E1) + case ID_TMC_CURRENT_E1: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + value = E1current; + lv_clear_tmc_current_settings(); + lv_draw_number_key(); + } + break; + #endif + case ID_TMC_CURRENT_UP: if (event == LV_EVENT_CLICKED) { } else if (event == LV_EVENT_RELEASED) { - value = Zcurrent; + uiCfg.para_ui_page = 0; lv_clear_tmc_current_settings(); - lv_draw_number_key(); + lv_draw_tmc_current_settings(); } break; - case ID_TMC_CURRENT_E0: + case ID_TMC_CURRENT_DOWN: if (event == LV_EVENT_CLICKED) { } else if (event == LV_EVENT_RELEASED) { - value = E0current; + uiCfg.para_ui_page = 1; lv_clear_tmc_current_settings(); - lv_draw_number_key(); + lv_draw_tmc_current_settings(); } break; - #if AXIS_IS_TMC(E1) - case ID_TMC_CURRENT_E1: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - value = E1current; - lv_clear_tmc_current_settings(); - lv_draw_number_key(); - } - break; - - case ID_TMC_CURRENT_UP: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - uiCfg.para_ui_page = 0; - lv_clear_tmc_current_settings(); - lv_draw_tmc_current_settings(); - } - break; - case ID_TMC_CURRENT_DOWN: - if (event == LV_EVENT_CLICKED) { - - } - else if (event == LV_EVENT_RELEASED) { - uiCfg.para_ui_page = 1; - lv_clear_tmc_current_settings(); - lv_draw_tmc_current_settings(); - } - break; - #endif } } void lv_draw_tmc_current_settings(void) { lv_obj_t *buttonBack = NULL, *label_Back = NULL; - lv_obj_t *buttonXText = NULL, *labelXText = NULL, *buttonXValue = NULL, *labelXValue = NULL; - lv_obj_t *buttonYText = NULL, *labelYText = NULL, *buttonYValue = NULL, *labelYValue = NULL; - lv_obj_t *buttonZText = NULL, *labelZText = NULL, *buttonZValue = NULL, *labelZValue = NULL; - lv_obj_t *buttonE0Text = NULL, *labelE0Text = NULL, *buttonE0Value = NULL, *labelE0Value = NULL; + lv_obj_t *labelXText = NULL, *buttonXValue = NULL, *labelXValue = NULL; + lv_obj_t *labelYText = NULL, *buttonYValue = NULL, *labelYValue = NULL; + lv_obj_t *labelZText = NULL, *buttonZValue = NULL, *labelZValue = NULL; + lv_obj_t *labelE0Text = NULL, *buttonE0Value = NULL, *labelE0Value = NULL; lv_obj_t * line1 = NULL, * line2 = NULL, * line3 = NULL, * line4 = NULL; - #if AXIS_IS_TMC(E1) + //#if AXIS_IS_TMC(E1) lv_obj_t *buttonTurnPage = NULL, *labelTurnPage = NULL; - lv_obj_t *buttonE1Text = NULL, *labelE1Text = NULL, *buttonE1Value = NULL, *labelE1Value = NULL; - #endif + lv_obj_t *labelE1Text = NULL, *buttonE1Value = NULL, *labelE1Value = NULL; + //#endif float milliamps; if (disp_state_stack._disp_state[disp_state_stack._disp_index] != TMC_CURRENT_UI) { @@ -162,217 +175,201 @@ void lv_draw_tmc_current_settings(void) { lv_refr_now(lv_refr_get_disp_refreshing()); - LV_IMG_DECLARE(bmp_para_back); - // LV_IMG_DECLARE(bmp_para_arrow); - LV_IMG_DECLARE(bmp_para_bank); - if (uiCfg.para_ui_page != 1) { - buttonXText = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonXText, PARA_UI_POS_X, PARA_UI_POS_Y); /*Set its position*/ - lv_obj_set_size(buttonXText, PARA_UI_VALUE_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - lv_obj_set_event_cb(buttonXText, event_handler); - lv_btn_set_style(buttonXText, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonXText, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonXText, LV_LAYOUT_OFF); - labelXText = lv_label_create(buttonXText, NULL); /*Add a label to the button*/ - - buttonXValue = lv_imgbtn_create(scr, NULL); + labelXText = lv_label_create(scr, NULL); + lv_obj_set_style(labelXText, &tft_style_label_rel); + lv_obj_set_pos(labelXText, PARA_UI_POS_X, PARA_UI_POS_Y + 10); + lv_label_set_text(labelXText, machine_menu.X_Current); + + buttonXValue = lv_btn_create(scr, NULL); lv_obj_set_pos(buttonXValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y + PARA_UI_VALUE_V); - lv_obj_set_event_cb_mks(buttonXValue, event_handler, ID_TMC_CURRENT_X, "bmp_value_blank.bin", 0); - lv_imgbtn_set_src(buttonXValue, LV_BTN_STATE_REL, &bmp_para_bank); - lv_imgbtn_set_src(buttonXValue, LV_BTN_STATE_PR, &bmp_para_bank); - lv_imgbtn_set_style(buttonXValue, LV_BTN_STATE_PR, &style_para_value_pre); - lv_imgbtn_set_style(buttonXValue, LV_BTN_STATE_REL, &style_para_value_rel); - lv_btn_set_layout(buttonXValue, LV_LAYOUT_OFF); + lv_obj_set_size(buttonXValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonXValue, event_handler, ID_TMC_CURRENT_X, NULL, 0); + lv_btn_set_style(buttonXValue, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonXValue, LV_BTN_STYLE_PR, &style_para_value); labelXValue = lv_label_create(buttonXValue, NULL); line1 = lv_line_create(scr, NULL); lv_ex_line(line1, line_points[0]); - buttonYText = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonYText, PARA_UI_POS_X, PARA_UI_POS_Y * 2); /*Set its position*/ - lv_obj_set_size(buttonYText, PARA_UI_VALUE_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - lv_obj_set_event_cb(buttonYText, event_handler); - lv_btn_set_style(buttonYText, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonYText, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonYText, LV_LAYOUT_OFF); - labelYText = lv_label_create(buttonYText, NULL); /*Add a label to the button*/ + labelYText = lv_label_create(scr, NULL); + lv_obj_set_style(labelYText, &tft_style_label_rel); + lv_obj_set_pos(labelYText, PARA_UI_POS_X, PARA_UI_POS_Y * 2 + 10); + lv_label_set_text(labelYText, machine_menu.Y_Current); - buttonYValue = lv_imgbtn_create(scr, NULL); + buttonYValue = lv_btn_create(scr, NULL); lv_obj_set_pos(buttonYValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 2 + PARA_UI_VALUE_V); - lv_obj_set_event_cb_mks(buttonYValue, event_handler, ID_TMC_CURRENT_Y, "bmp_value_blank.bin", 0); - lv_imgbtn_set_src(buttonYValue, LV_BTN_STATE_REL, &bmp_para_bank); - lv_imgbtn_set_src(buttonYValue, LV_BTN_STATE_PR, &bmp_para_bank); - lv_imgbtn_set_style(buttonYValue, LV_BTN_STATE_PR, &style_para_value_pre); - lv_imgbtn_set_style(buttonYValue, LV_BTN_STATE_REL, &style_para_value_rel); - lv_btn_set_layout(buttonYValue, LV_LAYOUT_OFF); + lv_obj_set_size(buttonYValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonYValue, event_handler, ID_TMC_CURRENT_Y, NULL, 0); + lv_btn_set_style(buttonYValue, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonYValue, LV_BTN_STYLE_PR, &style_para_value); labelYValue = lv_label_create(buttonYValue, NULL); line2 = lv_line_create(scr, NULL); lv_ex_line(line2, line_points[1]); - buttonZText = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonZText, PARA_UI_POS_X, PARA_UI_POS_Y * 3); /*Set its position*/ - lv_obj_set_size(buttonZText, PARA_UI_VALUE_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - lv_obj_set_event_cb(buttonZText, event_handler); - lv_btn_set_style(buttonZText, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonZText, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonZText, LV_LAYOUT_OFF); - labelZText = lv_label_create(buttonZText, NULL); /*Add a label to the button*/ + labelZText = lv_label_create(scr, NULL); + lv_obj_set_style(labelZText, &tft_style_label_rel); + lv_obj_set_pos(labelZText, PARA_UI_POS_X, PARA_UI_POS_Y * 3 + 10); + lv_label_set_text(labelZText, machine_menu.Z_Current); - buttonZValue = lv_imgbtn_create(scr, NULL); + buttonZValue = lv_btn_create(scr, NULL); lv_obj_set_pos(buttonZValue, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 3 + PARA_UI_VALUE_V); - lv_obj_set_event_cb_mks(buttonZValue, event_handler, ID_TMC_CURRENT_Z, "bmp_value_blank.bin", 0); - lv_imgbtn_set_src(buttonZValue, LV_BTN_STATE_REL, &bmp_para_bank); - lv_imgbtn_set_src(buttonZValue, LV_BTN_STATE_PR, &bmp_para_bank); - lv_imgbtn_set_style(buttonZValue, LV_BTN_STATE_PR, &style_para_value_pre); - lv_imgbtn_set_style(buttonZValue, LV_BTN_STATE_REL, &style_para_value_rel); - lv_btn_set_layout(buttonZValue, LV_LAYOUT_OFF); + lv_obj_set_size(buttonZValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonZValue, event_handler, ID_TMC_CURRENT_Z, NULL, 0); + lv_btn_set_style(buttonZValue, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonZValue, LV_BTN_STYLE_PR, &style_para_value); labelZValue = lv_label_create(buttonZValue, NULL); line3 = lv_line_create(scr, NULL); lv_ex_line(line3, line_points[2]); - buttonE0Text = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonE0Text, PARA_UI_POS_X, PARA_UI_POS_Y * 4); /*Set its position*/ - lv_obj_set_size(buttonE0Text, PARA_UI_VALUE_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - lv_obj_set_event_cb(buttonE0Text, event_handler); - lv_btn_set_style(buttonE0Text, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonE0Text, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonE0Text, LV_LAYOUT_OFF); - labelE0Text = lv_label_create(buttonE0Text, NULL); /*Add a label to the button*/ + labelE0Text = lv_label_create(scr, NULL); + lv_obj_set_style(labelE0Text, &tft_style_label_rel); + lv_obj_set_pos(labelE0Text, PARA_UI_POS_X, PARA_UI_POS_Y * 4 + 10); + lv_label_set_text(labelE0Text, machine_menu.E0_Current); - buttonE0Value = lv_imgbtn_create(scr, NULL); + buttonE0Value = lv_btn_create(scr, NULL); lv_obj_set_pos(buttonE0Value, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y * 4 + PARA_UI_VALUE_V); - lv_obj_set_event_cb_mks(buttonE0Value, event_handler, ID_TMC_CURRENT_E0, "bmp_value_blank.bin", 0); - lv_imgbtn_set_src(buttonE0Value, LV_BTN_STATE_REL, &bmp_para_bank); - lv_imgbtn_set_src(buttonE0Value, LV_BTN_STATE_PR, &bmp_para_bank); - lv_imgbtn_set_style(buttonE0Value, LV_BTN_STATE_PR, &style_para_value_pre); - lv_imgbtn_set_style(buttonE0Value, LV_BTN_STATE_REL, &style_para_value_rel); - lv_btn_set_layout(buttonE0Value, LV_LAYOUT_OFF); + lv_obj_set_size(buttonE0Value, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonE0Value, event_handler, ID_TMC_CURRENT_E0, NULL, 0); + lv_btn_set_style(buttonE0Value, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonE0Value, LV_BTN_STYLE_PR, &style_para_value); labelE0Value = lv_label_create(buttonE0Value, NULL); + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonXValue); + lv_group_add_obj(g, buttonYValue); + lv_group_add_obj(g, buttonZValue); + lv_group_add_obj(g, buttonE0Value); + } + #endif + line4 = lv_line_create(scr, NULL); lv_ex_line(line4, line_points[3]); - #if AXIS_IS_TMC(E1) - buttonTurnPage = lv_imgbtn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonTurnPage, event_handler, ID_TMC_CURRENT_DOWN, "bmp_back70x40.bin", 0); - lv_imgbtn_set_src(buttonTurnPage, LV_BTN_STATE_REL, &bmp_para_back); - lv_imgbtn_set_src(buttonTurnPage, LV_BTN_STATE_PR, &bmp_para_back); - lv_imgbtn_set_style(buttonTurnPage, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonTurnPage, LV_BTN_STATE_REL, &tft_style_label_rel); - #endif + //#if AXIS_IS_TMC(E1) + buttonTurnPage = lv_btn_create(scr, NULL); + lv_obj_set_event_cb_mks(buttonTurnPage, event_handler, ID_TMC_CURRENT_DOWN, NULL, 0); + lv_btn_set_style(buttonTurnPage, LV_BTN_STYLE_REL, &style_para_back); + lv_btn_set_style(buttonTurnPage, LV_BTN_STYLE_PR, &style_para_back); + + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonTurnPage); + #endif + //#endif } else { - #if AXIS_IS_TMC(E1) - buttonE1Text = lv_btn_create(scr, NULL); /*Add a button the current screen*/ - lv_obj_set_pos(buttonE1Text, PARA_UI_POS_X, PARA_UI_POS_Y); /*Set its position*/ - lv_obj_set_size(buttonE1Text, PARA_UI_VALUE_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ - lv_obj_set_event_cb(buttonE1Text, event_handler); - lv_btn_set_style(buttonE1Text, LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ - lv_btn_set_style(buttonE1Text, LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ - lv_btn_set_layout(buttonE1Text, LV_LAYOUT_OFF); - labelE1Text = lv_label_create(buttonE1Text, NULL); /*Add a label to the button*/ - - buttonE1Value = lv_imgbtn_create(scr, NULL); + //#if AXIS_IS_TMC(E1) + labelE1Text = lv_label_create(scr, NULL); + lv_obj_set_style(labelE1Text, &tft_style_label_rel); + lv_obj_set_pos(labelE1Text, PARA_UI_POS_X, PARA_UI_POS_Y + 10); + lv_label_set_text(labelE1Text, machine_menu.E1_Current); + + buttonE1Value = lv_btn_create(scr, NULL); lv_obj_set_pos(buttonE1Value, PARA_UI_VALUE_POS_X, PARA_UI_POS_Y + PARA_UI_VALUE_V); - lv_obj_set_event_cb_mks(buttonE1Value, event_handler, ID_TMC_CURRENT_E1, "bmp_value_blank.bin", 0); - lv_imgbtn_set_src(buttonE1Value, LV_BTN_STATE_REL, &bmp_para_bank); - lv_imgbtn_set_src(buttonE1Value, LV_BTN_STATE_PR, &bmp_para_bank); - lv_imgbtn_set_style(buttonE1Value, LV_BTN_STATE_PR, &style_para_value_pre); - lv_imgbtn_set_style(buttonE1Value, LV_BTN_STATE_REL, &style_para_value_rel); - lv_btn_set_layout(buttonE1Value, LV_LAYOUT_OFF); + lv_obj_set_size(buttonE1Value, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonE1Value, event_handler, ID_TMC_CURRENT_E1, NULL, 0); + lv_btn_set_style(buttonE1Value, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonE1Value, LV_BTN_STYLE_PR, &style_para_value); labelE1Value = lv_label_create(buttonE1Value, NULL); line1 = lv_line_create(scr, NULL); lv_ex_line(line1, line_points[0]); - buttonTurnPage = lv_imgbtn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonTurnPage, event_handler, ID_TMC_CURRENT_UP, "bmp_back70x40.bin", 0); - lv_imgbtn_set_src(buttonTurnPage, LV_BTN_STATE_REL, &bmp_para_back); - lv_imgbtn_set_src(buttonTurnPage, LV_BTN_STATE_PR, &bmp_para_back); - lv_imgbtn_set_style(buttonTurnPage, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonTurnPage, LV_BTN_STATE_REL, &tft_style_label_rel); - #endif + buttonTurnPage = lv_btn_create(scr, NULL); + lv_obj_set_event_cb_mks(buttonTurnPage, event_handler, ID_TMC_CURRENT_UP, NULL, 0); + lv_btn_set_style(buttonTurnPage, LV_BTN_STYLE_REL, &style_para_back); + lv_btn_set_style(buttonTurnPage, LV_BTN_STYLE_PR, &style_para_back); + + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonE1Value); + lv_group_add_obj(g, buttonTurnPage); + } + #endif + //#endif } - #if AXIS_IS_TMC(E1) + //#if AXIS_IS_TMC(E1) lv_obj_set_pos(buttonTurnPage, PARA_UI_TURN_PAGE_POS_X, PARA_UI_TURN_PAGE_POS_Y); - lv_btn_set_layout(buttonTurnPage, LV_LAYOUT_OFF); + lv_obj_set_size(buttonTurnPage, PARA_UI_BACK_BTN_X_SIZE, PARA_UI_BACK_BTN_Y_SIZE); labelTurnPage = lv_label_create(buttonTurnPage, NULL); - #endif + //#endif - buttonBack = lv_imgbtn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_TMC_CURRENT_RETURN, "bmp_back70x40.bin", 0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, &bmp_para_back); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, &bmp_para_back); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); + buttonBack = lv_btn_create(scr, NULL); + lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_TMC_CURRENT_RETURN, NULL, 0); + lv_btn_set_style(buttonBack, LV_BTN_STYLE_REL, &style_para_back); + lv_btn_set_style(buttonBack, LV_BTN_STYLE_PR, &style_para_back); + + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonBack); + #endif lv_obj_set_pos(buttonBack, PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y); - lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); + lv_obj_set_size(buttonBack, PARA_UI_BACK_BTN_X_SIZE, PARA_UI_BACK_BTN_Y_SIZE); label_Back = lv_label_create(buttonBack, NULL); if (gCfgItems.multiple_language != 0) { if (uiCfg.para_ui_page != 1) { - lv_label_set_text(labelXText, machine_menu.X_Current); - lv_obj_align(labelXText, buttonXText, LV_ALIGN_IN_LEFT_MID, 0, 0); - - lv_label_set_text(labelYText, machine_menu.Y_Current); - lv_obj_align(labelYText, buttonYText, LV_ALIGN_IN_LEFT_MID, 0, 0); - - lv_label_set_text(labelZText, machine_menu.Z_Current); - lv_obj_align(labelZText, buttonZText, LV_ALIGN_IN_LEFT_MID, 0, 0); - - lv_label_set_text(labelE0Text, machine_menu.E0_Current); - lv_obj_align(labelE0Text, buttonE0Text, LV_ALIGN_IN_LEFT_MID, 0, 0); - #if AXIS_IS_TMC(E1) + //#if AXIS_IS_TMC(E1) lv_label_set_text(labelTurnPage, machine_menu.next); lv_obj_align(labelTurnPage, buttonTurnPage, LV_ALIGN_CENTER, 0, 0); - #endif + //#endif #if AXIS_IS_TMC(X) milliamps = stepperX.getMilliamps(); - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%.1f"), milliamps); - lv_label_set_text(labelXValue, public_buf_l); - lv_obj_align(labelXValue, buttonXValue, LV_ALIGN_CENTER, 0, 0); + #else + milliamps = -1; #endif + ZERO(public_buf_l); + sprintf_P(public_buf_l, PSTR("%.1f"), milliamps); + lv_label_set_text(labelXValue, public_buf_l); + lv_obj_align(labelXValue, buttonXValue, LV_ALIGN_CENTER, 0, 0); + #if AXIS_IS_TMC(Y) milliamps = stepperY.getMilliamps(); - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%.1f"), milliamps); - lv_label_set_text(labelYValue, public_buf_l); - lv_obj_align(labelYValue, buttonYValue, LV_ALIGN_CENTER, 0, 0); + #else + milliamps = -1; #endif + ZERO(public_buf_l); + sprintf_P(public_buf_l, PSTR("%.1f"), milliamps); + lv_label_set_text(labelYValue, public_buf_l); + lv_obj_align(labelYValue, buttonYValue, LV_ALIGN_CENTER, 0, 0); + #if AXIS_IS_TMC(Z) milliamps = stepperZ.getMilliamps(); - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%.1f"), milliamps); - lv_label_set_text(labelZValue, public_buf_l); - lv_obj_align(labelZValue, buttonZValue, LV_ALIGN_CENTER, 0, 0); + #else + milliamps = -1; #endif + ZERO(public_buf_l); + sprintf_P(public_buf_l, PSTR("%.1f"), milliamps); + lv_label_set_text(labelZValue, public_buf_l); + lv_obj_align(labelZValue, buttonZValue, LV_ALIGN_CENTER, 0, 0); + #if AXIS_IS_TMC(E0) milliamps = stepperE0.getMilliamps(); - ZERO(public_buf_l); - sprintf_P(public_buf_l, PSTR("%.1f"), milliamps); - lv_label_set_text(labelE0Value, public_buf_l); - lv_obj_align(labelE0Value, buttonE0Value, LV_ALIGN_CENTER, 0, 0); + #else + milliamps = -1; #endif + ZERO(public_buf_l); + sprintf_P(public_buf_l, PSTR("%.1f"), milliamps); + lv_label_set_text(labelE0Value, public_buf_l); + lv_obj_align(labelE0Value, buttonE0Value, LV_ALIGN_CENTER, 0, 0); } else { - #if AXIS_IS_TMC(E1) - lv_label_set_text(labelE1Text, machine_menu.E1_Current); - lv_obj_align(labelE1Text, buttonE1Text, LV_ALIGN_IN_LEFT_MID, 0, 0); - + //#if AXIS_IS_TMC(E1) lv_label_set_text(labelTurnPage, machine_menu.previous); lv_obj_align(labelTurnPage, buttonTurnPage, LV_ALIGN_CENTER, 0, 0); - - milliamps = stepperE1.getMilliamps(); + #if AXIS_IS_TMC(E1) + milliamps = stepperE1.getMilliamps(); + #else + milliamps = -1; + #endif ZERO(public_buf_l); sprintf_P(public_buf_l, PSTR("%.1f"), milliamps); lv_label_set_text(labelE1Value, public_buf_l); lv_obj_align(labelE1Value, buttonE1Value, LV_ALIGN_CENTER, 0, 0); - #endif + //#endif } lv_label_set_text(label_Back, common_menu.text_back); @@ -380,6 +377,11 @@ void lv_draw_tmc_current_settings(void) { } } -void lv_clear_tmc_current_settings() { lv_obj_del(scr); } +void lv_clear_tmc_current_settings() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} #endif // HAS_TFT_LVGL_UI && HAS_TRINAMIC_CONFIG diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_tmc_current_settings.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_tmc_current_settings.h index 46463dd3c6..927db37138 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_tmc_current_settings.h +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_tmc_current_settings.h @@ -22,13 +22,13 @@ #pragma once #ifdef __cplusplus -extern "C" { /* C-declarations for C++ */ + extern "C" { /* C-declarations for C++ */ #endif extern void lv_draw_tmc_current_settings(void); extern void lv_clear_tmc_current_settings(); #ifdef __cplusplus -} /* C-declarations for C++ */ + } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_tmc_step_mode_settings.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_tmc_step_mode_settings.cpp index b0d40fde28..3e014a781c 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_tmc_step_mode_settings.cpp +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_tmc_step_mode_settings.cpp @@ -33,6 +33,7 @@ #include "../../../../gcode/gcode.h" #include "../../../../module/planner.h" +extern lv_group_t * g; static lv_obj_t * scr; #define ID_TMC_MODE_RETURN 1 @@ -47,9 +48,9 @@ static lv_obj_t * scr; static lv_obj_t *labelXState = NULL, *labelYState = NULL, *labelZState = NULL, *labelE0State = NULL; static lv_obj_t *buttonXState = NULL, *buttonYState = NULL, *buttonZState = NULL, *buttonE0State = NULL; -#if AXIS_HAS_STEALTHCHOP(E1) +//#if AXIS_HAS_STEALTHCHOP(E1) static lv_obj_t *labelE1State = NULL, *buttonE1State = NULL; -#endif +//#endif static void event_handler(lv_obj_t * obj, lv_event_t event) { switch (obj->mks_obj_id) { @@ -63,136 +64,158 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { draw_return_ui(); } break; - case ID_TMC_MODE_X: - if (event == LV_EVENT_CLICKED) { - } - else if (event == LV_EVENT_RELEASED) { - if (stepperX.stored.stealthChop_enabled == true) { - stepperX.stored.stealthChop_enabled = false; - stepperX.refresh_stepping_mode(); - lv_obj_set_event_cb_mks(buttonXState, event_handler, ID_TMC_MODE_X, "bmp_disable.bin", 0); - lv_label_set_text(labelXState, machine_menu.disable); - //lv_obj_align(labelXState, buttonE1State, LV_ALIGN_IN_LEFT_MID,0, 0); - // gcode.process_subcommands_now_P(PSTR("M500")); - } - else { - stepperX.stored.stealthChop_enabled = true; - stepperX.refresh_stepping_mode(); - lv_obj_set_event_cb_mks(buttonXState, event_handler, ID_TMC_MODE_X, "bmp_enable.bin", 0); - lv_label_set_text(labelXState, machine_menu.enable); - // gcode.process_subcommands_now_P(PSTR("M500")); - } - gcode.process_subcommands_now_P(PSTR("M500")); - } - break; - case ID_TMC_MODE_Y: - if (event == LV_EVENT_CLICKED) { + #if AXIS_HAS_STEALTHCHOP(X) + case ID_TMC_MODE_X: + if (event == LV_EVENT_CLICKED) { - } - else if (event == LV_EVENT_RELEASED) { - if (stepperY.stored.stealthChop_enabled == true) { - stepperY.stored.stealthChop_enabled = false; - stepperY.refresh_stepping_mode(); - lv_obj_set_event_cb_mks(buttonYState, event_handler, ID_TMC_MODE_Y, "bmp_disable.bin", 0); - lv_label_set_text(labelYState, machine_menu.disable); - //lv_obj_align(labelXState, buttonE1State, LV_ALIGN_IN_LEFT_MID,0, 0); } - else { - stepperY.stored.stealthChop_enabled = true; - stepperY.refresh_stepping_mode(); - lv_obj_set_event_cb_mks(buttonYState, event_handler, ID_TMC_MODE_Y, "bmp_enable.bin", 0); - lv_label_set_text(labelYState, machine_menu.enable); + else if (event == LV_EVENT_RELEASED) { + if (stepperX.stored.stealthChop_enabled) { + stepperX.stored.stealthChop_enabled = false; + stepperX.refresh_stepping_mode(); + lv_imgbtn_set_src(buttonXState, LV_BTN_STATE_REL, "F:/bmp_disable.bin"); + lv_imgbtn_set_src(buttonXState, LV_BTN_STATE_PR, "F:/bmp_disable.bin"); + lv_label_set_text(labelXState, machine_menu.disable); + //lv_obj_align(labelXState, buttonE1State, LV_ALIGN_IN_LEFT_MID,0, 0); + // gcode.process_subcommands_now_P(PSTR("M500")); + } + else { + stepperX.stored.stealthChop_enabled = true; + stepperX.refresh_stepping_mode(); + lv_imgbtn_set_src(buttonXState, LV_BTN_STATE_REL, "F:/bmp_enable.bin"); + lv_imgbtn_set_src(buttonXState, LV_BTN_STATE_PR, "F:/bmp_enable.bin"); + lv_label_set_text(labelXState, machine_menu.enable); + // gcode.process_subcommands_now_P(PSTR("M500")); + } + gcode.process_subcommands_now_P(PSTR("M500")); } - gcode.process_subcommands_now_P(PSTR("M500")); - } - break; - case ID_TMC_MODE_Z: - if (event == LV_EVENT_CLICKED) { + break; + #endif // if AXIS_HAS_STEALTHCHOP(X) - } - else if (event == LV_EVENT_RELEASED) { - if (stepperZ.stored.stealthChop_enabled == true) { - stepperZ.stored.stealthChop_enabled = false; - stepperZ.refresh_stepping_mode(); - lv_obj_set_event_cb_mks(buttonZState, event_handler, ID_TMC_MODE_Z, "bmp_disable.bin", 0); - lv_label_set_text(labelZState, machine_menu.disable); - //lv_obj_align(labelXState, buttonE1State, LV_ALIGN_IN_LEFT_MID,0, 0); - } - else { - stepperZ.stored.stealthChop_enabled = true; - stepperZ.refresh_stepping_mode(); - lv_obj_set_event_cb_mks(buttonZState, event_handler, ID_TMC_MODE_Z, "bmp_enable.bin", 0); - lv_label_set_text(labelZState, machine_menu.enable); - } - gcode.process_subcommands_now_P(PSTR("M500")); - } - break; - case ID_TMC_MODE_E0: - if (event == LV_EVENT_CLICKED) { + #if AXIS_HAS_STEALTHCHOP(Y) + case ID_TMC_MODE_Y: + if (event == LV_EVENT_CLICKED) { - } - else if (event == LV_EVENT_RELEASED) { - if (stepperE0.stored.stealthChop_enabled == true) { - stepperE0.stored.stealthChop_enabled = false; - stepperE0.refresh_stepping_mode(); - lv_obj_set_event_cb_mks(buttonE0State, event_handler, ID_TMC_MODE_E0, "bmp_disable.bin", 0); - lv_label_set_text(labelE0State, machine_menu.disable); - //lv_obj_align(labelXState, buttonE1State, LV_ALIGN_IN_LEFT_MID,0, 0); } - else { - stepperE0.stored.stealthChop_enabled = true; - stepperE0.refresh_stepping_mode(); - lv_obj_set_event_cb_mks(buttonE0State, event_handler, ID_TMC_MODE_E0, "bmp_enable.bin", 0); - lv_label_set_text(labelE0State, machine_menu.enable); + else if (event == LV_EVENT_RELEASED) { + if (stepperY.stored.stealthChop_enabled) { + stepperY.stored.stealthChop_enabled = false; + stepperY.refresh_stepping_mode(); + lv_imgbtn_set_src(buttonYState, LV_BTN_STATE_REL, "F:/bmp_disable.bin"); + lv_imgbtn_set_src(buttonYState, LV_BTN_STATE_PR, "F:/bmp_disable.bin"); + lv_label_set_text(labelYState, machine_menu.disable); + //lv_obj_align(labelXState, buttonE1State, LV_ALIGN_IN_LEFT_MID,0, 0); + } + else { + stepperY.stored.stealthChop_enabled = true; + stepperY.refresh_stepping_mode(); + lv_imgbtn_set_src(buttonYState, LV_BTN_STATE_REL, "F:/bmp_enable.bin"); + lv_imgbtn_set_src(buttonYState, LV_BTN_STATE_PR, "F:/bmp_enable.bin"); + lv_label_set_text(labelYState, machine_menu.enable); + } + gcode.process_subcommands_now_P(PSTR("M500")); } - gcode.process_subcommands_now_P(PSTR("M500")); - } - break; - #if AXIS_HAS_STEALTHCHOP(E1) - case ID_TMC_MODE_E1: - if (event == LV_EVENT_CLICKED) { + break; + #endif // if AXIS_HAS_STEALTHCHOP(Y) + #if AXIS_HAS_STEALTHCHOP(Z) + case ID_TMC_MODE_Z: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + if (stepperZ.stored.stealthChop_enabled) { + stepperZ.stored.stealthChop_enabled = false; + stepperZ.refresh_stepping_mode(); + lv_imgbtn_set_src(buttonZState, LV_BTN_STATE_REL, "F:/bmp_disable.bin"); + lv_imgbtn_set_src(buttonZState, LV_BTN_STATE_PR, "F:/bmp_disable.bin"); + lv_label_set_text(labelZState, machine_menu.disable); + //lv_obj_align(labelXState, buttonE1State, LV_ALIGN_IN_LEFT_MID,0, 0); } - else if (event == LV_EVENT_RELEASED) { - if (stepperE1.stored.stealthChop_enabled == true) { - stepperE1.stored.stealthChop_enabled = false; - stepperE1.refresh_stepping_mode(); - lv_obj_set_event_cb_mks(buttonE1State, event_handler, ID_TMC_MODE_E1, "bmp_disable.bin", 0); - lv_label_set_text(labelE1State, machine_menu.disable); - //lv_obj_align(labelXState, buttonE1State, LV_ALIGN_IN_LEFT_MID,0, 0); - } - else { - stepperE1.stored.stealthChop_enabled = true; - stepperE1.refresh_stepping_mode(); - lv_obj_set_event_cb_mks(buttonE1State, event_handler, ID_TMC_MODE_E1, "bmp_enable.bin", 0); - lv_label_set_text(labelE1State, machine_menu.enable); - } - gcode.process_subcommands_now_P(PSTR("M500")); + else { + stepperZ.stored.stealthChop_enabled = true; + stepperZ.refresh_stepping_mode(); + lv_imgbtn_set_src(buttonZState, LV_BTN_STATE_REL, "F:/bmp_enable.bin"); + lv_imgbtn_set_src(buttonZState, LV_BTN_STATE_PR, "F:/bmp_enable.bin"); + lv_label_set_text(labelZState, machine_menu.enable); } - break; + gcode.process_subcommands_now_P(PSTR("M500")); + } + break; + #endif // if AXIS_HAS_STEALTHCHOP(Z) - case ID_TMC_MODE_UP: - if (event == LV_EVENT_CLICKED) { + #if AXIS_HAS_STEALTHCHOP(E0) + case ID_TMC_MODE_E0: + if (event == LV_EVENT_CLICKED) { + } + else if (event == LV_EVENT_RELEASED) { + if (stepperE0.stored.stealthChop_enabled) { + stepperE0.stored.stealthChop_enabled = false; + stepperE0.refresh_stepping_mode(); + lv_imgbtn_set_src(buttonE0State, LV_BTN_STATE_REL, "F:/bmp_disable.bin"); + lv_imgbtn_set_src(buttonE0State, LV_BTN_STATE_PR, "F:/bmp_disable.bin"); + lv_label_set_text(labelE0State, machine_menu.disable); + //lv_obj_align(labelXState, buttonE1State, LV_ALIGN_IN_LEFT_MID,0, 0); } - else if (event == LV_EVENT_RELEASED) { - uiCfg.para_ui_page = 0; - lv_clear_tmc_step_mode_settings(); - lv_draw_tmc_step_mode_settings(); + else { + stepperE0.stored.stealthChop_enabled = true; + stepperE0.refresh_stepping_mode(); + lv_imgbtn_set_src(buttonE0State, LV_BTN_STATE_REL, "F:/bmp_enable.bin"); + lv_imgbtn_set_src(buttonE0State, LV_BTN_STATE_PR, "F:/bmp_enable.bin"); + lv_label_set_text(labelE0State, machine_menu.enable); } - break; - case ID_TMC_MODE_DOWN: - if (event == LV_EVENT_CLICKED) { + gcode.process_subcommands_now_P(PSTR("M500")); + } + break; + #endif // if AXIS_HAS_STEALTHCHOP(E0) + + #if AXIS_HAS_STEALTHCHOP(E1) + case ID_TMC_MODE_E1: + if (event == LV_EVENT_CLICKED) { + } + else if (event == LV_EVENT_RELEASED) { + if (stepperE1.stored.stealthChop_enabled) { + stepperE1.stored.stealthChop_enabled = false; + stepperE1.refresh_stepping_mode(); + lv_imgbtn_set_src(buttonE1State, LV_BTN_STATE_REL, "F:/bmp_disable.bin"); + lv_imgbtn_set_src(buttonE1State, LV_BTN_STATE_PR, "F:/bmp_disable.bin"); + lv_label_set_text(labelE1State, machine_menu.disable); + //lv_obj_align(labelXState, buttonE1State, LV_ALIGN_IN_LEFT_MID,0, 0); } - else if (event == LV_EVENT_RELEASED) { - uiCfg.para_ui_page = 1; - lv_clear_tmc_step_mode_settings(); - lv_draw_tmc_step_mode_settings(); + else { + stepperE1.stored.stealthChop_enabled = true; + stepperE1.refresh_stepping_mode(); + lv_imgbtn_set_src(buttonE1State, LV_BTN_STATE_REL, "F:/bmp_enable.bin"); + lv_imgbtn_set_src(buttonE1State, LV_BTN_STATE_PR, "F:/bmp_enable.bin"); + lv_label_set_text(labelE1State, machine_menu.enable); } - break; - #endif // if AXIS_HAS_STEALTHCHOP(E1) + gcode.process_subcommands_now_P(PSTR("M500")); + } + break; + #endif // if AXIS_HAS_STEALTHCHOP(E1) + case ID_TMC_MODE_UP: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + uiCfg.para_ui_page = 0; + lv_clear_tmc_step_mode_settings(); + lv_draw_tmc_step_mode_settings(); + } + break; + case ID_TMC_MODE_DOWN: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + uiCfg.para_ui_page = 1; + lv_clear_tmc_step_mode_settings(); + lv_draw_tmc_step_mode_settings(); + } + break; } } @@ -204,10 +227,10 @@ void lv_draw_tmc_step_mode_settings(void) { lv_obj_t *buttonE0Text = NULL, *labelE0Text = NULL; lv_obj_t * line1 = NULL, * line2 = NULL, * line3 = NULL, * line4 = NULL; - #if AXIS_HAS_STEALTHCHOP(E1) + //#if AXIS_HAS_STEALTHCHOP(E1) lv_obj_t *buttonTurnPage = NULL, *labelTurnPage = NULL; lv_obj_t *buttonE1Text = NULL, *labelE1Text = NULL; - #endif + //#endif labelXState = NULL; @@ -218,10 +241,10 @@ void lv_draw_tmc_step_mode_settings(void) { buttonZState = NULL; labelE0State = NULL; buttonE0State = NULL; - #if AXIS_HAS_STEALTHCHOP(E1) + //#if AXIS_HAS_STEALTHCHOP(E1) labelE1State = NULL; buttonE1State = NULL; - #endif + //#endif if (disp_state_stack._disp_state[disp_state_stack._disp_index] != TMC_MODE_UI) { disp_state_stack._disp_index++; @@ -242,10 +265,6 @@ void lv_draw_tmc_step_mode_settings(void) { lv_refr_now(lv_refr_get_disp_refreshing()); - LV_IMG_DECLARE(bmp_para_back); - LV_IMG_DECLARE(bmp_para_state); - // LV_IMG_DECLARE(bmp_para_bank); - if (uiCfg.para_ui_page != 1) { buttonXText = lv_btn_create(scr, NULL); /*Add a button the current screen*/ lv_obj_set_pos(buttonXText, PARA_UI_POS_X, PARA_UI_POS_Y); /*Set its position*/ @@ -258,16 +277,28 @@ void lv_draw_tmc_step_mode_settings(void) { buttonXState = lv_imgbtn_create(scr, NULL); lv_obj_set_pos(buttonXState, PARA_UI_STATE_POS_X, PARA_UI_POS_Y + PARA_UI_STATE_V); - if (stepperX.get_stealthChop_status()) - lv_obj_set_event_cb_mks(buttonXState, event_handler, ID_TMC_MODE_X, "bmp_enable.bin", 0); - else - lv_obj_set_event_cb_mks(buttonXState, event_handler, ID_TMC_MODE_X, "bmp_disable.bin", 0); - lv_imgbtn_set_src(buttonXState, LV_BTN_STATE_REL, &bmp_para_state); - lv_imgbtn_set_src(buttonXState, LV_BTN_STATE_PR, &bmp_para_state); + #if AXIS_HAS_STEALTHCHOP(X) + if (stepperX.get_stealthChop_status()) { + lv_imgbtn_set_src(buttonXState, LV_BTN_STATE_REL, "F:/bmp_enable.bin"); + lv_imgbtn_set_src(buttonXState, LV_BTN_STATE_PR, "F:/bmp_enable.bin"); + } + else { + lv_imgbtn_set_src(buttonXState, LV_BTN_STATE_REL, "F:/bmp_disable.bin"); + lv_imgbtn_set_src(buttonXState, LV_BTN_STATE_PR, "F:/bmp_disable.bin"); + } + #else + lv_imgbtn_set_src(buttonXState, LV_BTN_STATE_REL, "F:/bmp_disable.bin"); + lv_imgbtn_set_src(buttonXState, LV_BTN_STATE_PR, "F:/bmp_disable.bin"); + #endif + lv_obj_set_event_cb_mks(buttonXState, event_handler, ID_TMC_MODE_X, NULL, 0); + lv_imgbtn_set_style(buttonXState, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonXState, LV_BTN_STATE_REL, &tft_style_label_rel); lv_btn_set_layout(buttonXState, LV_LAYOUT_OFF); labelXState = lv_label_create(buttonXState, NULL); + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonXState); + #endif line1 = lv_line_create(scr, NULL); lv_ex_line(line1, line_points[0]); @@ -283,16 +314,28 @@ void lv_draw_tmc_step_mode_settings(void) { buttonYState = lv_imgbtn_create(scr, NULL); lv_obj_set_pos(buttonYState, PARA_UI_STATE_POS_X, PARA_UI_POS_Y * 2 + PARA_UI_STATE_V); - if (stepperY.get_stealthChop_status()) - lv_obj_set_event_cb_mks(buttonYState, event_handler, ID_TMC_MODE_Y, "bmp_enable.bin", 0); - else - lv_obj_set_event_cb_mks(buttonYState, event_handler, ID_TMC_MODE_Y, "bmp_disable.bin", 0); - lv_imgbtn_set_src(buttonYState, LV_BTN_STATE_REL, &bmp_para_state); - lv_imgbtn_set_src(buttonYState, LV_BTN_STATE_PR, &bmp_para_state); + #if AXIS_HAS_STEALTHCHOP(Y) + if (stepperY.get_stealthChop_status()) { + lv_imgbtn_set_src(buttonYState, LV_BTN_STATE_REL, "F:/bmp_enable.bin"); + lv_imgbtn_set_src(buttonYState, LV_BTN_STATE_PR, "F:/bmp_enable.bin"); + } + else { + lv_imgbtn_set_src(buttonYState, LV_BTN_STATE_REL, "F:/bmp_disable.bin"); + lv_imgbtn_set_src(buttonYState, LV_BTN_STATE_PR, "F:/bmp_disable.bin"); + } + #else + lv_imgbtn_set_src(buttonYState, LV_BTN_STATE_REL, "F:/bmp_disable.bin"); + lv_imgbtn_set_src(buttonYState, LV_BTN_STATE_PR, "F:/bmp_disable.bin"); + #endif + lv_obj_set_event_cb_mks(buttonYState, event_handler, ID_TMC_MODE_Y, NULL, 0); + lv_imgbtn_set_style(buttonYState, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonYState, LV_BTN_STATE_REL, &tft_style_label_rel); lv_btn_set_layout(buttonYState, LV_LAYOUT_OFF); labelYState = lv_label_create(buttonYState, NULL); + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonYState); + #endif line2 = lv_line_create(scr, NULL); lv_ex_line(line2, line_points[1]); @@ -308,16 +351,27 @@ void lv_draw_tmc_step_mode_settings(void) { buttonZState = lv_imgbtn_create(scr, NULL); lv_obj_set_pos(buttonZState, PARA_UI_STATE_POS_X, PARA_UI_POS_Y * 3 + PARA_UI_STATE_V); - if (stepperZ.get_stealthChop_status()) - lv_obj_set_event_cb_mks(buttonZState, event_handler, ID_TMC_MODE_Z, "bmp_enable.bin", 0); - else - lv_obj_set_event_cb_mks(buttonZState, event_handler, ID_TMC_MODE_Z, "bmp_disable.bin", 0); - lv_imgbtn_set_src(buttonZState, LV_BTN_STATE_REL, &bmp_para_state); - lv_imgbtn_set_src(buttonZState, LV_BTN_STATE_PR, &bmp_para_state); + #if AXIS_HAS_STEALTHCHOP(Z) + if (stepperZ.get_stealthChop_status()) { + lv_imgbtn_set_src(buttonZState, LV_BTN_STATE_REL, "F:/bmp_enable.bin"); + lv_imgbtn_set_src(buttonZState, LV_BTN_STATE_PR, "F:/bmp_enable.bin"); + } + else { + lv_imgbtn_set_src(buttonZState, LV_BTN_STATE_REL, "F:/bmp_disable.bin"); + lv_imgbtn_set_src(buttonZState, LV_BTN_STATE_PR, "F:/bmp_disable.bin"); + } + #else + lv_imgbtn_set_src(buttonZState, LV_BTN_STATE_REL, "F:/bmp_disable.bin"); + lv_imgbtn_set_src(buttonZState, LV_BTN_STATE_PR, "F:/bmp_disable.bin"); + #endif + lv_obj_set_event_cb_mks(buttonZState, event_handler, ID_TMC_MODE_Z, NULL, 0); lv_imgbtn_set_style(buttonZState, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonZState, LV_BTN_STATE_REL, &tft_style_label_rel); lv_btn_set_layout(buttonZState, LV_LAYOUT_OFF); labelZState = lv_label_create(buttonZState, NULL); + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonZState); + #endif line3 = lv_line_create(scr, NULL); lv_ex_line(line3, line_points[2]); @@ -333,31 +387,48 @@ void lv_draw_tmc_step_mode_settings(void) { buttonE0State = lv_imgbtn_create(scr, NULL); lv_obj_set_pos(buttonE0State, PARA_UI_STATE_POS_X, PARA_UI_POS_Y * 4 + PARA_UI_STATE_V); - if (stepperE0.get_stealthChop_status()) - lv_obj_set_event_cb_mks(buttonE0State, event_handler, ID_TMC_MODE_E0, "bmp_enable.bin", 0); - else - lv_obj_set_event_cb_mks(buttonE0State, event_handler, ID_TMC_MODE_E0, "bmp_disable.bin", 0); - lv_imgbtn_set_src(buttonE0State, LV_BTN_STATE_REL, &bmp_para_state); - lv_imgbtn_set_src(buttonE0State, LV_BTN_STATE_PR, &bmp_para_state); + #if AXIS_HAS_STEALTHCHOP(E0) + if (stepperE0.get_stealthChop_status()) { + lv_imgbtn_set_src(buttonE0State, LV_BTN_STATE_REL, "F:/bmp_enable.bin"); + lv_imgbtn_set_src(buttonE0State, LV_BTN_STATE_PR, "F:/bmp_enable.bin"); + } + else { + lv_imgbtn_set_src(buttonE0State, LV_BTN_STATE_REL, "F:/bmp_disable.bin"); + lv_imgbtn_set_src(buttonE0State, LV_BTN_STATE_PR, "F:/bmp_disable.bin"); + } + #else + lv_imgbtn_set_src(buttonE0State, LV_BTN_STATE_REL, "F:/bmp_disable.bin"); + lv_imgbtn_set_src(buttonE0State, LV_BTN_STATE_PR, "F:/bmp_disable.bin"); + #endif + + lv_obj_set_event_cb_mks(buttonE0State, event_handler, ID_TMC_MODE_E0, NULL, 0); + lv_imgbtn_set_style(buttonE0State, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonE0State, LV_BTN_STATE_REL, &tft_style_label_rel); lv_btn_set_layout(buttonE0State, LV_LAYOUT_OFF); labelE0State = lv_label_create(buttonE0State, NULL); + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonE0State); + #endif + line4 = lv_line_create(scr, NULL); lv_ex_line(line4, line_points[3]); - #if AXIS_HAS_STEALTHCHOP(E1) + //#if AXIS_HAS_STEALTHCHOP(E1) buttonTurnPage = lv_imgbtn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonTurnPage, event_handler, ID_TMC_MODE_DOWN, "bmp_back70x40.bin", 0); - lv_imgbtn_set_src(buttonTurnPage, LV_BTN_STATE_REL, &bmp_para_back); - lv_imgbtn_set_src(buttonTurnPage, LV_BTN_STATE_PR, &bmp_para_back); + lv_obj_set_event_cb_mks(buttonTurnPage, event_handler, ID_TMC_MODE_DOWN, NULL, 0); + lv_imgbtn_set_src(buttonTurnPage, LV_BTN_STATE_REL, "F:/bmp_back70x40.bin"); + lv_imgbtn_set_src(buttonTurnPage, LV_BTN_STATE_PR, "F:/bmp_back70x40.bin"); lv_imgbtn_set_style(buttonTurnPage, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonTurnPage, LV_BTN_STATE_REL, &tft_style_label_rel); - #endif + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonTurnPage); + #endif + //#endif } else { - #if AXIS_HAS_STEALTHCHOP(E1) + //#if AXIS_HAS_STEALTHCHOP(E1) buttonE1Text = lv_btn_create(scr, NULL); /*Add a button the current screen*/ lv_obj_set_pos(buttonE1Text, PARA_UI_POS_X, PARA_UI_POS_Y); /*Set its position*/ lv_obj_set_size(buttonE1Text, PARA_UI_VALUE_SIZE_X, PARA_UI_SIZE_Y); /*Set its size*/ @@ -369,40 +440,54 @@ void lv_draw_tmc_step_mode_settings(void) { buttonE1State = lv_imgbtn_create(scr, NULL); lv_obj_set_pos(buttonE1State, PARA_UI_STATE_POS_X, PARA_UI_POS_Y + PARA_UI_STATE_V); - if (stepperE1.get_stealthChop_status()) - lv_obj_set_event_cb_mks(buttonE1State, event_handler, ID_TMC_MODE_E1, "bmp_enable.bin", 0); - else - lv_obj_set_event_cb_mks(buttonE1State, event_handler, ID_TMC_MODE_E1, "bmp_disable.bin", 0); - lv_imgbtn_set_src(buttonE1State, LV_BTN_STATE_REL, &bmp_para_state); - lv_imgbtn_set_src(buttonE1State, LV_BTN_STATE_PR, &bmp_para_state); + #if AXIS_HAS_STEALTHCHOP(E1) + if (stepperE1.get_stealthChop_status()) { + lv_imgbtn_set_src(buttonE1State, LV_BTN_STATE_REL, "F:/bmp_enable.bin"); + lv_imgbtn_set_src(buttonE1State, LV_BTN_STATE_PR, "F:/bmp_enable.bin"); + } + else { + lv_imgbtn_set_src(buttonE1State, LV_BTN_STATE_REL, "F:/bmp_disable.bin"); + lv_imgbtn_set_src(buttonE1State, LV_BTN_STATE_PR, "F:/bmp_disable.bin"); + } + #else + lv_imgbtn_set_src(buttonE1State, LV_BTN_STATE_REL, "F:/bmp_disable.bin"); + lv_imgbtn_set_src(buttonE1State, LV_BTN_STATE_PR, "F:/bmp_disable.bin"); + #endif + lv_obj_set_event_cb_mks(buttonE1State, event_handler, ID_TMC_MODE_E1, NULL, 0); lv_imgbtn_set_style(buttonE1State, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonE1State, LV_BTN_STATE_REL, &tft_style_label_rel); lv_btn_set_layout(buttonE1State, LV_LAYOUT_OFF); labelE1State = lv_label_create(buttonE1State, NULL); + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonE1State); + #endif line1 = lv_line_create(scr, NULL); lv_ex_line(line1, line_points[0]); buttonTurnPage = lv_imgbtn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonTurnPage, event_handler, ID_TMC_MODE_UP, "bmp_back70x40.bin", 0); - lv_imgbtn_set_src(buttonTurnPage, LV_BTN_STATE_REL, &bmp_para_back); - lv_imgbtn_set_src(buttonTurnPage, LV_BTN_STATE_PR, &bmp_para_back); + lv_obj_set_event_cb_mks(buttonTurnPage, event_handler, ID_TMC_MODE_UP, NULL, 0); + lv_imgbtn_set_src(buttonTurnPage, LV_BTN_STATE_REL, "F:/bmp_back70x40.bin"); + lv_imgbtn_set_src(buttonTurnPage, LV_BTN_STATE_PR, "F:/bmp_back70x40.bin"); lv_imgbtn_set_style(buttonTurnPage, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonTurnPage, LV_BTN_STATE_REL, &tft_style_label_rel); - #endif + //#endif } - #if AXIS_HAS_STEALTHCHOP(E1) + //#if AXIS_HAS_STEALTHCHOP(E1) lv_obj_set_pos(buttonTurnPage, PARA_UI_TURN_PAGE_POS_X, PARA_UI_TURN_PAGE_POS_Y); lv_btn_set_layout(buttonTurnPage, LV_LAYOUT_OFF); labelTurnPage = lv_label_create(buttonTurnPage, NULL); - #endif + //#endif buttonBack = lv_imgbtn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_TMC_MODE_RETURN, "bmp_back70x40.bin", 0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, &bmp_para_back); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, &bmp_para_back); + lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_TMC_MODE_RETURN, NULL, 0); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_back70x40.bin"); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_back70x40.bin"); lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonBack); + #endif lv_obj_set_pos(buttonBack, PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y); lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); @@ -422,50 +507,68 @@ void lv_draw_tmc_step_mode_settings(void) { lv_label_set_text(labelE0Text, machine_menu.E0_StepMode); lv_obj_align(labelE0Text, buttonE0Text, LV_ALIGN_IN_LEFT_MID, 0, 0); + #if AXIS_HAS_STEALTHCHOP(X) if (stepperX.get_stealthChop_status()) lv_label_set_text(labelXState, machine_menu.enable); else lv_label_set_text(labelXState, machine_menu.disable); + #else + lv_label_set_text(labelXState, machine_menu.disable); + #endif lv_obj_align(labelXState, buttonXState, LV_ALIGN_CENTER, 0, 0); + #if AXIS_HAS_STEALTHCHOP(Y) if (stepperY.get_stealthChop_status()) lv_label_set_text(labelYState, machine_menu.enable); else lv_label_set_text(labelYState, machine_menu.disable); + #else + lv_label_set_text(labelYState, machine_menu.disable); + #endif lv_obj_align(labelYState, buttonYState, LV_ALIGN_CENTER, 0, 0); + #if AXIS_HAS_STEALTHCHOP(Z) if (stepperZ.get_stealthChop_status()) lv_label_set_text(labelZState, machine_menu.enable); else lv_label_set_text(labelZState, machine_menu.disable); + #else + lv_label_set_text(labelZState, machine_menu.disable); + #endif lv_obj_align(labelZState, buttonZState, LV_ALIGN_CENTER, 0, 0); + #if AXIS_HAS_STEALTHCHOP(E0) if (stepperE0.get_stealthChop_status()) lv_label_set_text(labelE0State, machine_menu.enable); else lv_label_set_text(labelE0State, machine_menu.disable); + #else + lv_label_set_text(labelE0State, machine_menu.disable); + #endif lv_obj_align(labelE0State, buttonE0State, LV_ALIGN_CENTER, 0, 0); - #if AXIS_HAS_STEALTHCHOP(E1) + //#if AXIS_HAS_STEALTHCHOP(E1) lv_label_set_text(labelTurnPage, machine_menu.next); lv_obj_align(labelTurnPage, buttonTurnPage, LV_ALIGN_CENTER, 0, 0); - #endif + //#endif } else { - #if AXIS_HAS_STEALTHCHOP(E1) + //#if AXIS_HAS_STEALTHCHOP(E1) lv_label_set_text(labelE1Text, machine_menu.E1_StepMode); lv_obj_align(labelE1Text, buttonE1Text, LV_ALIGN_IN_LEFT_MID, 0, 0); - + #if AXIS_HAS_STEALTHCHOP(E1) if (stepperE1.get_stealthChop_status()) lv_label_set_text(labelE1State, machine_menu.enable); else lv_label_set_text(labelE1State, machine_menu.disable); + #else + lv_label_set_text(labelE1State, machine_menu.disable); + #endif lv_obj_align(labelE1State, buttonE1State, LV_ALIGN_CENTER, 0, 0); lv_label_set_text(labelTurnPage, machine_menu.previous); lv_obj_align(labelTurnPage, buttonTurnPage, LV_ALIGN_CENTER, 0, 0); - - #endif + //#endif } lv_label_set_text(label_Back, common_menu.text_back); @@ -473,6 +576,11 @@ void lv_draw_tmc_step_mode_settings(void) { } } -void lv_clear_tmc_step_mode_settings() { lv_obj_del(scr); } +void lv_clear_tmc_step_mode_settings() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} #endif // HAS_TFT_LVGL_UI && HAS_STEALTHCHOP diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_tmc_step_mode_settings.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_tmc_step_mode_settings.h index 93085b7ca1..35c57ab0cc 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_tmc_step_mode_settings.h +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_tmc_step_mode_settings.h @@ -22,12 +22,12 @@ #pragma once #ifdef __cplusplus -extern "C" { /* C-declarations for C++ */ + extern "C" { /* C-declarations for C++ */ #endif extern void lv_draw_tmc_step_mode_settings(void); extern void lv_clear_tmc_step_mode_settings(); #ifdef __cplusplus -} /* C-declarations for C++ */ + } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_tool.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_tool.cpp index 91dd2f36ab..3681b1b2d6 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_tool.cpp +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_tool.cpp @@ -32,8 +32,9 @@ #include "../../../../MarlinCore.h" #include "../../../../gcode/queue.h" +#include "../../../../module/temperature.h" -// static lv_obj_t *buttonMoveZ,*buttonTest,*buttonZ0,*buttonStop,*buttonReturn; +extern lv_group_t * g; static lv_obj_t * scr; #define ID_T_PRE_HEAT 1 @@ -45,6 +46,10 @@ static lv_obj_t * scr; #define ID_T_MORE 7 #define ID_T_RETURN 8 +#if ENABLED(MKS_TEST) + extern uint8_t curent_disp_ui; +#endif + static void event_handler(lv_obj_t * obj, lv_event_t event) { switch (obj->mks_obj_id) { case ID_T_PRE_HEAT: @@ -89,8 +94,11 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { } else if (event == LV_EVENT_RELEASED) { #if ENABLED(AUTO_BED_LEVELING_BILINEAR) - queue.enqueue_one_P(PSTR("G28")); - queue.enqueue_one_P(PSTR("G29")); + //queue.enqueue_one_P(PSTR("G28")); + //queue.enqueue_one_P(PSTR("G29")); + get_gcode_command(AUTO_LEVELING_COMMAND_ADDR,(uint8_t *)public_buf_m); + public_buf_m[sizeof(public_buf_m)-1] = 0; + queue.inject_P(PSTR(public_buf_m)); #else uiCfg.leveling_first_time = 1; lv_clear_tool(); @@ -98,7 +106,16 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { #endif } break; - case ID_T_FILAMENT: break; + case ID_T_FILAMENT: + if (event == LV_EVENT_CLICKED) { + // nothing to do + } + else if (event == LV_EVENT_RELEASED) { + uiCfg.desireSprayerTempBak = thermalManager.temp_hotend[uiCfg.curSprayerChoose].target; + lv_clear_tool(); + lv_draw_filament_change(); + } + break; case ID_T_MORE: break; case ID_T_RETURN: if (event == LV_EVENT_CLICKED) { @@ -106,7 +123,7 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { } else if (event == LV_EVENT_RELEASED) { TERN_(MKS_TEST, curent_disp_ui = 1); - lv_obj_del(scr); + lv_clear_tool(); lv_draw_ready_print(); } break; @@ -115,6 +132,7 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { void lv_draw_tool(void) { lv_obj_t *buttonPreHeat, *buttonExtrusion, *buttonMove, *buttonHome, *buttonLevel; + lv_obj_t *buttonFilament; lv_obj_t *buttonBack; if (disp_state_stack._disp_state[disp_state_stack._disp_index] != TOOL_UI) { @@ -138,96 +156,85 @@ void lv_draw_tool(void) { lv_refr_now(lv_refr_get_disp_refreshing()); - LV_IMG_DECLARE(bmp_pic); - - /*Create an Image button*/ + // Create image buttons buttonPreHeat = lv_imgbtn_create(scr, NULL); buttonExtrusion = lv_imgbtn_create(scr, NULL); buttonMove = lv_imgbtn_create(scr, NULL); buttonHome = lv_imgbtn_create(scr, NULL); buttonLevel = lv_imgbtn_create(scr, NULL); - // buttonFilament = lv_imgbtn_create(scr, NULL); - // buttonMore = lv_imgbtn_create(scr, NULL); - buttonBack = lv_imgbtn_create(scr, NULL); + buttonFilament = lv_imgbtn_create(scr, NULL); + //buttonMore = lv_imgbtn_create(scr, NULL); + buttonBack = lv_imgbtn_create(scr, NULL); - lv_obj_set_event_cb_mks(buttonPreHeat, event_handler, ID_T_PRE_HEAT, "bmp_preHeat.bin", 0); - lv_imgbtn_set_src(buttonPreHeat, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonPreHeat, LV_BTN_STATE_PR, &bmp_pic); + lv_obj_set_event_cb_mks(buttonPreHeat, event_handler, ID_T_PRE_HEAT, NULL, 0); + lv_imgbtn_set_src(buttonPreHeat, LV_BTN_STATE_REL, "F:/bmp_preHeat.bin"); + lv_imgbtn_set_src(buttonPreHeat, LV_BTN_STATE_PR, "F:/bmp_preHeat.bin"); lv_imgbtn_set_style(buttonPreHeat, LV_BTN_STATE_PR, &tft_style_label_pre); lv_imgbtn_set_style(buttonPreHeat, LV_BTN_STATE_REL, &tft_style_label_rel); - lv_obj_clear_protect(buttonPreHeat, LV_PROTECT_FOLLOW); - - #if 1 - lv_obj_set_event_cb_mks(buttonExtrusion, event_handler, ID_T_EXTRUCT, "bmp_extruct.bin", 0); - lv_imgbtn_set_src(buttonExtrusion, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonExtrusion, LV_BTN_STATE_PR, &bmp_pic); - lv_imgbtn_set_style(buttonExtrusion, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonExtrusion, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonMove, event_handler, ID_T_MOV, "bmp_mov.bin", 0); - lv_imgbtn_set_src(buttonMove, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonMove, LV_BTN_STATE_PR, &bmp_pic); - lv_imgbtn_set_style(buttonMove, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonMove, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonHome, event_handler, ID_T_HOME, "bmp_zero.bin", 0); - lv_imgbtn_set_src(buttonHome, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonHome, LV_BTN_STATE_PR, &bmp_pic); - lv_imgbtn_set_style(buttonHome, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonHome, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonLevel, event_handler, ID_T_LEVELING, "bmp_leveling.bin", 0); - lv_imgbtn_set_src(buttonLevel, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonLevel, LV_BTN_STATE_PR, &bmp_pic); - lv_imgbtn_set_style(buttonLevel, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonLevel, LV_BTN_STATE_REL, &tft_style_label_rel); - - //lv_obj_set_event_cb_mks(buttonFilament, event_handler,ID_T_FILAMENT,"bmp_Filamentchange.bin",0); - //lv_imgbtn_set_src(buttonFilament, LV_BTN_STATE_REL, &bmp_pic); - //lv_imgbtn_set_src(buttonFilament, LV_BTN_STATE_PR, &bmp_pic); - //lv_imgbtn_set_style(buttonFilament, LV_BTN_STATE_PR, &tft_style_label_pre); - //lv_imgbtn_set_style(buttonFilament, LV_BTN_STATE_REL, &tft_style_label_rel); - - //lv_obj_set_event_cb_mks(buttonMore, event_handler,ID_T_MORE,"bmp_More.bin",0); - //lv_imgbtn_set_src(buttonMore, LV_BTN_STATE_REL, &bmp_pic); - //lv_imgbtn_set_src(buttonMore, LV_BTN_STATE_PR, &bmp_pic); - //lv_imgbtn_set_style(buttonMore, LV_BTN_STATE_PR, &tft_style_label_pre); - //lv_imgbtn_set_style(buttonMore, LV_BTN_STATE_REL, &tft_style_label_rel); - - lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_T_RETURN, "bmp_return.bin", 0); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, &bmp_pic); - lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, &bmp_pic); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); - lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); - #endif // if 1 + + lv_obj_set_event_cb_mks(buttonExtrusion, event_handler, ID_T_EXTRUCT, NULL, 0); + lv_imgbtn_set_src(buttonExtrusion, LV_BTN_STATE_REL, "F:/bmp_extruct.bin"); + lv_imgbtn_set_src(buttonExtrusion, LV_BTN_STATE_PR, "F:/bmp_extruct.bin"); + lv_imgbtn_set_style(buttonExtrusion, LV_BTN_STATE_PR, &tft_style_label_pre); + lv_imgbtn_set_style(buttonExtrusion, LV_BTN_STATE_REL, &tft_style_label_rel); + + lv_obj_set_event_cb_mks(buttonMove, event_handler, ID_T_MOV, NULL, 0); + lv_imgbtn_set_src(buttonMove, LV_BTN_STATE_REL, "F:/bmp_mov.bin"); + lv_imgbtn_set_src(buttonMove, LV_BTN_STATE_PR, "F:/bmp_mov.bin"); + lv_imgbtn_set_style(buttonMove, LV_BTN_STATE_PR, &tft_style_label_pre); + lv_imgbtn_set_style(buttonMove, LV_BTN_STATE_REL, &tft_style_label_rel); + + lv_obj_set_event_cb_mks(buttonHome, event_handler, ID_T_HOME, NULL, 0); + lv_imgbtn_set_src(buttonHome, LV_BTN_STATE_REL, "F:/bmp_zero.bin"); + lv_imgbtn_set_src(buttonHome, LV_BTN_STATE_PR, "F:/bmp_zero.bin"); + lv_imgbtn_set_style(buttonHome, LV_BTN_STATE_PR, &tft_style_label_pre); + lv_imgbtn_set_style(buttonHome, LV_BTN_STATE_REL, &tft_style_label_rel); + + lv_obj_set_event_cb_mks(buttonLevel, event_handler, ID_T_LEVELING, NULL, 0); + lv_imgbtn_set_src(buttonLevel, LV_BTN_STATE_REL, "F:/bmp_leveling.bin"); + lv_imgbtn_set_src(buttonLevel, LV_BTN_STATE_PR, "F:/bmp_leveling.bin"); + lv_imgbtn_set_style(buttonLevel, LV_BTN_STATE_PR, &tft_style_label_pre); + lv_imgbtn_set_style(buttonLevel, LV_BTN_STATE_REL, &tft_style_label_rel); + + lv_obj_set_event_cb_mks(buttonFilament, event_handler,ID_T_FILAMENT,NULL,0); + lv_imgbtn_set_src(buttonFilament, LV_BTN_STATE_REL, "F:/bmp_filamentchange.bin"); + lv_imgbtn_set_src(buttonFilament, LV_BTN_STATE_PR, "F:/bmp_filamentchange.bin"); + lv_imgbtn_set_style(buttonFilament, LV_BTN_STATE_PR, &tft_style_label_pre); + lv_imgbtn_set_style(buttonFilament, LV_BTN_STATE_REL, &tft_style_label_rel); + + lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_T_RETURN, NULL, 0); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_return.bin"); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_return.bin"); + lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); + lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); lv_obj_set_pos(buttonPreHeat, INTERVAL_V, titleHeight); lv_obj_set_pos(buttonExtrusion, BTN_X_PIXEL + INTERVAL_V * 2, titleHeight); lv_obj_set_pos(buttonMove, BTN_X_PIXEL * 2 + INTERVAL_V * 3, titleHeight); lv_obj_set_pos(buttonHome, BTN_X_PIXEL * 3 + INTERVAL_V * 4, titleHeight); lv_obj_set_pos(buttonLevel, INTERVAL_V, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - //lv_obj_set_pos(buttonFilament,BTN_X_PIXEL+INTERVAL_V*2,BTN_Y_PIXEL+INTERVAL_H+titleHeight); + lv_obj_set_pos(buttonFilament,BTN_X_PIXEL+INTERVAL_V*2,BTN_Y_PIXEL+INTERVAL_H+titleHeight); //lv_obj_set_pos(buttonMore,BTN_X_PIXEL*2+INTERVAL_V*3, BTN_Y_PIXEL+INTERVAL_H+titleHeight); lv_obj_set_pos(buttonBack, BTN_X_PIXEL * 3 + INTERVAL_V * 4, BTN_Y_PIXEL + INTERVAL_H + titleHeight); - /*Create a label on the Image button*/ + // Create labels on the image buttons lv_btn_set_layout(buttonPreHeat, LV_LAYOUT_OFF); lv_btn_set_layout(buttonExtrusion, LV_LAYOUT_OFF); lv_btn_set_layout(buttonMove, LV_LAYOUT_OFF); lv_btn_set_layout(buttonHome, LV_LAYOUT_OFF); lv_btn_set_layout(buttonLevel, LV_LAYOUT_OFF); - //lv_btn_set_layout(buttonFilament, LV_LAYOUT_OFF); + lv_btn_set_layout(buttonFilament, LV_LAYOUT_OFF); //lv_btn_set_layout(buttonMore, LV_LAYOUT_OFF); lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); - lv_obj_t * labelPreHeat = lv_label_create(buttonPreHeat, NULL); - lv_obj_t * labelExtrusion = lv_label_create(buttonExtrusion, NULL); - lv_obj_t * label_Move = lv_label_create(buttonMove, NULL); - lv_obj_t * label_Home = lv_label_create(buttonHome, NULL); - lv_obj_t * label_Level = lv_label_create(buttonLevel, NULL); - //lv_obj_t * label_Filament = lv_label_create(buttonFilament, NULL); - //lv_obj_t * label_More = lv_label_create(buttonMore, NULL); - lv_obj_t * label_Back = lv_label_create(buttonBack, NULL); + lv_obj_t *labelPreHeat = lv_label_create(buttonPreHeat, NULL); + lv_obj_t *labelExtrusion = lv_label_create(buttonExtrusion, NULL); + lv_obj_t *label_Move = lv_label_create(buttonMove, NULL); + lv_obj_t *label_Home = lv_label_create(buttonHome, NULL); + lv_obj_t *label_Level = lv_label_create(buttonLevel, NULL); + lv_obj_t *label_Filament = lv_label_create(buttonFilament, NULL); + //lv_obj_t *label_More = lv_label_create(buttonMore, NULL); + lv_obj_t *label_Back = lv_label_create(buttonBack, NULL); if (gCfgItems.multiple_language != 0) { lv_label_set_text(labelPreHeat, tool_menu.preheat); @@ -242,17 +249,11 @@ void lv_draw_tool(void) { lv_label_set_text(label_Home, tool_menu.home); lv_obj_align(label_Home, buttonHome, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - /* - if (gCfgItems.leveling_mode != 2) { - lv_label_set_text(label_Level, gCfgItems.leveling_mode == 1 ? tool_menu.autoleveling : tool_menu.leveling); - lv_obj_align(label_Level, buttonLevel, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - } - */ lv_label_set_text(label_Level, tool_menu.TERN(AUTO_BED_LEVELING_BILINEAR, autoleveling, leveling)); lv_obj_align(label_Level, buttonLevel, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); - //lv_label_set_text(label_Filament, tool_menu.filament); - //lv_obj_align(label_Filament, buttonFilament, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); + lv_label_set_text(label_Filament, tool_menu.filament); + lv_obj_align(label_Filament, buttonFilament, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); //lv_label_set_text(label_More, tool_menu.more); //lv_obj_align(label_More, buttonMore, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); @@ -260,8 +261,24 @@ void lv_draw_tool(void) { lv_label_set_text(label_Back, common_menu.text_back); lv_obj_align(label_Back, buttonBack, LV_ALIGN_IN_BOTTOM_MID, 0, BUTTON_TEXT_Y_OFFSET); } + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonPreHeat); + lv_group_add_obj(g, buttonExtrusion); + lv_group_add_obj(g, buttonMove); + lv_group_add_obj(g, buttonHome); + lv_group_add_obj(g, buttonLevel); + lv_group_add_obj(g, buttonFilament); + lv_group_add_obj(g, buttonBack); + } + #endif } -void lv_clear_tool() { lv_obj_del(scr); } +void lv_clear_tool() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} #endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_tool.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_tool.h index 14be3bce4f..8a033e2c40 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_tool.h +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_tool.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus -extern "C" { /* C-declarations for C++ */ + extern "C" { /* C-declarations for C++ */ #endif extern void lv_draw_tool(void); @@ -30,5 +30,5 @@ extern void lv_clear_tool(); //extern void disp_temp_ready_print(); #ifdef __cplusplus -} /* C-declarations for C++ */ + } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_ui.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_ui.cpp index ff9d0518d3..922f6a2dc7 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_ui.cpp +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_ui.cpp @@ -49,14 +49,14 @@ #include "../../../../feature/pause.h" #endif -W25QXXFlash W25QXX; CFG_ITMES gCfgItems; UI_CFG uiCfg; DISP_STATE_STACK disp_state_stack; DISP_STATE disp_state = MAIN_UI; DISP_STATE last_disp_state; PRINT_TIME print_time; -value_state value; +num_key_value_state value; +keyboard_value_state keyboard_value; uint32_t To_pre_view; uint8_t gcode_preview_over; @@ -74,6 +74,14 @@ extern uint8_t bmp_public_buf[17 * 1024]; extern void LCD_IO_WriteData(uint16_t RegValue); +static const char custom_gcode_command[][100] = { + "G28\nG29\nM500", + "G28", + "G28", + "G28", + "G28" +}; + lv_point_t line_points[4][2] = { {{PARA_UI_POS_X, PARA_UI_POS_Y + PARA_UI_SIZE_Y}, {TFT_WIDTH, PARA_UI_POS_Y + PARA_UI_SIZE_Y}}, {{PARA_UI_POS_X, PARA_UI_POS_Y*2 + PARA_UI_SIZE_Y}, {TFT_WIDTH, PARA_UI_POS_Y*2 + PARA_UI_SIZE_Y}}, @@ -109,22 +117,58 @@ void gCfgItems_init() { #elif LCD_LANGUAGE == pt gCfgItems.language = LANG_PORTUGUESE; #endif - gCfgItems.leveling_mode = 0; - gCfgItems.from_flash_pic = 0; - gCfgItems.curFilesize = 0; - gCfgItems.finish_power_off = 0; - gCfgItems.pause_reprint = 0; - gCfgItems.pausePosX = -1; - gCfgItems.pausePosY = -1; - gCfgItems.pausePosZ = 5; + gCfgItems.leveling_mode = 0; + gCfgItems.from_flash_pic = 0; + gCfgItems.curFilesize = 0; + gCfgItems.finish_power_off = 0; + gCfgItems.pause_reprint = 0; + gCfgItems.pausePosX = -1; + gCfgItems.pausePosY = -1; + gCfgItems.pausePosZ = 5; + gCfgItems.levelingPos[0][0] = X_MIN_POS + 30; + gCfgItems.levelingPos[0][1] = Y_MIN_POS + 30; + gCfgItems.levelingPos[1][0] = X_MAX_POS - 30; + gCfgItems.levelingPos[1][1] = Y_MIN_POS + 30; + gCfgItems.levelingPos[2][0] = X_MAX_POS - 30; + gCfgItems.levelingPos[2][1] = Y_MAX_POS - 30; + gCfgItems.levelingPos[3][0] = X_MIN_POS + 30; + gCfgItems.levelingPos[3][1] = Y_MAX_POS - 30; + gCfgItems.levelingPos[4][0] = X_BED_SIZE / 2; + gCfgItems.levelingPos[4][1] = Y_BED_SIZE / 2; + gCfgItems.cloud_enable = true; + #if ENABLED(USE_WIFI_FUNCTION) + gCfgItems.wifi_mode_sel = STA_MODEL; + gCfgItems.fileSysType = FILE_SYS_SD; + gCfgItems.wifi_type = ESP_WIFI; + #endif + gCfgItems.filamentchange_load_length = 200; + gCfgItems.filamentchange_load_speed = 1000; + gCfgItems.filamentchange_unload_length = 200; + gCfgItems.filamentchange_unload_speed = 1000; + gCfgItems.filament_limit_temper = 200; + + gCfgItems.encoder_enable = true; + W25QXX.SPI_FLASH_BufferRead((uint8_t *)&gCfgItems.spi_flash_flag, VAR_INF_ADDR, sizeof(gCfgItems.spi_flash_flag)); - if (gCfgItems.spi_flash_flag == GCFG_FLAG_VALUE) { + if (gCfgItems.spi_flash_flag == FLASH_INF_VALID_FLAG) { W25QXX.SPI_FLASH_BufferRead((uint8_t *)&gCfgItems, VAR_INF_ADDR, sizeof(gCfgItems)); } else { - gCfgItems.spi_flash_flag = GCFG_FLAG_VALUE; + gCfgItems.spi_flash_flag = FLASH_INF_VALID_FLAG; W25QXX.SPI_FLASH_SectorErase(VAR_INF_ADDR); W25QXX.SPI_FLASH_BufferWrite((uint8_t *)&gCfgItems, VAR_INF_ADDR, sizeof(gCfgItems)); + //init gcode command + W25QXX.SPI_FLASH_BufferWrite((uint8_t *)&custom_gcode_command[0], AUTO_LEVELING_COMMAND_ADDR, 100); + W25QXX.SPI_FLASH_BufferWrite((uint8_t *)&custom_gcode_command[1], OTHERS_COMMAND_ADDR_1, 100); + W25QXX.SPI_FLASH_BufferWrite((uint8_t *)&custom_gcode_command[2], OTHERS_COMMAND_ADDR_2, 100); + W25QXX.SPI_FLASH_BufferWrite((uint8_t *)&custom_gcode_command[3], OTHERS_COMMAND_ADDR_3, 100); + W25QXX.SPI_FLASH_BufferWrite((uint8_t *)&custom_gcode_command[4], OTHERS_COMMAND_ADDR_4, 100); + } + + const byte rot = TERN0(GRAPHICAL_TFT_ROTATE_180, 0xEE); + if (gCfgItems.disp_rotation_180 != rot) { + gCfgItems.disp_rotation_180 = rot; + update_spi_flash(); } uiCfg.F[0] = 'N'; @@ -135,11 +179,6 @@ void gCfgItems_init() { W25QXX.SPI_FLASH_BufferWrite(uiCfg.F,REFLSHE_FLGA_ADD,4); } -void gCfg_to_spiFlah() { - W25QXX.SPI_FLASH_SectorErase(VAR_INF_ADDR); - W25QXX.SPI_FLASH_BufferWrite((uint8_t *)&gCfgItems, VAR_INF_ADDR, sizeof(gCfgItems)); -} - void ui_cfg_init() { uiCfg.curTempType = 0; uiCfg.curSprayerChoose = 0; @@ -151,12 +190,81 @@ void ui_cfg_init() { uiCfg.move_dist = 1; uiCfg.moveSpeed = 3000; uiCfg.stepPrintSpeed = 10; + uiCfg.command_send = 0; + uiCfg.dialogType = 0; + uiCfg.filament_heat_completed_load = 0; + uiCfg.filament_rate = 0; + uiCfg.filament_loading_completed = 0; + uiCfg.filament_unloading_completed = 0; + uiCfg.filament_loading_time_flg = 0; + uiCfg.filament_loading_time_cnt = 0; + uiCfg.filament_unloading_time_flg = 0; + uiCfg.filament_unloading_time_cnt = 0; + + #if ENABLED(USE_WIFI_FUNCTION) + memset(&wifiPara, 0, sizeof(wifiPara)); + memset(&ipPara, 0, sizeof(ipPara)); + strcpy(wifiPara.ap_name, WIFI_AP_NAME); + strcpy(wifiPara.keyCode, WIFI_KEY_CODE); + //client + strcpy(ipPara.ip_addr, IP_ADDR); + strcpy(ipPara.mask, IP_MASK); + strcpy(ipPara.gate, IP_GATE); + strcpy(ipPara.dns, IP_DNS); + + ipPara.dhcp_flag = IP_DHCP_FLAG; + + //AP + strcpy(ipPara.dhcpd_ip, AP_IP_ADDR); + strcpy(ipPara.dhcpd_mask, AP_IP_MASK); + strcpy(ipPara.dhcpd_gate, AP_IP_GATE); + strcpy(ipPara.dhcpd_dns, AP_IP_DNS); + strcpy(ipPara.start_ip_addr, IP_START_IP); + strcpy(ipPara.end_ip_addr, IP_END_IP); + + ipPara.dhcpd_flag = AP_IP_DHCP_FLAG; + + strcpy((char*)uiCfg.cloud_hostUrl, "baizhongyun.cn"); + uiCfg.cloud_port = 10086; + #endif + + uiCfg.filament_loading_time = (uint32_t)((gCfgItems.filamentchange_load_length * 60.0 / gCfgItems.filamentchange_load_speed) + 0.5); + uiCfg.filament_unloading_time = (uint32_t)((gCfgItems.filamentchange_unload_length * 60.0 / gCfgItems.filamentchange_unload_speed) + 0.5); } void update_spi_flash() { + uint8_t command_buf[512]; + + W25QXX.init(SPI_QUARTER_SPEED); + //read back the gcode command befor erase spi flash + W25QXX.SPI_FLASH_BufferRead((uint8_t *)&command_buf, GCODE_COMMAND_ADDR, sizeof(command_buf)); + W25QXX.SPI_FLASH_SectorErase(VAR_INF_ADDR); + W25QXX.SPI_FLASH_BufferWrite((uint8_t *)&gCfgItems, VAR_INF_ADDR, sizeof(gCfgItems)); + W25QXX.SPI_FLASH_BufferWrite((uint8_t *)&command_buf, GCODE_COMMAND_ADDR, sizeof(command_buf)); +} + +void update_gcode_command(int addr,uint8_t *s) { + uint8_t command_buf[512]; + W25QXX.init(SPI_QUARTER_SPEED); + //read back the gcode command befor erase spi flash + W25QXX.SPI_FLASH_BufferRead((uint8_t *)&command_buf, GCODE_COMMAND_ADDR, sizeof(command_buf)); W25QXX.SPI_FLASH_SectorErase(VAR_INF_ADDR); W25QXX.SPI_FLASH_BufferWrite((uint8_t *)&gCfgItems, VAR_INF_ADDR, sizeof(gCfgItems)); + switch (addr) { + case AUTO_LEVELING_COMMAND_ADDR: memcpy(&command_buf[0*100], s, 100); break; + case OTHERS_COMMAND_ADDR_1: memcpy(&command_buf[1*100], s, 100); break; + case OTHERS_COMMAND_ADDR_2: memcpy(&command_buf[2*100], s, 100); break; + case OTHERS_COMMAND_ADDR_3: memcpy(&command_buf[3*100], s, 100); break; + case OTHERS_COMMAND_ADDR_4: memcpy(&command_buf[4*100], s, 100); break; + default: break; + } + W25QXX.SPI_FLASH_BufferWrite((uint8_t *)&command_buf, GCODE_COMMAND_ADDR, sizeof(command_buf)); +} + +void get_gcode_command(int addr,uint8_t *d) { + W25QXX.init(SPI_QUARTER_SPEED); + W25QXX.SPI_FLASH_BufferRead((uint8_t *)d, addr, 100); } lv_style_t tft_style_scr; @@ -170,6 +278,13 @@ lv_style_t style_num_key_pre; lv_style_t style_num_key_rel; lv_style_t style_num_text; +lv_style_t style_sel_text; + +lv_style_t style_para_value; +lv_style_t style_para_back; + +lv_style_t lv_bar_style_indic; + void tft_style_init() { lv_style_copy(&tft_style_scr, &lv_style_scr); tft_style_scr.body.main_color = LV_COLOR_BACKGROUND; @@ -198,12 +313,13 @@ void tft_style_init() { tft_style_label_rel.text.letter_space = 0; tft_style_label_pre.text.line_space = -5; tft_style_label_rel.text.line_space = -5; + lv_style_copy(&style_para_value_pre, &lv_style_scr); lv_style_copy(&style_para_value_rel, &lv_style_scr); style_para_value_pre.body.main_color = LV_COLOR_BACKGROUND; style_para_value_pre.body.grad_color = LV_COLOR_BACKGROUND; - style_para_value_pre.text.color = LV_COLOR_BLACK; - style_para_value_pre.text.sel_color = LV_COLOR_BLACK; + style_para_value_pre.text.color = LV_COLOR_TEXT; + style_para_value_pre.text.sel_color = LV_COLOR_TEXT; style_para_value_rel.body.main_color = LV_COLOR_BACKGROUND; style_para_value_rel.body.grad_color = LV_COLOR_BACKGROUND; style_para_value_rel.text.color = LV_COLOR_BLACK; @@ -216,6 +332,7 @@ void tft_style_init() { style_para_value_rel.text.letter_space = 0; style_para_value_pre.text.line_space = -5; style_para_value_rel.text.line_space = -5; + lv_style_copy(&style_num_key_pre, &lv_style_scr); lv_style_copy(&style_num_key_rel, &lv_style_scr); style_num_key_pre.body.main_color = LV_COLOR_KEY_BACKGROUND; @@ -251,10 +368,48 @@ void tft_style_init() { style_num_text.text.letter_space = 0; style_num_text.text.line_space = -5; + lv_style_copy(&style_sel_text, &lv_style_scr); + style_sel_text.body.main_color = LV_COLOR_BACKGROUND; + style_sel_text.body.grad_color = LV_COLOR_BACKGROUND; + style_sel_text.text.color = LV_COLOR_YELLOW; + style_sel_text.text.sel_color = LV_COLOR_YELLOW; + style_sel_text.text.font = &gb2312_puhui32; + style_sel_text.line.width = 0; + style_sel_text.text.letter_space = 0; + style_sel_text.text.line_space = -5; lv_style_copy(&style_line, &lv_style_plain); style_line.line.color = LV_COLOR_MAKE(0x49, 0x54, 0xff); style_line.line.width = 1; style_line.line.rounded = 1; + + lv_style_copy(&style_para_value, &lv_style_plain); + style_para_value.body.border.color = LV_COLOR_BACKGROUND; + style_para_value.body.border.width = 1; + style_para_value.body.main_color = LV_COLOR_WHITE; + style_para_value.body.grad_color = LV_COLOR_WHITE; + style_para_value.body.shadow.width = 0; + style_para_value.body.radius = 3; + style_para_value.text.color = LV_COLOR_BLACK; + style_para_value.text.font = &TERN(HAS_SPI_FLASH_FONT, gb2312_puhui32, lv_font_roboto_22); + + lv_style_copy(&style_para_back, &lv_style_plain); + style_para_back.body.border.color = LV_COLOR_BACKGROUND; + style_para_back.body.border.width = 1; + style_para_back.body.main_color = TFT_LV_PARA_BACK_BODY_COLOR; + style_para_back.body.grad_color = TFT_LV_PARA_BACK_BODY_COLOR; + style_para_back.body.shadow.width = 0; + style_para_back.body.radius = 3; + style_para_back.text.color = LV_COLOR_WHITE; + style_para_back.text.font = &TERN(HAS_SPI_FLASH_FONT, gb2312_puhui32, lv_font_roboto_22); + + lv_style_copy(&lv_bar_style_indic, &lv_style_pretty_color); + lv_bar_style_indic.text.color = lv_color_hex3(0xADF); + lv_bar_style_indic.image.color = lv_color_hex3(0xADF); + lv_bar_style_indic.line.color = lv_color_hex3(0xADF); + lv_bar_style_indic.body.main_color = lv_color_hex3(0xADF); + lv_bar_style_indic.body.grad_color = lv_color_hex3(0xADF); + lv_bar_style_indic.body.border.color = lv_color_hex3(0xADF); + } #define MAX_TITLE_LEN 28 @@ -361,15 +516,14 @@ char *getDispText(int index) { case BIND_UI: strcpy(public_buf_l, cloud_menu.title); break; - case ZOFFSET_UI: - strcpy(public_buf_l, zoffset_menu.title); - break; case TOOL_UI: strcpy(public_buf_l, tool_menu.title); break; case WIFI_LIST_UI: - //strcpy(public_buf_l, list_menu.title); - break; + #if ENABLED(USE_WIFI_FUNCTION) + strcpy(public_buf_l, list_menu.title); + break; + #endif case MACHINE_PARA_UI: strcpy(public_buf_l, MachinePara_menu.title); break; @@ -504,7 +658,7 @@ char *creat_title_text() { #if ENABLED(TFT_LVGL_UI_SPI) SPI_TFT.SetWindows(xpos_pixel, ypos_pixel + row, 200, 1); #else - ili9320_SetWindows(xpos_pixel, ypos_pixel + row, 200, 1); + LCD_setWindowArea(xpos_pixel, ypos_pixel + row, 200, 1); LCD_WriteRAM_Prepare(); #endif @@ -583,10 +737,10 @@ char *creat_title_text() { //saved_feedrate_percentage = feedrate_percentage; planner.flow_percentage[0] = 100; planner.e_factor[0] = planner.flow_percentage[0] * 0.01; - if (EXTRUDERS == 2) { + #if HAS_MULTI_EXTRUDER planner.flow_percentage[1] = 100; planner.e_factor[1] = planner.flow_percentage[1] * 0.01; - } + #endif card.startFileprint(); TERN_(POWER_LOSS_RECOVERY, recovery.prepare()); once_flag = 0; @@ -616,7 +770,7 @@ char *creat_title_text() { #if ENABLED(TFT_LVGL_UI_SPI) SPI_TFT.SetWindows(xpos_pixel, ypos_pixel + row, 200, 1); #else - ili9320_SetWindows(xpos_pixel, ypos_pixel + row, 200, 1); + LCD_setWindowArea(xpos_pixel, ypos_pixel + row, 200, 1); LCD_WriteRAM_Prepare(); #endif @@ -715,10 +869,10 @@ char *creat_title_text() { //saved_feedrate_percentage = feedrate_percentage; planner.flow_percentage[0] = 100; planner.e_factor[0] = planner.flow_percentage[0] * 0.01; - if (EXTRUDERS == 2) { + #if HAS_MULTI_EXTRUDER planner.flow_percentage[1] = 100; planner.e_factor[1] = planner.flow_percentage[1] * 0.01; - } + #endif card.startFileprint(); TERN_(POWER_LOSS_RECOVERY, recovery.prepare()); once_flag = 0; @@ -734,17 +888,17 @@ char *creat_title_text() { void Draw_default_preview(int xpos_pixel, int ypos_pixel, uint8_t sel) { int index; int y_off = 0; - + W25QXX.init(SPI_QUARTER_SPEED); for (index = 0; index < 10; index++) { // 200*200 #if HAS_BAK_VIEW_IN_FLASH if (sel == 1) { flash_view_Read(bmp_public_buf, 8000); // 20k } else { - default_view_Read(bmp_public_buf, DEFAULT_VIEW_MAX_SIZE / 10); // 20k + default_view_Read(bmp_public_buf, DEFAULT_VIEW_MAX_SIZE / 10); // 8k } #else - default_view_Read(bmp_public_buf, DEFAULT_VIEW_MAX_SIZE / 10); // 20k + default_view_Read(bmp_public_buf, DEFAULT_VIEW_MAX_SIZE / 10); // 8k #endif #if ENABLED(TFT_LVGL_UI_SPI) @@ -755,7 +909,7 @@ char *creat_title_text() { uint16_t temp_p; int i = 0; uint16_t *p_index; - ili9320_SetWindows(xpos_pixel, y_off * 20 + ypos_pixel, 200, 20); // 200*200 + LCD_setWindowArea(xpos_pixel, y_off * 20 + ypos_pixel, 200, 20); // 200*200 LCD_WriteRAM_Prepare(); @@ -905,29 +1059,28 @@ void GUI_RefreshPage() { */ break; - case WIFI_UI: - /* - if (wifi_refresh_flg == 1) { - disp_wifi_state(); - wifi_refresh_flg = 0; - } - */ - break; + #if ENABLED(USE_WIFI_FUNCTION) + case WIFI_UI: + if (temperature_change_frequency == 1) { + disp_wifi_state(); + temperature_change_frequency = 0; + } + break; + #endif + case BIND_UI: /*refresh_bind_ui();*/ break; case FILAMENTCHANGE_UI: - /* if (temperature_change_frequency) { temperature_change_frequency = 0; - disp_filament_sprayer_temp(); + disp_filament_temp(); } - */ break; case DIALOG_UI: - /*filament_dialog_handle(); - wifi_scan_handle();*/ + filament_dialog_handle(); + TERN_(USE_WIFI_FUNCTION, wifi_scan_handle()); break; case MESHLEVELING_UI: /*disp_zpos();*/ @@ -935,66 +1088,68 @@ void GUI_RefreshPage() { case HARDWARE_TEST_UI: break; case WIFI_LIST_UI: - /* - if (wifi_refresh_flg == 1) { - disp_wifi_list(); - wifi_refresh_flg = 0; - } - */ + #if ENABLED(USE_WIFI_FUNCTION) + if (printing_rate_update_flag == 1) { + disp_wifi_list(); + printing_rate_update_flag = 0; + } + #endif break; case KEY_BOARD_UI: /*update_password_disp(); update_join_state_disp();*/ break; - case TIPS_UI: - /* - switch (tips_type) { - case TIPS_TYPE_JOINING: - if (wifi_link_state == WIFI_CONNECTED && strcmp((const char *)wifi_list.wifiConnectedName, (const char *)wifi_list.wifiName[wifi_list.nameIndex]) == 0) { - tips_disp.timer = TIPS_TIMER_STOP; - tips_disp.timer_count = 0; - Clear_Tips(); - tips_type = TIPS_TYPE_WIFI_CONECTED; - draw_Tips(); - } - if (tips_disp.timer_count >= 30) { - tips_disp.timer = TIPS_TIMER_STOP; - tips_disp.timer_count = 0; - Clear_Tips(); - tips_type = TIPS_TYPE_TAILED_JOIN; - draw_Tips(); - } - break; - case TIPS_TYPE_TAILED_JOIN: - if (tips_disp.timer_count >= 3) { - tips_disp.timer = TIPS_TIMER_STOP; - tips_disp.timer_count = 0; - last_disp_state = TIPS_UI; - Clear_Tips(); - draw_Wifi_list(); - } - break; - case TIPS_TYPE_WIFI_CONECTED: - if (tips_disp.timer_count >= 3) { - tips_disp.timer = TIPS_TIMER_STOP; - tips_disp.timer_count = 0; - - last_disp_state = TIPS_UI; - Clear_Tips(); - draw_Wifi(); - } - break; - default: break; - } - */ - break; + #if ENABLED(USE_WIFI_FUNCTION) + case WIFI_TIPS_UI: + switch (wifi_tips_type) { + case TIPS_TYPE_JOINING: + if (wifi_link_state == WIFI_CONNECTED && strcmp((const char *)wifi_list.wifiConnectedName,(const char *)wifi_list.wifiName[wifi_list.nameIndex]) == 0) { + tips_disp.timer = TIPS_TIMER_STOP; + tips_disp.timer_count = 0; + + lv_clear_wifi_tips(); + wifi_tips_type = TIPS_TYPE_WIFI_CONECTED; + lv_draw_wifi_tips(); + + } + if (tips_disp.timer_count >= 30 * 1000) { + tips_disp.timer = TIPS_TIMER_STOP; + tips_disp.timer_count = 0; + lv_clear_wifi_tips(); + wifi_tips_type = TIPS_TYPE_TAILED_JOIN; + lv_draw_wifi_tips(); + } + break; + case TIPS_TYPE_TAILED_JOIN: + if (tips_disp.timer_count >= 3 * 1000) { + tips_disp.timer = TIPS_TIMER_STOP; + tips_disp.timer_count = 0; + + last_disp_state = WIFI_TIPS_UI; + lv_clear_wifi_tips(); + lv_draw_wifi_list(); + } + break; + case TIPS_TYPE_WIFI_CONECTED: + if (tips_disp.timer_count >= 3 * 1000) { + tips_disp.timer = TIPS_TIMER_STOP; + tips_disp.timer_count = 0; + + last_disp_state = WIFI_TIPS_UI; + lv_clear_wifi_tips(); + lv_draw_wifi(); + } + break; + default: break; + } + break; + #endif + case BABY_STEP_UI: - /* if (temperature_change_frequency == 1) { temperature_change_frequency = 0; disp_z_offset_value(); } - */ break; default: break; } @@ -1061,9 +1216,11 @@ void clear_cur_ui() { case DISK_UI: //Clear_Disk(); break; - case WIFI_UI: - //Clear_Wifi(); - break; + #if ENABLED(USE_WIFI_FUNCTION) + case WIFI_UI: + lv_clear_wifi(); + break; + #endif case MORE_UI: //Clear_more(); break; @@ -1079,15 +1236,20 @@ void clear_cur_ui() { case PRINT_MORE_UI: //Clear_Printmore(); break; + case FILAMENTCHANGE_UI: + lv_clear_filament_change(); + break; case LEVELING_UI: lv_clear_manualLevel(); break; case BIND_UI: //Clear_Bind(); break; - case ZOFFSET_UI: - //Clear_Zoffset(); - break; + #if HAS_BED_PROBE + case NOZZLE_PROBE_OFFSET_UI: + lv_clear_auto_level_offset_settings(); + break; + #endif case TOOL_UI: lv_clear_tool(); break; @@ -1097,15 +1259,19 @@ void clear_cur_ui() { case HARDWARE_TEST_UI: //Clear_Hardwaretest(); break; - case WIFI_LIST_UI: - //Clear_Wifi_list(); - break; + #if ENABLED(USE_WIFI_FUNCTION) + case WIFI_LIST_UI: + lv_clear_wifi_list(); + break; + #endif case KEY_BOARD_UI: - //Clear_Keyboard(); - break; - case TIPS_UI: - //Clear_Tips(); + lv_clear_keyboard(); break; + #if ENABLED(USE_WIFI_FUNCTION) + case WIFI_TIPS_UI: + lv_clear_wifi_tips(); + break; + #endif case MACHINE_PARA_UI: lv_clear_machine_para(); break; @@ -1131,19 +1297,19 @@ void clear_cur_ui() { //Clear_EndstopType(); break; case FILAMENT_SETTINGS_UI: - //Clear_FilamentSettings(); + lv_clear_filament_settings(); break; case LEVELING_SETTIGNS_UI: //Clear_LevelingSettings(); break; case LEVELING_PARA_UI: - //Clear_LevelingPara(); + lv_clear_level_settings(); break; case DELTA_LEVELING_PARA_UI: //Clear_DeltaLevelPara(); break; - case XYZ_LEVELING_PARA_UI: - //Clear_XYZLevelPara(); + case MANUAL_LEVELING_POSIGION_UI: + lv_clear_manual_level_pos_settings(); break; case MAXFEEDRATE_UI: lv_clear_max_feedrate_settings(); @@ -1184,7 +1350,7 @@ void clear_cur_ui() { lv_clear_number_key(); break; case BABY_STEP_UI: - //Clear_babyStep(); + lv_clear_baby_stepping(); break; case PAUSE_POS_UI: lv_clear_pause_position(); @@ -1202,8 +1368,22 @@ void clear_cur_ui() { lv_clear_tmc_step_mode_settings(); break; #endif - default: + #if ENABLED(USE_WIFI_FUNCTION) + case WIFI_SETTINGS_UI: + lv_clear_wifi_settings(); break; + #endif + #if USE_SENSORLESS + case HOMING_SENSITIVITY_UI: + lv_clear_homing_sensitivity_settings(); + break; + #endif + #if HAS_ROTARY_ENCODER + case ENCODER_SETTINGS_UI: + lv_clear_encoder_settings(); + break; + #endif + default: break; } //GUI_Clear(); } @@ -1268,21 +1448,17 @@ void draw_return_ui() { lv_draw_about(); break; - #if tan_mask - case LOG_UI: - //draw_Connect(); - break; - #endif - case CALIBRATE_UI: //draw_calibrate(); break; case DISK_UI: //draw_Disk(); break; - case WIFI_UI: - //draw_Wifi(); - break; + #if ENABLED(USE_WIFI_FUNCTION) + case WIFI_UI: + lv_draw_wifi(); + break; + #endif case MORE_UI: //draw_More(); break; @@ -1290,7 +1466,7 @@ void draw_return_ui() { //draw_printmore(); break; case FILAMENTCHANGE_UI: - //draw_FilamentChange(); + lv_draw_filament_change(); break; case LEVELING_UI: lv_draw_manualLevel(); @@ -1298,13 +1474,11 @@ void draw_return_ui() { case BIND_UI: //draw_bind(); break; - - #if tan_mask - case ZOFFSET_UI: - //draw_Zoffset(); - break; - #endif - + #if HAS_BED_PROBE + case NOZZLE_PROBE_OFFSET_UI: + lv_draw_auto_level_offset_settings(); + break; + #endif case TOOL_UI: lv_draw_tool(); break; @@ -1315,13 +1489,17 @@ void draw_return_ui() { //draw_Hardwaretest(); break; case WIFI_LIST_UI: - //draw_Wifi_list(); + #if ENABLED(USE_WIFI_FUNCTION) + lv_draw_wifi_list(); + #endif break; case KEY_BOARD_UI: - //draw_Keyboard(); + lv_draw_keyboard(); break; - case TIPS_UI: - //draw_Tips(); + case WIFI_TIPS_UI: + #if ENABLED(USE_WIFI_FUNCTION) + lv_draw_wifi_tips(); + #endif break; case MACHINE_PARA_UI: lv_draw_machine_para(); @@ -1348,19 +1526,19 @@ void draw_return_ui() { //draw_EndstopType(); break; case FILAMENT_SETTINGS_UI: - //draw_FilamentSettings(); + lv_draw_filament_settings(); break; case LEVELING_SETTIGNS_UI: //draw_LevelingSettings(); break; case LEVELING_PARA_UI: - //draw_LevelingPara(); + lv_draw_level_settings(); break; case DELTA_LEVELING_PARA_UI: //draw_DeltaLevelPara(); break; - case XYZ_LEVELING_PARA_UI: - //draw_XYZLevelPara(); + case MANUAL_LEVELING_POSIGION_UI: + lv_draw_manual_level_pos_settings(); break; case MAXFEEDRATE_UI: lv_draw_max_feedrate_settings(); @@ -1401,10 +1579,10 @@ void draw_return_ui() { lv_draw_number_key(); break; case DIALOG_UI: - //draw_dialog(DialogType); + //draw_dialog(uiCfg.dialogType); break; case BABY_STEP_UI: - //draw_babyStep(); + lv_draw_baby_stepping(); break; case PAUSE_POS_UI: lv_draw_pause_position(); @@ -1422,6 +1600,21 @@ void draw_return_ui() { lv_draw_tmc_step_mode_settings(); break; #endif + #if ENABLED(USE_WIFI_FUNCTION) + case WIFI_SETTINGS_UI: + lv_draw_wifi_settings(); + break; + #endif + #if USE_SENSORLESS + case HOMING_SENSITIVITY_UI: + lv_draw_homing_sensitivity_settings(); + break; + #endif + #if HAS_ROTARY_ENCODER + case ENCODER_SETTINGS_UI: + lv_draw_encoder_settings(); + break; + #endif default: break; } } @@ -1441,8 +1634,8 @@ void draw_return_ui() { #endif void lv_ex_line(lv_obj_t * line, lv_point_t *points) { - /*Copy the previous line and apply the new style*/ - lv_line_set_points(line, points, 2); /*Set the points*/ + // Copy the previous line and apply the new style + lv_line_set_points(line, points, 2); // Set the points lv_line_set_style(line, LV_LINE_STYLE_MAIN, &style_line); lv_obj_align(line, NULL, LV_ALIGN_IN_TOP_MID, 0, 0); } @@ -1451,18 +1644,29 @@ extern volatile uint32_t systick_uptime_millis; void print_time_count() { if ((systick_uptime_millis % 1000) == 0) - if (print_time.start == 1) print_time.seconds++; + if (print_time.start == 1) print_time.seconds++; } void LV_TASK_HANDLER() { //lv_tick_inc(1); lv_task_handler(); if (mks_test_flag == 0x1e) mks_hardware_test(); + #if HAS_GCODE_PREVIEW disp_pre_gcode(2, 36); #endif + GUI_RefreshPage(); + + #if ENABLED(USE_WIFI_FUNCTION) + get_wifi_commands(); + #endif + //sd_detection(); + + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_update_encoder(); + #endif } #endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_ui.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_ui.h index 595565e1c7..ddc9ea6271 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/draw_ui.h +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_ui.h @@ -21,10 +21,6 @@ */ #pragma once -#ifdef __cplusplus - extern "C" { /* C-declarations for C++ */ -#endif - #include #include @@ -34,7 +30,11 @@ #undef LV_COLOR_BACKGROUND #define LV_COLOR_BACKGROUND LV_COLOR_MAKE(0x1A, 0x1A, 0x1A) // LV_COLOR_MAKE(0x00, 0x00, 0x00) +#define TFT_LV_PARA_BACK_BODY_COLOR LV_COLOR_MAKE(0x4A, 0x52, 0xFF) + +#include "tft_lvgl_configuration.h" #include "tft_multi_language.h" +#include "pic_manager.h" #include "draw_ready_print.h" #include "draw_language.h" #include "draw_set.h" @@ -66,8 +66,33 @@ #include "draw_eeprom_settings.h" #include "draw_max_feedrate_settings.h" #include "draw_tmc_step_mode_settings.h" +#include "draw_level_settings.h" +#include "draw_manual_level_pos_settings.h" +#include "draw_auto_level_offset_settings.h" +#include "draw_filament_change.h" +#include "draw_filament_settings.h" +#include "draw_homing_sensitivity_settings.h" +#include "draw_baby_stepping.h" +#include "draw_keyboard.h" +#include "draw_encoder_settings.h" + +#if ENABLED(USE_WIFI_FUNCTION) + #include "wifiSerial.h" + #include "wifi_module.h" + #include "wifi_upload.h" + #include "draw_wifi_settings.h" + #include "draw_wifi.h" + #include "draw_wifi_list.h" + #include "draw_wifi_tips.h" +#endif #include "../../inc/MarlinConfigPre.h" +#define FILE_SYS_USB 0 +#define FILE_SYS_SD 1 + +#define TICK_CYCLE 1 + +#define PARA_SEL_ICON_TEXT_COLOR LV_COLOR_MAKE(0x4a, 0x52, 0xff); #define TFT35 @@ -100,30 +125,38 @@ #define PREVIEW_LITTLE_PIC_SIZE 40910 // 400*100+9*101+1 #define PREVIEW_SIZE 202720 // (PREVIEW_LITTLE_PIC_SIZE+800*200+201*9+1) - #define GCFG_FLAG_VALUE 0xEE - // machine parameter ui - #define PARA_UI_POS_X 10 - #define PARA_UI_POS_Y 50 + #define PARA_UI_POS_X 10 + #define PARA_UI_POS_Y 50 - #define PARA_UI_SIZE_X 450 - #define PARA_UI_SIZE_Y 40 + #define PARA_UI_SIZE_X 450 + #define PARA_UI_SIZE_Y 40 #define PARA_UI_ARROW_V 12 - #define PARA_UI_BACL_POS_X 400 - #define PARA_UI_BACL_POS_Y 270 + #define PARA_UI_BACL_POS_X 400 + #define PARA_UI_BACL_POS_Y 270 - #define PARA_UI_TURN_PAGE_POS_X 320 - #define PARA_UI_TURN_PAGE_POS_Y 270 + #define PARA_UI_TURN_PAGE_POS_X 320 + #define PARA_UI_TURN_PAGE_POS_Y 270 - #define PARA_UI_VALUE_SIZE_X 370 - #define PARA_UI_VALUE_POS_X 400 + #define PARA_UI_VALUE_SIZE_X 370 + #define PARA_UI_VALUE_POS_X 400 #define PARA_UI_VALUE_V 5 - #define PARA_UI_STATE_POS_X 380 + #define PARA_UI_STATE_POS_X 380 #define PARA_UI_STATE_V 2 + #define PARA_UI_VALUE_SIZE_X_2 200 + #define PARA_UI_VALUE_POS_X_2 320 + #define PARA_UI_VALUE_V_2 5 + + #define PARA_UI_VALUE_BTN_X_SIZE 70 + #define PARA_UI_VALUE_BTN_Y_SIZE 28 + + #define PARA_UI_BACK_BTN_X_SIZE 70 + #define PARA_UI_BACK_BTN_Y_SIZE 40 + #else // ifdef TFT35 #define TFT_WIDTH 320 @@ -131,17 +164,33 @@ #endif // ifdef TFT35 +#ifdef __cplusplus + extern "C" { /* C-declarations for C++ */ +#endif + extern char public_buf_m[100]; extern char public_buf_l[30]; typedef struct { - uint8_t spi_flash_flag; + uint32_t spi_flash_flag; + uint8_t disp_rotation_180; uint8_t multiple_language; uint8_t language; uint8_t leveling_mode; uint8_t from_flash_pic; uint8_t finish_power_off; uint8_t pause_reprint; + uint8_t wifi_mode_sel; + uint8_t fileSysType; + uint8_t wifi_type; + bool cloud_enable; + bool encoder_enable; + int levelingPos[5][2]; + int filamentchange_load_length; + int filamentchange_load_speed; + int filamentchange_unload_length; + int filamentchange_unload_speed; + int filament_limit_temper; float pausePosX; float pausePosY; float pausePosZ; @@ -153,15 +202,42 @@ typedef struct { curSprayerChoose : 3, stepHeat : 4; uint8_t leveling_first_time : 1, - para_ui_page : 1; + para_ui_page:1, + configWifi:1, + command_send:1, + filament_load_heat_flg:1, + filament_heat_completed_load:1, + filament_unload_heat_flg:1, + filament_heat_completed_unload:1; + uint8_t filament_loading_completed:1, + filament_unloading_completed:1, + filament_loading_time_flg:1, + filament_unloading_time_flg:1, + curSprayerChoose_bak:4; + uint8_t wifi_name[32]; + uint8_t wifi_key[64]; + uint8_t cloud_hostUrl[96]; uint8_t extruStep; uint8_t extruSpeed; uint8_t print_state; uint8_t stepPrintSpeed; uint8_t waitEndMoves; + uint8_t dialogType; + uint8_t F[4]; + uint8_t filament_rate; uint16_t moveSpeed; + uint16_t cloud_port; + uint16_t moveSpeed_bak; + uint32_t totalSend; + uint32_t filament_loading_time; + uint32_t filament_unloading_time; + uint32_t filament_loading_time_cnt; + uint32_t filament_unloading_time_cnt; float move_dist; - uint8_t F[4]; + float desireSprayerTempBak; + float current_x_position_bak; + float current_y_position_bak; + float current_e_position_bak; } UI_CFG; typedef enum { @@ -196,12 +272,14 @@ typedef enum { LEVELING_UI, MESHLEVELING_UI, BIND_UI, - ZOFFSET_UI, + #if HAS_BED_PROBE + NOZZLE_PROBE_OFFSET_UI, + #endif TOOL_UI, HARDWARE_TEST_UI, WIFI_LIST_UI, KEY_BOARD_UI, - TIPS_UI, + WIFI_TIPS_UI, MACHINE_PARA_UI, MACHINE_SETTINGS_UI, TEMPERATURE_SETTINGS_UI, @@ -214,7 +292,7 @@ typedef enum { LEVELING_SETTIGNS_UI, LEVELING_PARA_UI, DELTA_LEVELING_PARA_UI, - XYZ_LEVELING_PARA_UI, + MANUAL_LEVELING_POSIGION_UI, MAXFEEDRATE_UI, STEPS_UI, ACCELERATION_UI, @@ -232,7 +310,10 @@ typedef enum { PAUSE_POS_UI, TMC_CURRENT_UI, TMC_MODE_UI, - EEPROM_SETTINGS_UI + EEPROM_SETTINGS_UI, + WIFI_SETTINGS_UI, + HOMING_SENSITIVITY_UI, + ENCODER_SETTINGS_UI } DISP_STATE; typedef struct { @@ -285,10 +366,45 @@ typedef enum { pause_pos_x, pause_pos_y, - pause_pos_z + pause_pos_z, + + level_pos_x1, + level_pos_y1, + level_pos_x2, + level_pos_y2, + level_pos_x3, + level_pos_y3, + level_pos_x4, + level_pos_y4, + level_pos_x5, + level_pos_y5 + #if HAS_BED_PROBE + , + x_offset, + y_offset, + z_offset + #endif + , + load_length, + load_speed, + unload_length, + unload_speed, + filament_temp, + + x_sensitivity, + y_sensitivity, + z_sensitivity, + z2_sensitivity +} num_key_value_state; +extern num_key_value_state value; -}value_state; -extern value_state value; +typedef enum { + wifiName, + wifiPassWord, + wifiConfig, + gcodeCommand +} keyboard_value_state; +extern keyboard_value_state keyboard_value; extern CFG_ITMES gCfgItems; extern UI_CFG uiCfg; @@ -305,6 +421,10 @@ extern lv_style_t style_para_value_rel; extern lv_style_t style_num_key_pre; extern lv_style_t style_num_key_rel; extern lv_style_t style_num_text; +extern lv_style_t style_sel_text; +extern lv_style_t style_para_value; +extern lv_style_t style_para_back; +extern lv_style_t lv_bar_style_indic; extern lv_point_t line_points[4][2]; @@ -314,6 +434,8 @@ extern void tft_style_init(); extern char *creat_title_text(void); extern void preview_gcode_prehandle(char *path); extern void update_spi_flash(); +extern void update_gcode_command(int addr,uint8_t *s); +extern void get_gcode_command(int addr,uint8_t *d); #if HAS_GCODE_PREVIEW extern void disp_pre_gcode(int xpos_pixel, int ypos_pixel); #endif @@ -328,5 +450,5 @@ extern void LV_TASK_HANDLER(); extern void lv_ex_line(lv_obj_t * line, lv_point_t *points); #ifdef __cplusplus -} /* C-declarations for C++ */ + } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi.cpp new file mode 100644 index 0000000000..9cf4555b25 --- /dev/null +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi.cpp @@ -0,0 +1,222 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "lv_conf.h" +#include "draw_ui.h" + +#if ENABLED(USE_WIFI_FUNCTION) + +#include "../../../../../Configuration.h" +#include "../../../../module/temperature.h" + +extern lv_group_t * g; +static lv_obj_t *scr, *wifi_name_text, *wifi_key_text, *wifi_state_text, *wifi_ip_text; + +#define ID_W_RETURN 1 +#define ID_W_CLOUD 2 +#define ID_W_RECONNECT 3 + +static void event_handler(lv_obj_t * obj, lv_event_t event) { + switch (obj->mks_obj_id) { + case ID_W_RETURN: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + clear_cur_ui(); + lv_draw_set(); + } + break; + case ID_W_CLOUD: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + //clear_cur_ui(); + //draw_return_ui(); + } + break; + case ID_W_RECONNECT: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + clear_cur_ui(); + lv_draw_wifi_list(); + } + break; + } +} + +void lv_draw_wifi(void) { + lv_obj_t *buttonBack=NULL,*label_Back=NULL; + lv_obj_t *buttonCloud=NULL,*label_Cloud=NULL; + lv_obj_t *buttonReconnect=NULL,*label_Reconnect=NULL; + if (disp_state_stack._disp_state[disp_state_stack._disp_index] != WIFI_UI) { + disp_state_stack._disp_index++; + disp_state_stack._disp_state[disp_state_stack._disp_index] = WIFI_UI; + } + disp_state = WIFI_UI; + + scr = lv_obj_create(NULL, NULL); + + lv_obj_set_style(scr, &tft_style_scr); + lv_scr_load(scr); + lv_obj_clean(scr); + + lv_obj_t * title = lv_label_create(scr, NULL); + lv_obj_set_style(title, &tft_style_label_rel); + lv_obj_set_pos(title,TITLE_XPOS,TITLE_YPOS); + lv_label_set_text(title, creat_title_text()); + + lv_refr_now(lv_refr_get_disp_refreshing()); + + // Create an Image button + buttonBack = lv_imgbtn_create(scr, NULL); + if (gCfgItems.wifi_mode_sel == STA_MODEL) { + //buttonCloud = lv_imgbtn_create(scr, NULL); + buttonReconnect = lv_imgbtn_create(scr, NULL); + } + + lv_obj_set_event_cb_mks(buttonBack, event_handler,ID_W_RETURN, NULL,0); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_return.bin"); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_return.bin"); + lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); + lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonBack); + #endif + + lv_obj_set_pos(buttonBack,BTN_X_PIXEL*3+INTERVAL_V*4, BTN_Y_PIXEL+INTERVAL_H+titleHeight); + lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); + + if (gCfgItems.wifi_mode_sel == STA_MODEL) { + + lv_obj_set_event_cb_mks(buttonReconnect, event_handler,ID_W_RECONNECT, NULL,0); + lv_imgbtn_set_src(buttonReconnect, LV_BTN_STATE_REL, "F:/bmp_wifi.bin"); + lv_imgbtn_set_src(buttonReconnect, LV_BTN_STATE_PR, "F:/bmp_wifi.bin"); + lv_imgbtn_set_style(buttonReconnect, LV_BTN_STATE_PR, &tft_style_label_pre); + lv_imgbtn_set_style(buttonReconnect, LV_BTN_STATE_REL, &tft_style_label_rel); + + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_add_obj(g, buttonReconnect); + #endif + + lv_obj_set_pos(buttonReconnect,BTN_X_PIXEL*2+INTERVAL_V*3, BTN_Y_PIXEL+INTERVAL_H+titleHeight); + lv_btn_set_layout(buttonReconnect, LV_LAYOUT_OFF); + } + + label_Back = lv_label_create(buttonBack, NULL); + + if (gCfgItems.wifi_mode_sel == STA_MODEL) { + //label_Cloud = lv_label_create(buttonCloud, NULL); + label_Reconnect = lv_label_create(buttonReconnect, NULL); + } + + if (gCfgItems.multiple_language !=0) { + lv_label_set_text(label_Back, common_menu.text_back); + lv_obj_align(label_Back, buttonBack, LV_ALIGN_IN_BOTTOM_MID,0, BUTTON_TEXT_Y_OFFSET); + + if (gCfgItems.wifi_mode_sel == STA_MODEL) { + //lv_label_set_text(label_Cloud, common_menu.text_back); + //lv_obj_align(label_Cloud, buttonCloud, LV_ALIGN_IN_BOTTOM_MID,0, BUTTON_TEXT_Y_OFFSET); + + lv_label_set_text(label_Reconnect, wifi_menu.reconnect); + lv_obj_align(label_Reconnect, buttonReconnect, LV_ALIGN_IN_BOTTOM_MID,0, BUTTON_TEXT_Y_OFFSET); + } + } + + wifi_ip_text = lv_label_create(scr, NULL); + lv_obj_set_style(wifi_ip_text, &tft_style_label_rel); + + wifi_name_text = lv_label_create(scr, NULL); + lv_obj_set_style(wifi_name_text, &tft_style_label_rel); + + wifi_key_text = lv_label_create(scr, NULL); + lv_obj_set_style(wifi_key_text, &tft_style_label_rel); + + wifi_state_text = lv_label_create(scr, NULL); + lv_obj_set_style(wifi_state_text, &tft_style_label_rel); + + disp_wifi_state(); +} + +void disp_wifi_state() { + memset(public_buf_m, 0, sizeof(public_buf_m)); + strcpy(public_buf_m,wifi_menu.ip); + strcat(public_buf_m,ipPara.ip_addr); + lv_label_set_text(wifi_ip_text, public_buf_m); + lv_obj_align(wifi_ip_text, NULL, LV_ALIGN_CENTER,0, -100); + + memset(public_buf_m, 0, sizeof(public_buf_m)); + strcpy(public_buf_m,wifi_menu.wifi); + strcat(public_buf_m,wifiPara.ap_name); + lv_label_set_text(wifi_name_text, public_buf_m); + lv_obj_align(wifi_name_text, NULL, LV_ALIGN_CENTER,0, -70); + + if (wifiPara.mode == AP_MODEL) { + memset(public_buf_m, 0, sizeof(public_buf_m)); + strcpy(public_buf_m,wifi_menu.key); + strcat(public_buf_m,wifiPara.keyCode); + lv_label_set_text(wifi_key_text, public_buf_m); + lv_obj_align(wifi_key_text, NULL, LV_ALIGN_CENTER,0, -40); + + memset(public_buf_m, 0, sizeof(public_buf_m)); + strcpy(public_buf_m,wifi_menu.state_ap); + if (wifi_link_state == WIFI_CONNECTED) + strcat(public_buf_m,wifi_menu.connected); + else if (wifi_link_state == WIFI_NOT_CONFIG) + strcat(public_buf_m,wifi_menu.disconnected); + else + strcat(public_buf_m,wifi_menu.exception); + lv_label_set_text(wifi_state_text, public_buf_m); + lv_obj_align(wifi_state_text, NULL, LV_ALIGN_CENTER,0, -10); + } + else { + ZERO(public_buf_m); + strcpy(public_buf_m, wifi_menu.state_sta); + if (wifi_link_state == WIFI_CONNECTED) + strcat(public_buf_m, wifi_menu.connected); + else if (wifi_link_state == WIFI_NOT_CONFIG) + strcat(public_buf_m, wifi_menu.disconnected); + else + strcat(public_buf_m, wifi_menu.exception); + lv_label_set_text(wifi_state_text, public_buf_m); + lv_obj_align(wifi_state_text, NULL, LV_ALIGN_CENTER,0, -40); + + lv_label_set_text(wifi_key_text, ""); + lv_obj_align(wifi_key_text, NULL, LV_ALIGN_CENTER,0, -10); + } +} + +void lv_clear_wifi() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // USE_WIFI_FUNCTION +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi.h new file mode 100644 index 0000000000..966a84d3b1 --- /dev/null +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi.h @@ -0,0 +1,38 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#ifdef __cplusplus + extern "C" { /* C-declarations for C++ */ +#endif + + +extern void lv_draw_wifi(void); +extern void lv_clear_wifi(); +extern void disp_wifi_state(); + +#ifdef __cplusplus + } /* C-declarations for C++ */ +#endif + + + diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_list.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_list.cpp new file mode 100644 index 0000000000..14fd63f852 --- /dev/null +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_list.cpp @@ -0,0 +1,235 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "lv_conf.h" +#include "draw_ui.h" + +#if ENABLED(USE_WIFI_FUNCTION) + +#include "../../../../../Configuration.h" +#include "../../../../module/temperature.h" + +#define NAME_BTN_X 330 +#define NAME_BTN_Y 48 + +#define MARK_BTN_X 0 +#define MARK_BTN_Y 68 + +WIFI_LIST wifi_list; +list_menu_def list_menu; + +extern lv_group_t * g; +static lv_obj_t * scr; +static lv_obj_t *buttonWifiN[NUMBER_OF_PAGE]; +static lv_obj_t *lableWifiText[NUMBER_OF_PAGE]; +static lv_obj_t *lablePageText; + +#define ID_WL_RETURN 11 +#define ID_WL_DOWN 12 + +static void event_handler(lv_obj_t * obj, lv_event_t event) { + if (obj->mks_obj_id == ID_WL_RETURN) { + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + clear_cur_ui(); + lv_draw_set(); + } + } + else if (obj->mks_obj_id == ID_WL_DOWN) { + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + if (wifi_list.getNameNum > 0) { + if ((wifi_list.nameIndex + NUMBER_OF_PAGE) >= wifi_list.getNameNum) { + wifi_list.nameIndex = 0; + wifi_list.currentWifipage = 1; + } + else { + wifi_list.nameIndex += NUMBER_OF_PAGE; + wifi_list.currentWifipage++; + } + disp_wifi_list(); + } + } + } + else { + for (uint8_t i = 0; i < NUMBER_OF_PAGE; i++) { + if (obj->mks_obj_id == i + 1) { + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + if (wifi_list.getNameNum != 0) { + const bool do_wifi = wifi_link_state == WIFI_CONNECTED && strcmp((const char *)wifi_list.wifiConnectedName, (const char *)wifi_list.wifiName[wifi_list.nameIndex + i]) == 0; + wifi_list.nameIndex += i; + last_disp_state = WIFI_LIST_UI; + lv_clear_wifi_list(); + if (do_wifi) + lv_draw_wifi(); + else { + keyboard_value = wifiConfig; + lv_draw_keyboard(); + } + } + } + } + } + } +} + +void lv_draw_wifi_list(void) { + lv_obj_t *buttonBack = NULL, *buttonDown = NULL; + + if (disp_state_stack._disp_state[disp_state_stack._disp_index] != WIFI_LIST_UI) { + disp_state_stack._disp_index++; + disp_state_stack._disp_state[disp_state_stack._disp_index] = WIFI_LIST_UI; + } + disp_state = WIFI_LIST_UI; + + scr = lv_obj_create(NULL, NULL); + + lv_obj_set_style(scr, &tft_style_scr); + lv_scr_load(scr); + lv_obj_clean(scr); + + lv_obj_t * title = lv_label_create(scr, NULL); + lv_obj_set_style(title, &tft_style_label_rel); + lv_obj_set_pos(title,TITLE_XPOS,TITLE_YPOS); + lv_label_set_text(title, creat_title_text()); + + lv_refr_now(lv_refr_get_disp_refreshing()); + + buttonDown = lv_imgbtn_create(scr, NULL); + buttonBack = lv_imgbtn_create(scr, NULL); + + lv_obj_set_event_cb_mks(buttonDown, event_handler,ID_WL_DOWN,NULL,0); + lv_imgbtn_set_src(buttonDown, LV_BTN_STATE_REL, "F:/bmp_pageDown.bin"); + lv_imgbtn_set_src(buttonDown, LV_BTN_STATE_PR, "F:/bmp_pageDown.bin"); + lv_imgbtn_set_style(buttonDown, LV_BTN_STATE_PR, &tft_style_label_pre); + lv_imgbtn_set_style(buttonDown, LV_BTN_STATE_REL, &tft_style_label_rel); + + lv_obj_set_event_cb_mks(buttonBack, event_handler,ID_WL_RETURN,NULL,0); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_back.bin"); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_back.bin"); + lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); + lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); + + lv_obj_set_pos(buttonDown,OTHER_BTN_XPIEL*3+INTERVAL_V*4,titleHeight+OTHER_BTN_YPIEL+INTERVAL_H); + lv_obj_set_pos(buttonBack,OTHER_BTN_XPIEL*3+INTERVAL_V*4,titleHeight+OTHER_BTN_YPIEL*2+INTERVAL_H*2); + + lv_btn_set_layout(buttonDown, LV_LAYOUT_OFF); + lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); + + for (uint8_t i = 0; i < NUMBER_OF_PAGE; i++) { + buttonWifiN[i] = lv_btn_create(scr, NULL); /*Add a button the current screen*/ + lv_obj_set_pos(buttonWifiN[i], 0,NAME_BTN_Y*i+10+titleHeight); /*Set its position*/ + lv_obj_set_size(buttonWifiN[i], NAME_BTN_X,NAME_BTN_Y); /*Set its size*/ + lv_obj_set_event_cb_mks(buttonWifiN[i], event_handler,(i+1),NULL,0); + lv_btn_set_style(buttonWifiN[i], LV_BTN_STYLE_REL, &tft_style_label_rel); /*Set the button's released style*/ + lv_btn_set_style(buttonWifiN[i], LV_BTN_STYLE_PR, &tft_style_label_pre); /*Set the button's pressed style*/ + lv_btn_set_layout(buttonWifiN[i], LV_LAYOUT_OFF); + lableWifiText[i] = lv_label_create(buttonWifiN[i], NULL); + #if HAS_ROTARY_ENCODER + uint8_t j = 0; + if (gCfgItems.encoder_enable) { + j = wifi_list.nameIndex + i; + if (j < wifi_list.getNameNum) lv_group_add_obj(g, buttonWifiN[i]); + } + #endif + } + + lablePageText = lv_label_create(scr, NULL); + lv_obj_set_style(lablePageText, &tft_style_label_rel); + + wifi_list.nameIndex = 0; + wifi_list.currentWifipage = 1; + + if (wifi_link_state == WIFI_CONNECTED && wifiPara.mode == STA_MODEL) { + memset(wifi_list.wifiConnectedName, 0, sizeof(&wifi_list.wifiConnectedName)); + memcpy(wifi_list.wifiConnectedName, wifiPara.ap_name, sizeof(wifi_list.wifiConnectedName)); + } + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonDown); + lv_group_add_obj(g, buttonBack); + } + #endif + + disp_wifi_list(); +} + +void disp_wifi_list(void) { + int8_t tmpStr[WIFI_NAME_BUFFER_SIZE] = { 0 }; + uint8_t i, j; + + sprintf((char *)tmpStr, list_menu.file_pages, wifi_list.currentWifipage, wifi_list.getPage); + lv_label_set_text(lablePageText, (const char *)tmpStr); + lv_obj_align(lablePageText, NULL, LV_ALIGN_CENTER, 50, -100); + + for (i = 0; i < NUMBER_OF_PAGE; i++) { + memset(tmpStr, 0, sizeof(tmpStr)); + + j = wifi_list.nameIndex + i; + if (j >= wifi_list.getNameNum) { + lv_label_set_text(lableWifiText[i], (const char *)tmpStr); + lv_obj_align(lableWifiText[i], buttonWifiN[i], LV_ALIGN_IN_LEFT_MID, 20, 0); + } + else { + lv_label_set_text(lableWifiText[i], (char const *)wifi_list.wifiName[j]); + lv_obj_align(lableWifiText[i], buttonWifiN[i], LV_ALIGN_IN_LEFT_MID, 20, 0); + + if (wifi_link_state == WIFI_CONNECTED && strcmp((const char *)wifi_list.wifiConnectedName, (const char *)wifi_list.wifiName[j]) == 0) { + lv_btn_set_style(buttonWifiN[i], LV_BTN_STYLE_REL, &style_sel_text); + } + else { + lv_btn_set_style(buttonWifiN[i], LV_BTN_STYLE_REL, &tft_style_label_rel); + } + } + } +} + +void wifi_scan_handle() { + if (uiCfg.dialogType != WIFI_ENABLE_TIPS || uiCfg.command_send != 1) return; + last_disp_state = DIALOG_UI; + lv_clear_dialog(); + if (wifi_link_state == WIFI_CONNECTED && wifiPara.mode != AP_MODEL) + lv_draw_wifi(); + else + lv_draw_wifi_list(); +} + +void lv_clear_wifi_list() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // USE_WIFI_FUNCTION + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_list.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_list.h new file mode 100644 index 0000000000..e2d9275ef9 --- /dev/null +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_list.h @@ -0,0 +1,76 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#ifdef __cplusplus + extern "C" { /* C-declarations for C++ */ +#endif + +extern void lv_draw_wifi_list(); +extern void lv_clear_wifi_list(); +extern void disp_wifi_list(void); +extern void cutWifiName(char *name, int len,char *outStr); +extern void wifi_scan_handle(); + +#define NUMBER_OF_PAGE 5 + +#define WIFI_TOTAL_NUMBER 20 +#define WIFI_NAME_BUFFER_SIZE 33 + +typedef struct { + int8_t getNameNum; + int8_t nameIndex; + int8_t currentWifipage; + int8_t getPage; + int8_t RSSI[WIFI_TOTAL_NUMBER]; + uint8_t wifiName[WIFI_TOTAL_NUMBER][WIFI_NAME_BUFFER_SIZE]; + uint8_t wifiConnectedName[WIFI_NAME_BUFFER_SIZE]; +} WIFI_LIST; +extern WIFI_LIST wifi_list; + +typedef struct list_menu_disp { + const char *title; + const char *file_pages; +} list_menu_def; +extern list_menu_def list_menu; + +typedef struct keyboard_menu_disp { + const char *title; + const char *apply; + const char *password; + const char *letter; + const char *digital; + const char *symbol; + const char *space; +} keyboard_menu_def; +extern keyboard_menu_def keyboard_menu; + +typedef struct tips_menu_disp { + const char *joining; + const char *failedJoin; + const char *wifiConected; +} tips_menu_def; +extern tips_menu_def tips_menu; + +#ifdef __cplusplus + } /* C-declarations for C++ */ +#endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_settings.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_settings.cpp new file mode 100644 index 0000000000..86733470dd --- /dev/null +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_settings.cpp @@ -0,0 +1,299 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "lv_conf.h" +#include "draw_ui.h" + +#if ENABLED(USE_WIFI_FUNCTION) + +#include "../../../../../Configuration.h" +#include "../../../../module/planner.h" + +extern lv_group_t * g; +static lv_obj_t *scr, *labelModelValue = NULL, *buttonModelValue = NULL, *labelCloudValue = NULL; + +#define ID_WIFI_RETURN 1 +#define ID_WIFI_MODEL 2 +#define ID_WIFI_NAME 3 +#define ID_WIFI_PASSWORD 4 +#define ID_WIFI_CLOUD 5 +#define ID_WIFI_CONFIG 6 + +static void event_handler(lv_obj_t * obj, lv_event_t event) { + switch (obj->mks_obj_id) { + case ID_WIFI_RETURN: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + lv_clear_wifi_settings(); + draw_return_ui(); + } + break; + case ID_WIFI_MODEL: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + if (gCfgItems.wifi_mode_sel == AP_MODEL) { + gCfgItems.wifi_mode_sel = STA_MODEL; + lv_label_set_text(labelModelValue, WIFI_STA_TEXT); + lv_obj_align(labelModelValue, buttonModelValue, LV_ALIGN_CENTER,0, 0); + update_spi_flash(); + } + else{ + gCfgItems.wifi_mode_sel = AP_MODEL; + lv_label_set_text(labelModelValue, WIFI_AP_TEXT); + lv_obj_align(labelModelValue, buttonModelValue, LV_ALIGN_CENTER,0, 0); + update_spi_flash(); + } + } + break; + case ID_WIFI_NAME: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + keyboard_value=wifiName; + lv_clear_wifi_settings(); + lv_draw_keyboard(); + } + break; + case ID_WIFI_PASSWORD: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + keyboard_value=wifiPassWord; + lv_clear_wifi_settings(); + lv_draw_keyboard(); + } + break; + case ID_WIFI_CLOUD: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + if (gCfgItems.cloud_enable) { + gCfgItems.cloud_enable = false; + lv_obj_set_event_cb_mks(obj, event_handler,ID_WIFI_CLOUD,"bmp_disable.bin",0); + lv_label_set_text(labelCloudValue, machine_menu.disable); + update_spi_flash(); + } + else { + gCfgItems.cloud_enable = true; + lv_obj_set_event_cb_mks(obj, event_handler,ID_WIFI_CLOUD,"bmp_enable.bin",0); + lv_label_set_text(labelCloudValue, machine_menu.enable); + update_spi_flash(); + } + } + break; + case ID_WIFI_CONFIG: + if (event == LV_EVENT_CLICKED) { + + } + else if (event == LV_EVENT_RELEASED) { + lv_clear_wifi_settings(); + lv_draw_dialog(DIALOG_WIFI_CONFIG_TIPS); + } + break; + } +} + +void lv_draw_wifi_settings(void) { + lv_obj_t *buttonBack = NULL, *label_Back = NULL, *buttonConfig = NULL, *labelConfig = NULL; + lv_obj_t *labelModelText = NULL; + lv_obj_t *labelNameText = NULL, *buttonNameValue = NULL, *labelNameValue = NULL; + lv_obj_t *labelPassWordText = NULL, *buttonPassWordValue = NULL, *labelPassWordValue = NULL; + lv_obj_t *labelCloudText = NULL, *buttonCloudValue = NULL; + lv_obj_t * line1 = NULL, *line2 = NULL, *line3 = NULL, *line4 = NULL; + if (disp_state_stack._disp_state[disp_state_stack._disp_index] != WIFI_SETTINGS_UI) { + disp_state_stack._disp_index++; + disp_state_stack._disp_state[disp_state_stack._disp_index] = WIFI_SETTINGS_UI; + } + disp_state = WIFI_SETTINGS_UI; + + scr = lv_obj_create(NULL, NULL); + + lv_obj_set_style(scr, &tft_style_scr); + lv_scr_load(scr); + lv_obj_clean(scr); + + lv_obj_t * title = lv_label_create(scr, NULL); + lv_obj_set_style(title, &tft_style_label_rel); + lv_obj_set_pos(title,TITLE_XPOS,TITLE_YPOS); + lv_label_set_text(title, machine_menu.WifiConfTitle); + + lv_refr_now(lv_refr_get_disp_refreshing()); + + labelModelText = lv_label_create(scr, NULL); + lv_obj_set_style(labelModelText, &tft_style_label_rel); + lv_obj_set_pos(labelModelText, PARA_UI_POS_X, PARA_UI_POS_Y + 10); + lv_label_set_text(labelModelText, machine_menu.wifiMode); + + buttonModelValue = lv_imgbtn_create(scr, NULL); + lv_obj_set_pos(buttonModelValue,PARA_UI_VALUE_POS_X,PARA_UI_POS_Y+PARA_UI_VALUE_V); + lv_obj_set_event_cb_mks(buttonModelValue, event_handler,ID_WIFI_MODEL, NULL,0); + lv_imgbtn_set_src(buttonModelValue, LV_BTN_STATE_REL, "F:/bmp_blank_sel.bin"); + lv_imgbtn_set_src(buttonModelValue, LV_BTN_STATE_PR, "F:/bmp_blank_sel.bin"); + lv_imgbtn_set_style(buttonModelValue, LV_BTN_STATE_PR, &style_para_value_pre); + lv_imgbtn_set_style(buttonModelValue, LV_BTN_STATE_REL, &style_para_value_pre); + lv_btn_set_layout(buttonModelValue, LV_LAYOUT_OFF); + labelModelValue = lv_label_create(buttonModelValue, NULL); + + line1 = lv_line_create(scr, NULL); + lv_ex_line(line1,line_points[0]); + + labelNameText = lv_label_create(scr, NULL); + lv_obj_set_style(labelNameText, &tft_style_label_rel); + lv_obj_set_pos(labelNameText, PARA_UI_POS_X, PARA_UI_POS_Y * 2 + 10); + + buttonNameValue = lv_btn_create(scr, NULL); + lv_obj_set_pos(buttonNameValue,PARA_UI_VALUE_POS_X,PARA_UI_POS_Y*2+PARA_UI_VALUE_V); + lv_obj_set_size(buttonNameValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonNameValue, event_handler,ID_WIFI_NAME, NULL,0); + lv_btn_set_style(buttonNameValue, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonNameValue, LV_BTN_STYLE_PR, &style_para_value); + labelNameValue = lv_label_create(buttonNameValue, NULL); + + line2 = lv_line_create(scr, NULL); + lv_ex_line(line2,line_points[1]); + + labelPassWordText = lv_label_create(scr, NULL); + lv_obj_set_style(labelPassWordText, &tft_style_label_rel); + lv_obj_set_pos(labelPassWordText, PARA_UI_POS_X, PARA_UI_POS_Y * 3 + 10); + + buttonPassWordValue = lv_btn_create(scr, NULL); + lv_obj_set_pos(buttonPassWordValue,PARA_UI_VALUE_POS_X,PARA_UI_POS_Y*3+PARA_UI_VALUE_V); + lv_obj_set_size(buttonPassWordValue, PARA_UI_VALUE_BTN_X_SIZE, PARA_UI_VALUE_BTN_Y_SIZE); + lv_obj_set_event_cb_mks(buttonPassWordValue, event_handler,ID_WIFI_PASSWORD, NULL,0); + lv_btn_set_style(buttonPassWordValue, LV_BTN_STYLE_REL, &style_para_value); + lv_btn_set_style(buttonPassWordValue, LV_BTN_STYLE_PR, &style_para_value); + labelPassWordValue = lv_label_create(buttonPassWordValue, NULL); + + line3 = lv_line_create(scr, NULL); + lv_ex_line(line3,line_points[2]); + + labelCloudText = lv_label_create(scr, NULL); + lv_obj_set_style(labelCloudText, &tft_style_label_rel); + lv_obj_set_pos(labelCloudText, PARA_UI_POS_X, PARA_UI_POS_Y * 4 + 10); + lv_label_set_text(labelCloudText, machine_menu.wifiCloud); + + buttonCloudValue = lv_imgbtn_create(scr, NULL); + lv_obj_set_pos(buttonCloudValue,PARA_UI_STATE_POS_X,PARA_UI_POS_Y*4+PARA_UI_STATE_V); + if (gCfgItems.cloud_enable) { + lv_imgbtn_set_src(buttonCloudValue, LV_BTN_STATE_REL, "F:/bmp_enable.bin"); + lv_imgbtn_set_src(buttonCloudValue, LV_BTN_STATE_PR, "F:/bmp_enable.bin"); + } + else { + lv_imgbtn_set_src(buttonCloudValue, LV_BTN_STATE_REL, "F:/bmp_disable.bin"); + lv_imgbtn_set_src(buttonCloudValue, LV_BTN_STATE_PR, "F:/bmp_disable.bin"); + } + lv_obj_set_event_cb_mks(buttonCloudValue, event_handler,ID_WIFI_CLOUD, NULL,0); + lv_imgbtn_set_style(buttonCloudValue, LV_BTN_STATE_PR, &tft_style_label_pre); + lv_imgbtn_set_style(buttonCloudValue, LV_BTN_STATE_REL, &tft_style_label_rel); + lv_btn_set_layout(buttonCloudValue, LV_LAYOUT_OFF); + labelCloudValue = lv_label_create(buttonCloudValue, NULL); + + line4 = lv_line_create(scr, NULL); + lv_ex_line(line4,line_points[3]); + + buttonConfig = lv_imgbtn_create(scr, NULL); + lv_obj_set_event_cb_mks(buttonConfig, event_handler,ID_WIFI_CONFIG, NULL,0); + lv_imgbtn_set_src(buttonConfig, LV_BTN_STATE_REL, "F:/bmp_back70x40.bin"); + lv_imgbtn_set_src(buttonConfig, LV_BTN_STATE_PR, "F:/bmp_back70x40.bin"); + lv_imgbtn_set_style(buttonConfig, LV_BTN_STATE_PR, &tft_style_label_pre); + lv_imgbtn_set_style(buttonConfig, LV_BTN_STATE_REL, &tft_style_label_rel); + lv_obj_set_pos(buttonConfig, PARA_UI_TURN_PAGE_POS_X, PARA_UI_TURN_PAGE_POS_Y); + lv_btn_set_layout(buttonConfig, LV_LAYOUT_OFF); + labelConfig = lv_label_create(buttonConfig, NULL); + + buttonBack = lv_imgbtn_create(scr, NULL); + lv_obj_set_event_cb_mks(buttonBack, event_handler, ID_WIFI_RETURN, NULL, 0); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_REL, "F:/bmp_back70x40.bin"); + lv_imgbtn_set_src(buttonBack, LV_BTN_STATE_PR, "F:/bmp_back70x40.bin"); + lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_PR, &tft_style_label_pre); + lv_imgbtn_set_style(buttonBack, LV_BTN_STATE_REL, &tft_style_label_rel); + lv_obj_set_pos(buttonBack, PARA_UI_BACL_POS_X, PARA_UI_BACL_POS_Y); + lv_btn_set_layout(buttonBack, LV_LAYOUT_OFF); + label_Back = lv_label_create(buttonBack, NULL); + + if (gCfgItems.multiple_language !=0) { + if (gCfgItems.wifi_mode_sel == AP_MODEL) { + lv_label_set_text(labelModelValue, WIFI_AP_TEXT); + lv_obj_align(labelModelValue, buttonModelValue, LV_ALIGN_CENTER,0, 0); + } + else { + lv_label_set_text(labelModelValue, WIFI_STA_TEXT); + lv_obj_align(labelModelValue, buttonModelValue, LV_ALIGN_CENTER,0, 0); + } + memset(public_buf_m,0,sizeof(public_buf_m)); + strcat(public_buf_m,machine_menu.wifiName); + strcat(public_buf_m,(const char *)uiCfg.wifi_name); + lv_label_set_text(labelNameText,public_buf_m); + + lv_label_set_text(labelNameValue,machine_menu.wifiEdit); + lv_obj_align(labelNameValue, buttonNameValue, LV_ALIGN_CENTER,0, 0); + + memset(public_buf_m,0,sizeof(public_buf_m)); + strcat(public_buf_m,machine_menu.wifiPassWord); + strcat(public_buf_m,(const char *)uiCfg.wifi_key); + lv_label_set_text(labelPassWordText,public_buf_m); + + lv_label_set_text(labelPassWordValue,machine_menu.wifiEdit); + lv_obj_align(labelPassWordValue, buttonPassWordValue, LV_ALIGN_CENTER,0, 0); + + lv_label_set_text(labelCloudValue, gCfgItems.cloud_enable ? machine_menu.enable : machine_menu.disable); + lv_obj_align(labelCloudValue, buttonCloudValue, LV_ALIGN_CENTER,0, 0); + + lv_label_set_text(labelConfig,machine_menu.wifiConfig); + lv_obj_align(labelConfig, buttonConfig, LV_ALIGN_CENTER,0, 0); + + lv_label_set_text(label_Back, common_menu.text_back); + lv_obj_align(label_Back, buttonBack, LV_ALIGN_CENTER,0, 0); + } + + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) { + lv_group_add_obj(g, buttonModelValue); + lv_group_add_obj(g, buttonNameValue); + lv_group_add_obj(g, buttonPassWordValue); + lv_group_add_obj(g, buttonCloudValue); + lv_group_add_obj(g, buttonConfig); + lv_group_add_obj(g, buttonBack); + } + #endif +} + +void lv_clear_wifi_settings() { + #if HAS_ROTARY_ENCODER + if (gCfgItems.encoder_enable) lv_group_remove_all_objs(g); + #endif + lv_obj_del(scr); +} + +#endif // USE_WIFI_FUNCTION + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_settings.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_settings.h new file mode 100644 index 0000000000..c0d6e0ccdd --- /dev/null +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_settings.h @@ -0,0 +1,36 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#ifdef __cplusplus + extern "C" { /* C-declarations for C++ */ +#endif + +#define WIFI_AP_TEXT "AP" +#define WIFI_STA_TEXT "STA" + +extern void lv_draw_wifi_settings(void); +extern void lv_clear_wifi_settings(); + +#ifdef __cplusplus + } /* C-declarations for C++ */ +#endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_tips.cpp b/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_tips.cpp new file mode 100644 index 0000000000..50fa0aaf99 --- /dev/null +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_tips.cpp @@ -0,0 +1,85 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "lv_conf.h" +#include "draw_ui.h" + +#if ENABLED(USE_WIFI_FUNCTION) + +#include "../../../../../Configuration.h" +#include "../../../../module/temperature.h" + +static lv_obj_t * scr; + +TIPS_TYPE wifi_tips_type; +TIPS_DISP tips_disp; +tips_menu_def tips_menu; + +void lv_draw_wifi_tips(void) { + static lv_obj_t * text_tips,*wifi_name; + + if (disp_state_stack._disp_state[disp_state_stack._disp_index] != WIFI_TIPS_UI) { + disp_state_stack._disp_index++; + disp_state_stack._disp_state[disp_state_stack._disp_index] = WIFI_TIPS_UI; + } + disp_state = WIFI_TIPS_UI; + + scr = lv_obj_create(NULL, NULL); + + lv_obj_set_style(scr, &tft_style_scr); + lv_scr_load(scr); + lv_obj_clean(scr); + lv_refr_now(lv_refr_get_disp_refreshing()); + + text_tips = lv_label_create(scr, NULL); + lv_obj_set_style(text_tips, &tft_style_label_rel); + + wifi_name = lv_label_create(scr, NULL); + lv_obj_set_style(wifi_name, &tft_style_label_rel); + + if (wifi_tips_type == TIPS_TYPE_JOINING) { + lv_label_set_text(text_tips, tips_menu.joining); + lv_obj_align(text_tips, NULL, LV_ALIGN_CENTER,0, -60); + } + else if (wifi_tips_type == TIPS_TYPE_TAILED_JOIN) { + lv_label_set_text(text_tips, tips_menu.failedJoin); + lv_obj_align(text_tips, NULL, LV_ALIGN_CENTER,0, -60); + } + else if (wifi_tips_type == TIPS_TYPE_WIFI_CONECTED) { + lv_label_set_text(text_tips, tips_menu.wifiConected); + lv_obj_align(text_tips, NULL, LV_ALIGN_CENTER,0, -60); + } + + lv_label_set_text(wifi_name, (const char *)wifi_list.wifiName[wifi_list.nameIndex]); + lv_obj_align(wifi_name, NULL, LV_ALIGN_CENTER,0, -20); + + tips_disp.timer = TIPS_TIMER_START; + tips_disp.timer_count = 0; +} + +void lv_clear_wifi_tips() { lv_obj_del(scr); } + +#endif // USE_WIFI_FUNCTION +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_tips.h b/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_tips.h new file mode 100644 index 0000000000..4f81f00a43 --- /dev/null +++ b/Marlin/src/lcd/extui/lib/mks_ui/draw_wifi_tips.h @@ -0,0 +1,51 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#ifdef __cplusplus + extern "C" { /* C-declarations for C++ */ +#endif + + +extern void lv_draw_wifi_tips(void); +extern void lv_clear_wifi_tips(); + +typedef enum { + TIPS_TYPE_JOINING, + TIPS_TYPE_TAILED_JOIN, + TIPS_TYPE_WIFI_CONECTED +} TIPS_TYPE; +extern TIPS_TYPE wifi_tips_type; + +typedef struct { + unsigned char timer; + unsigned int timer_count; +} TIPS_DISP; +extern TIPS_DISP tips_disp; + +#define TIPS_TIMER_START 1 +#define TIPS_TIMER_STOP 0 + +#ifdef __cplusplus + } /* C-declarations for C++ */ +#endif + diff --git a/Marlin/src/lcd/extui/lib/mks_ui/irq_overrid.cpp b/Marlin/src/lcd/extui/lib/mks_ui/irq_overrid.cpp new file mode 100644 index 0000000000..cf64571292 --- /dev/null +++ b/Marlin/src/lcd/extui/lib/mks_ui/irq_overrid.cpp @@ -0,0 +1,69 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "draw_ui.h" + +#if ENABLED(USE_WIFI_FUNCTION) + +#include "wifiSerial.h" + +#include +#include +#include +#include +#include + +#include "../../../../inc/MarlinConfig.h" + +#ifdef __cplusplus + extern "C" { /* C-declarations for C++ */ +#endif + +#define WIFI_IO1_SET() WRITE(WIFI_IO1_PIN, HIGH); +#define WIFI_IO1_RESET() WRITE(WIFI_IO1_PIN, LOW); + +void __irq_usart1(void) { + WIFISERIAL.wifi_usart_irq(USART1_BASE); + if (wifi_link_state == WIFI_TRANS_FILE) { + if (WIFISERIAL.available() == (400)) WIFI_IO1_SET(); + if (WIFISERIAL.wifi_rb_is_full()) { + if (esp_state == TRANSFER_IDLE) esp_state = TRANSFERING; + if (storeRcvData(UART_RX_BUFFER_SIZE)) { + if (wifiTransError.flag != 0x1) WIFI_IO1_RESET(); + } + else { + WIFI_IO1_SET(); + esp_state = TRANSFER_STORE; + } + } + } +} + +#ifdef __cplusplus + } /* C-declarations for C++ */ +#endif + +#endif // USE_WIFI_FUNCTION +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/mks_hardware_test.cpp b/Marlin/src/lcd/extui/lib/mks_ui/mks_hardware_test.cpp index 297ba723de..743863d1f7 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/mks_hardware_test.cpp +++ b/Marlin/src/lcd/extui/lib/mks_ui/mks_hardware_test.cpp @@ -38,7 +38,10 @@ #include "../../../../module/temperature.h" #include "../../../../sd/cardreader.h" -uint8_t pw_det_sta, pw_off_sta, mt_det_sta, mt_det2_sta, mt_det3_sta; +uint8_t pw_det_sta, pw_off_sta, mt_det_sta, mt_det3_sta; +#if PIN_EXISTS(MT_DET_2) + uint8_t mt_det2_sta; +#endif uint8_t endstopx1_sta, endstopx2_sta, endstopy1_sta, endstopy2_sta, endstopz1_sta, endstopz2_sta; void test_gpio_readlevel_L() { #if ENABLED(MKS_TEST) @@ -46,15 +49,17 @@ void test_gpio_readlevel_L() { WRITE(WIFI_IO0_PIN, HIGH); itest = 10000; while (itest--); - pw_det_sta = (READ(POWER_LOSS_PIN) == 0); - pw_off_sta = (READ(PS_ON_PIN) == 0); + pw_det_sta = (READ(MKS_TEST_POWER_LOSS_PIN) == 0); + pw_off_sta = (READ(MKS_TEST_PS_ON_PIN) == 0); mt_det_sta = (READ(MT_DET_1_PIN) == 0); - mt_det2_sta = (READ(MT_DET_2_PIN) == 0); + #if PIN_EXISTS(MT_DET_2) + mt_det2_sta = (READ(MT_DET_2_PIN) == 0); + #endif //mt_det3_sta = (READ(FIL_RUNOUT_3_PIN) == 0); endstopx1_sta = (READ(X_MIN_PIN) == 0); - endstopx2_sta = (READ(X_MAX_PIN) == 0); + //endstopx2_sta = (READ(X_MAX_PIN) == 0); endstopy1_sta = (READ(Y_MIN_PIN) == 0); - endstopy2_sta = (READ(Y_MAX_PIN) == 0); + //endstopy2_sta = (READ(Y_MAX_PIN) == 0); endstopz1_sta = (READ(Z_MIN_PIN) == 0); endstopz2_sta = (READ(Z_MAX_PIN) == 0); #endif @@ -66,15 +71,17 @@ void test_gpio_readlevel_H() { WRITE(WIFI_IO0_PIN, LOW); itest = 10000; while (itest--); - pw_det_sta = (READ(POWER_LOSS_PIN) == 1); - pw_off_sta = (READ(PS_ON_PIN) == 1); + pw_det_sta = (READ(MKS_TEST_POWER_LOSS_PIN) == 1); + pw_off_sta = (READ(MKS_TEST_PS_ON_PIN) == 1); mt_det_sta = (READ(MT_DET_1_PIN) == 1); - mt_det2_sta = (READ(MT_DET_2_PIN) == 1); + #if PIN_EXISTS(MT_DET_2) + mt_det2_sta = (READ(MT_DET_2_PIN) == 1); + #endif //mt_det3_sta = (READ(MT_DET_3_PIN) == 1); endstopx1_sta = (READ(X_MIN_PIN) == 1); - endstopx2_sta = (READ(X_MAX_PIN) == 1); + //endstopx2_sta = (READ(X_MAX_PIN) == 1); endstopy1_sta = (READ(Y_MIN_PIN) == 1); - endstopy2_sta = (READ(Y_MAX_PIN) == 1); + //endstopy2_sta = (READ(Y_MAX_PIN) == 1); endstopz1_sta = (READ(Z_MIN_PIN) == 1); endstopz2_sta = (READ(Z_MAX_PIN) == 1); #endif @@ -83,20 +90,22 @@ void test_gpio_readlevel_H() { void init_test_gpio() { #ifdef MKS_TEST SET_INPUT_PULLUP(X_MIN_PIN); - SET_INPUT_PULLUP(X_MAX_PIN); + //SET_INPUT_PULLUP(X_MAX_PIN); SET_INPUT_PULLUP(Y_MIN_PIN); - SET_INPUT_PULLUP(Y_MAX_PIN); + //SET_INPUT_PULLUP(Y_MAX_PIN); SET_INPUT_PULLUP(Z_MIN_PIN); SET_INPUT_PULLUP(Z_MAX_PIN); SET_OUTPUT(WIFI_IO0_PIN); SET_INPUT_PULLUP(MT_DET_1_PIN); - SET_INPUT_PULLUP(MT_DET_2_PIN); + #if PIN_EXISTS(MT_DET_2) + SET_INPUT_PULLUP(MT_DET_2_PIN); + #endif //SET_INPUT_PULLUP(MT_DET_3_PIN); - SET_INPUT_PULLUP(POWER_LOSS_PIN); - SET_INPUT_PULLUP(PS_ON_PIN); + SET_INPUT_PULLUP(MKS_TEST_POWER_LOSS_PIN); + SET_INPUT_PULLUP(MKS_TEST_PS_ON_PIN); SET_INPUT_PULLUP(SERVO0_PIN); @@ -104,14 +113,28 @@ void init_test_gpio() { SET_OUTPUT(Y_ENABLE_PIN); SET_OUTPUT(Z_ENABLE_PIN); SET_OUTPUT(E0_ENABLE_PIN); - SET_OUTPUT(E1_ENABLE_PIN); + #if !MB(MKS_ROBIN_E3P) + SET_OUTPUT(E1_ENABLE_PIN); + #endif WRITE(X_ENABLE_PIN, LOW); WRITE(Y_ENABLE_PIN, LOW); WRITE(Z_ENABLE_PIN, LOW); WRITE(E0_ENABLE_PIN, LOW); - WRITE(E1_ENABLE_PIN, LOW); + #if !MB(MKS_ROBIN_E3P) + WRITE(E1_ENABLE_PIN, LOW); + #endif //WRITE(E2_ENABLE_PIN, LOW); + + #if MB(MKS_ROBIN_E3P) + SET_INPUT_PULLUP(PA1); + SET_INPUT_PULLUP(PA3); + SET_INPUT_PULLUP(PC2); + SET_INPUT_PULLUP(PD8); + SET_INPUT_PULLUP(PE5); + SET_INPUT_PULLUP(PE6); + SET_INPUT_PULLUP(PE7); + #endif #endif } @@ -124,22 +147,37 @@ void mks_test_beeper() { #endif } -void mks_gpio_test(){ +void mks_gpio_test() { #if ENABLED(MKS_TEST) init_test_gpio(); test_gpio_readlevel_L(); test_gpio_readlevel_H(); test_gpio_readlevel_L(); - if ((pw_det_sta == 1) && (mt_det_sta == 1) && (mt_det2_sta == 1)) // &&(mt_det3_sta == 1)) + if ((pw_det_sta == 1) + && (pw_off_sta == 1) + && (mt_det_sta == 1) + #if PIN_EXISTS(MT_DET_2) + && (mt_det2_sta == 1) + #endif + #if MB(MKS_ROBIN_E3P) + && (READ(PA1) == 0) + && (READ(PA3) == 0) + && (READ(PC2) == 0) + && (READ(PD8) == 0) + && (READ(PE5) == 0) + && (READ(PE6) == 0) + && (READ(PE7) == 0) + #endif + ) // &&(mt_det3_sta == 1)) disp_det_ok(); else disp_det_error(); if ( (endstopx1_sta == 1) - && (endstopx2_sta == 1) + //&& (endstopx2_sta == 1) && (endstopy1_sta == 1) - && (endstopy2_sta == 1) + //&& (endstopy2_sta == 1) && (endstopz1_sta == 1) && (endstopz2_sta == 1) ) @@ -149,18 +187,22 @@ void mks_gpio_test(){ #endif } -void mks_hardware_test(){ +void mks_hardware_test() { #if ENABLED(MKS_TEST) if (millis() % 2000 < 1000) { WRITE(X_DIR_PIN, LOW); WRITE(Y_DIR_PIN, LOW); WRITE(Z_DIR_PIN, LOW); WRITE(E0_DIR_PIN, LOW); - WRITE(E1_DIR_PIN, LOW); + #if !MB(MKS_ROBIN_E3P) + WRITE(E1_DIR_PIN, LOW); + #endif //WRITE(E2_DIR_PIN, LOW); thermalManager.fan_speed[0] = 255; //WRITE(HEATER_2_PIN, HIGH); // HE2 - WRITE(HEATER_1_PIN, HIGH); // HE1 + #if !MB(MKS_ROBIN_E3P) + WRITE(HEATER_1_PIN, HIGH); // HE1 + #endif WRITE(HEATER_0_PIN, HIGH); // HE0 WRITE(HEATER_BED_PIN, HIGH); // HOT-BED } @@ -169,11 +211,15 @@ void mks_hardware_test(){ WRITE(Y_DIR_PIN, HIGH); WRITE(Z_DIR_PIN, HIGH); WRITE(E0_DIR_PIN, HIGH); - WRITE(E1_DIR_PIN, HIGH); + #if !MB(MKS_ROBIN_E3P) + WRITE(E1_DIR_PIN, HIGH); + #endif //WRITE(E2_DIR_PIN, HIGH); thermalManager.fan_speed[0] = 0; //WRITE(HEATER_2_PIN, LOW); // HE2 - WRITE(HEATER_1_PIN, LOW); // HE1 + #if !MB(MKS_ROBIN_E3P) + WRITE(HEATER_1_PIN, LOW); // HE1 + #endif WRITE(HEATER_0_PIN, LOW); // HE0 WRITE(HEATER_BED_PIN, LOW); // HOT-BED } diff --git a/Marlin/src/lcd/extui/lib/mks_ui/pic_manager.cpp b/Marlin/src/lcd/extui/lib/mks_ui/pic_manager.cpp index 447303a887..e629915309 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/pic_manager.cpp +++ b/Marlin/src/lcd/extui/lib/mks_ui/pic_manager.cpp @@ -24,6 +24,7 @@ #if HAS_TFT_LVGL_UI #include "string.h" +#include "draw_ui.h" #include "pic_manager.h" #include "draw_ready_print.h" #include "mks_hardware_test.h" @@ -41,59 +42,61 @@ extern unsigned char bmp_public_buf[17 * 1024]; extern char *createFilename(char * const buffer, const dir_t &p); #endif -static char assets[][LONG_FILENAME_LENGTH] = { +static const char assets[][LONG_FILENAME_LENGTH] = { //homing screen - "bmp_Zero.bin", + "bmp_zeroAll.bin", + "bmp_zero.bin", "bmp_zeroX.bin", "bmp_zeroY.bin", "bmp_zeroZ.bin", "bmp_manual_off.bin", //tool screen - "bmp_PreHeat.bin", - "bmp_Extruct.bin", - "bmp_Mov.bin", + "bmp_preHeat.bin", + "bmp_extruct.bin", + "bmp_mov.bin", // "bmp_Zero.bin", - "bmp_Leveling.bin", + "bmp_leveling.bin", + "bmp_filamentchange.bin", //fan screen "bmp_Add.bin", "bmp_Dec.bin", - "bmp_Speed255.bin", - "bmp_Speed127.bin", - "bmp_Speed0.bin", + "bmp_speed255.bin", + "bmp_speed127.bin", + "bmp_speed0.bin", //preheat screen // "bmp_Add.bin", // "bmp_Dec.bin", - "bmp_Speed0.bin", + "bmp_speed0.bin", // "bmp_Extru2.bin", // "bmp_Extru1.bin", - "bmp_Bed.bin", - "bmp_Step1_degree.bin", - "bmp_Step5_degree.bin", - "bmp_Step10_degree.bin", + "bmp_bed.bin", + "bmp_step1_degree.bin", + "bmp_step5_degree.bin", + "bmp_step10_degree.bin", //extrusion screen - "bmp_In.bin", - "bmp_Out.bin", - "bmp_Extru1.bin", - #if EXTRUDERS > 1 - "bmp_Extru2.bin", + "bmp_in.bin", + "bmp_out.bin", + "bmp_extru1.bin", + #if HAS_MULTI_EXTRUDER + "bmp_extru2.bin", #endif - "bmp_Speed_high.bin", - "bmp_Speed_slow.bin", - "bmp_Speed_normal.bin", - "bmp_Step1_mm.bin", - "bmp_Step5_mm.bin", - "bmp_Step10_mm.bin", + "bmp_speed_high.bin", + "bmp_speed_slow.bin", + "bmp_speed_normal.bin", + "bmp_step1_mm.bin", + "bmp_step5_mm.bin", + "bmp_step10_mm.bin", //select file screen "bmp_pageUp.bin", "bmp_pageDown.bin", - "bmp_Back.bin", //TODO: why two back buttons? Why not just one? (return / back) - "bmp_Dir.bin", - "bmp_File.bin", + "bmp_back.bin", //TODO: why two back buttons? Why not just one? (return / back) + "bmp_dir.bin", + "bmp_file.bin", //move motor screen //TODO: 6 equal icons, just in diffenct rotation... it may be optimized too @@ -103,68 +106,69 @@ static char assets[][LONG_FILENAME_LENGTH] = { "bmp_yDec.bin", "bmp_zAdd.bin", "bmp_zDec.bin", - "bmp_Step_move0_1.bin", - "bmp_Step_move1.bin", - "bmp_Step_move10.bin", + "bmp_step_move0_1.bin", + "bmp_step_move1.bin", + "bmp_step_move10.bin", //operation screen "bmp_auto_off.bin", - "bmp_Speed.bin", + "bmp_speed.bin", //"bmp_Mamual.bin", //TODO: didn't find it.. changed to bmp_manual_off.bin - "bmp_Fan.bin", - //"bmp_PreHeat.bin", - //"bmp_Extruct.bin", - // "bmp_Mov.bin", + "bmp_fan.bin", + "bmp_temp.bin", + "bmp_extrude_opr.bin", + "bmp_move_opr.bin", //change speed screen - "bmp_Step1_percent.bin", - "bmp_Step5_percent.bin", - "bmp_Step10_percent.bin", + "bmp_step1_percent.bin", + "bmp_step5_percent.bin", + "bmp_step10_percent.bin", "bmp_extruct_sel.bin", "bmp_mov_changespeed.bin", // "bmp_extrude_opr.bin", equal to "bmp_Extruct.bin" "bmp_mov_sel.bin", + "bmp_speed_extruct.bin", //printing screen - "bmp_Pause.bin", - "bmp_Resume.bin", - "bmp_Stop.bin", - "bmp_Ext1_state.bin", - #if EXTRUDERS > 1 - "bmp_Ext2_state.bin", + "bmp_pause.bin", + "bmp_resume.bin", + "bmp_stop.bin", + "bmp_ext1_state.bin", + #if HAS_MULTI_EXTRUDER + "bmp_ext2_state.bin", #endif - "bmp_Bed_state.bin", - "bmp_Fan_state.bin", - "bmp_Time_state.bin", - "bmp_Zpos_state.bin", - "bmp_Operate.bin", + "bmp_bed_state.bin", + "bmp_fan_state.bin", + "bmp_time_state.bin", + "bmp_zpos_state.bin", + "bmp_operate.bin", //manual leval screen (only if disabled auto level) #if DISABLED(AUTO_BED_LEVELING_BILINEAR) - "bmp_Leveling1.bin", - "bmp_Leveling2.bin", - "bmp_Leveling3.bin", - "bmp_Leveling4.bin", - "bmp_Leveling5.bin", + "bmp_leveling1.bin", + "bmp_leveling2.bin", + "bmp_leveling3.bin", + "bmp_leveling4.bin", + "bmp_leveling5.bin", #endif //lang select screen #if HAS_LANG_SELECT_SCREEN - "bmp_Language.bin", + "bmp_language.bin", "bmp_simplified_cn.bin", "bmp_simplified_cn_sel.bin", "bmp_traditional_cn.bin", "bmp_traditional_cn_sel.bin", - "bmp_English.bin", - "bmp_English_sel.bin", - "bmp_Russian.bin", - "bmp_Russian_sel.bin", - "bmp_Spanish.bin", - "bmp_Spanish_sel.bin", - "bmp_French.bin", - "bmp_French_sel.bin", - "bmp_Italy.bin", - "bmp_Italy_sel.bin", + "bmp_english.bin", + "bmp_english_sel.bin", + "bmp_russian.bin", + "bmp_russian_sel.bin", + "bmp_spanish.bin", + "bmp_spanish_sel.bin", + "bmp_french.bin", + "bmp_french_sel.bin", + "bmp_italy.bin", + "bmp_italy_sel.bin", #endif // HAS_LANG_SELECT_SCREEN // gcode preview @@ -177,21 +181,15 @@ static char assets[][LONG_FILENAME_LENGTH] = { #endif // settings screen - "bmp_About.bin", + "bmp_about.bin", //"bmp_Language.bin", //"bmp_Fan.bin", //"bmp_manual_off.bin", //start screen "bmp_printing.bin", - "bmp_Set.bin", - "bmp_Tool.bin", - - #if ENABLED(HAS_STEALTHCHOP) - //"bmp_back70x40.bin", - "bmp_disable.bin", - "bmp_enable.bin", - #endif + "bmp_set.bin", + "bmp_tool.bin", // settings screen "bmp_eeprom_settings.bin", @@ -202,14 +200,27 @@ static char assets[][LONG_FILENAME_LENGTH] = { "bmp_arrow.bin", "bmp_back70x40.bin", "bmp_value_blank.bin", - "bmp_Return.bin" + "bmp_blank_sel.bin", + "bmp_disable.bin", + "bmp_enable.bin", + "bmp_return.bin", + + #if ENABLED(USE_WIFI_FUNCTION) + //wifi screen + "bmp_wifi.bin", + #endif + + //babystep screen + "bmp_baby_move0_01.bin", + "bmp_baby_move0_05.bin", + "bmp_baby_move0_1.bin" }; #if HAS_SPI_FLASH_FONT static char fonts[][LONG_FILENAME_LENGTH] = { "FontUNIGBK.bin" }; #endif -static uint8_t currentFlashPage = 0; +uint8_t currentFlashPage = 0; uint32_t lv_get_pic_addr(uint8_t *Pname) { uint8_t Pic_cnt; @@ -253,8 +264,13 @@ const char *bakPath = "_assets"; void spiFlashErase_PIC() { volatile uint32_t pic_sectorcnt = 0; W25QXX.init(SPI_QUARTER_SPEED); - for (pic_sectorcnt = 0; pic_sectorcnt < PIC_SIZE_xM * 1024 / 64; pic_sectorcnt++) - W25QXX.SPI_FLASH_BlockErase(PICINFOADDR + pic_sectorcnt * 64 * 1024); + //erase 0x001000 -64K + for (pic_sectorcnt = 0; pic_sectorcnt < (64 - 4) / 4; pic_sectorcnt++) { + W25QXX.SPI_FLASH_SectorErase(PICINFOADDR + pic_sectorcnt * 4 * 1024); + } + //erase 64K -- 6M + for (pic_sectorcnt = 0; pic_sectorcnt < (PIC_SIZE_xM * 1024 / 64 - 1); pic_sectorcnt++) + W25QXX.SPI_FLASH_BlockErase((pic_sectorcnt + 1) * 64 * 1024); } #if HAS_SPI_FLASH_FONT diff --git a/Marlin/src/lcd/extui/lib/mks_ui/pic_manager.h b/Marlin/src/lcd/extui/lib/mks_ui/pic_manager.h index 4d9d08a9b4..5d5227c2a4 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/pic_manager.h +++ b/Marlin/src/lcd/extui/lib/mks_ui/pic_manager.h @@ -119,12 +119,21 @@ // Flash flag #define REFLSHE_FLGA_ADD (0X800000-32) -#define FLASH_INF_VALID_FLAG 0xAA558761 + // SD card information first addr #define VAR_INF_ADDR 0x000000 +#define FLASH_INF_VALID_FLAG 0x20200831 + +//Store some gcode commands, such as auto leveling commands +#define GCODE_COMMAND_ADDR VAR_INF_ADDR + 3*1024 +#define AUTO_LEVELING_COMMAND_ADDR GCODE_COMMAND_ADDR +#define OTHERS_COMMAND_ADDR_1 AUTO_LEVELING_COMMAND_ADDR + 100 +#define OTHERS_COMMAND_ADDR_2 OTHERS_COMMAND_ADDR_1 + 100 +#define OTHERS_COMMAND_ADDR_3 OTHERS_COMMAND_ADDR_2 + 100 +#define OTHERS_COMMAND_ADDR_4 OTHERS_COMMAND_ADDR_3 + 100 #ifdef __cplusplus -extern "C" { /* C-declarations for C++ */ + extern "C" { /* C-declarations for C++ */ #endif union union32 { @@ -156,8 +165,6 @@ extern void spi_flash_read_test(); extern void default_view_Read(uint8_t *default_view_Rbuff, uint32_t default_view_Readsize); extern void flash_view_Read(uint8_t *flash_view_Rbuff, uint32_t flash_view_Readsize); -extern W25QXXFlash W25QXX; - #ifdef __cplusplus -} /* C-declarations for C++ */ + } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/printer_operation.cpp b/Marlin/src/lcd/extui/lib/mks_ui/printer_operation.cpp index 138168b12f..2b6f5f89f6 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/printer_operation.cpp +++ b/Marlin/src/lcd/extui/lib/mks_ui/printer_operation.cpp @@ -51,7 +51,13 @@ void printer_state_polling() { if (uiCfg.waitEndMoves > 20) { uiCfg.waitEndMoves = 0; planner.synchronize(); + gcode.process_subcommands_now_P(PSTR("M25")); + + //save the positon + uiCfg.current_x_position_bak = current_position.x; + uiCfg.current_y_position_bak = current_position.y; + if (gCfgItems.pausePosZ != (float)-1) { gcode.process_subcommands_now_P(PSTR("G91")); ZERO(public_buf_l); @@ -65,6 +71,7 @@ void printer_state_polling() { gcode.process_subcommands_now(public_buf_l); } uiCfg.print_state = PAUSED; + uiCfg.current_e_position_bak = current_position.e; // #if ENABLED(POWER_LOSS_RECOVERY) // if (recovery.enabled) recovery.save(true); @@ -82,7 +89,19 @@ void printer_state_polling() { if (uiCfg.print_state == RESUMING) { if (IS_SD_PAUSED()) { - gcode.process_subcommands_now_P(PSTR("M24\nG91\nG1 Z-5\nG90")); + if (gCfgItems.pausePosX != (float)-1 && gCfgItems.pausePosY != (float)-1) { + ZERO(public_buf_m); + sprintf_P(public_buf_m, PSTR("G1 X%.1f Y%.1f"), uiCfg.current_x_position_bak, uiCfg.current_y_position_bak); + gcode.process_subcommands_now(public_buf_m); + } + if (gCfgItems.pausePosZ != (float)-1) { + gcode.process_subcommands_now_P(PSTR("G91")); + ZERO(public_buf_l); + sprintf_P(public_buf_l, PSTR("G1 Z-%.1f"), gCfgItems.pausePosZ); + gcode.process_subcommands_now(public_buf_l); + gcode.process_subcommands_now_P(PSTR("G90")); + } + gcode.process_subcommands_now_P(PSTR("M24")); uiCfg.print_state = WORKING; start_print_time(); @@ -107,11 +126,25 @@ void printer_state_polling() { } #endif - if (gCfgItems.pause_reprint == 1) { - gcode.process_subcommands_now_P(PSTR("G91\nG1 Z-5\nG90")); - } recovery.resume(); - + #if 0 + // Move back to the saved XY + char str_1[16], str_2[16]; + ZERO(public_buf_m); + sprintf_P(public_buf_m, PSTR("G1 X%s Y%s F2000"), + dtostrf(recovery.info.current_position.x, 1, 3, str_1), + dtostrf(recovery.info.current_position.y, 1, 3, str_2) + ); + gcode.process_subcommands_now(public_buf_m); + + if ((gCfgItems.pause_reprint) == 1 && (gCfgItems.pausePosZ != (float)-1)) { + gcode.process_subcommands_now_P(PSTR("G91")); + ZERO(public_buf_l); + sprintf_P(public_buf_l, PSTR("G1 Z-%.1f"), gCfgItems.pausePosZ); + gcode.process_subcommands_now(public_buf_l); + gcode.process_subcommands_now_P(PSTR("G90")); + } + #endif uiCfg.print_state = WORKING; start_print_time(); @@ -122,17 +155,19 @@ void printer_state_polling() { if (uiCfg.print_state == WORKING) filament_check(); + + TERN_(USE_WIFI_FUNCTION, wifi_looping()); } void filament_pin_setup() { #if PIN_EXISTS(MT_DET_1) - pinMode(MT_DET_1_PIN, INPUT_PULLUP); + SET_INPUT_PULLUP(MT_DET_1_PIN); #endif #if PIN_EXISTS(MT_DET_2) - pinMode(MT_DET_2_PIN, INPUT_PULLUP); + SET_INPUT_PULLUP(MT_DET_2_PIN); #endif #if PIN_EXISTS(MT_DET_3) - pinMode(MT_DET_3_PIN, INPUT_PULLUP); + SET_INPUT_PULLUP(MT_DET_3_PIN); #endif } diff --git a/Marlin/src/lcd/extui/lib/mks_ui/printer_operation.h b/Marlin/src/lcd/extui/lib/mks_ui/printer_operation.h index 9605d65085..f304158824 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/printer_operation.h +++ b/Marlin/src/lcd/extui/lib/mks_ui/printer_operation.h @@ -22,7 +22,7 @@ #pragma once #ifdef __cplusplus -extern "C" { /* C-declarations for C++ */ + extern "C" { /* C-declarations for C++ */ #endif #define MIN_FILE_PRINTED 100 //5000 @@ -32,5 +32,5 @@ extern void filament_pin_setup(); extern void filament_check(); #ifdef __cplusplus -} /* C-declarations for C++ */ + } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_en.h b/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_en.h index 54e06f5826..fa8d5a52a4 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_en.h +++ b/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_en.h @@ -46,8 +46,8 @@ #define MACHINE_PARA_TITLE_EN "Config" #define MACHINE_TYPE_CNOFIG_EN "Machine settings" -#define TEMPERATURE_CONFIG_EN "Temperature settings" #define MOTOR_CONFIG_EN "Motor settings" +#define MACHINE_LEVELING_CONFIG_EN "Leveling settings" #define ADVANCE_CONFIG_EN "Adavance settings" #define MACHINE_CONFIG_TITLE_EN "Machine Settings" @@ -56,7 +56,6 @@ #define MACHINE_HOMEDIR_EN "Home direction" #define MACHINE_ENDSTOP_TYPE_EN "Endstop type" #define MACHINE_FILAMENT_CONFIG_EN "Filament settings" -#define MACHINE_LEVELING_CONFIG_EN "Leveling settings" #define MACHINE_TYPE_CONFIG_TITLE_EN "Machine Settings>Machine type" #define MACHINE_TYPE_XYZ_EN "XYZ Machine" @@ -91,18 +90,18 @@ #define ENDSTOP_OPENED_EN "Open" #define ENDSTOP_CLOSED_EN "Close" -#define FILAMENT_CONF_TITLE_EN "Filament settings" -#define FILAMENT_IN_TEMPERATURE_EN "Load temperature" +#define FILAMENT_CONF_TITLE_EN "Machine Settings>Filament settings" #define FILAMENT_IN_LENGTH_EN "Load length" #define FILAMENT_IN_SPEED_EN "Load speed" -#define FILAMENT_OUT_TEMPERATURE_EN "Unload temperature" +#define FILAMENT_TEMPERATURE_EN "Filament temperature" #define FILAMENT_OUT_LENGTH_EN "Unload length" #define FILAMENT_OUT_SPEED_EN "Unload speed" -#define LEVELING_CONF_TITLE_EN "Leveling settings" +#define LEVELING_CONF_TITLE_EN "Machine Settings>Leveling settings" #define LEVELING_PARA_CONF_EN "Leveling settings" -#define LEVELING_DELTA_EN "delta machine leveling" -#define LEVELING_XYZ_EN "Manual leveling coordinate settings" +#define LEVELING_MANUAL_POS_EN "Manual leveling coordinate settings" +#define LEVELING_AUTO_COMMAND_EN "AutoLeveling command settings" +#define LEVELING_AUTO_ZOFFSET_EN "Nozzle-to-probe offsets settings" #define LEVELING_PARA_CONF_TITLE_EN "leveling setting" #define AUTO_LEVELING_ENABLE_EN "Enable auto leveling" @@ -226,6 +225,9 @@ #define HAVE_UPS_EN "Has UPS power supply" #define Z2_AND_Z2ENDSTOP_CONF_EN "Z2 Settings" #define ENABLE_PINS_CONF_EN "Enable pins level settings" +#define WIFI_SETTINGS_EN "Wi-Fi parameter settings" +#define HOMING_SENSITIVITY_CONF_EN "Homing sensitivity settings" +#define ENCODER_SETTINGS_EN "Rotary encoder settings" #define Z2_AND_Z2ENDSTOP_CONF_TITLE_EN "Z2 Settings" #define Z2_ENABLE_EN "Z2 Enable" @@ -243,6 +245,29 @@ #define PAUSE_POSITION_Y_EN "Y axis position (Absolute position,-1 invalid)" #define PAUSE_POSITION_Z_EN "Z axis position (Relative position,-1 invalid)" +#define WIFI_SETTINGS_TITLE_EN "Machine Settings>Wi-Fi Parameter" +#define WIFI_SETTINGS_MODE_EN "Wi-Fi Mode" +#define WIFI_SETTINGS_NAME_EN "Wi-Fi Name: " +#define WIFI_SETTINGS_PASSWORD_EN "Wi-Fi Password: " +#define WIFI_SETTINGS_CLOUD_EN "Do you use cloud services?" +#define WIFI_SETTINGS_CONFIG_EN "Config" +#define WIFI_SETTINGS_EDIT_EN "Edit" +#define WIFI_CONFIG_TIPS_EN "Wi-Fi configuration?" + +#define OFFSET_TITLE_EN "Machine Settings>Offset" +#define OFFSET_X_EN "X offset" +#define OFFSET_Y_EN "Y offset" +#define OFFSET_Z_EN "Z offset" + +#define HOMING_SENSITIVITY_CONF_TITLE_EN "Machine Settings>Sensitivity" +#define X_SENSITIVITY_EN "X Axis Sensitivity" +#define Y_SENSITIVITY_EN "Y Axis Sensitivity" +#define Z_SENSITIVITY_EN "Z Axis Sensitivity" +#define Z2_SENSITIVITY_EN "Z2 Axis Sensitivity" + +#define ENCODER_CONF_TITLE_EN "Machine Settings>Rotary encoder settings" +#define ENCODER_CONF_TEXT_EN "Is the encoder function used?" + #define TOOL_TEXT_EN "Tool" #define PREHEAT_TEXT_EN "Preheat" #define MOVE_TEXT_EN "Move" @@ -429,10 +454,6 @@ #define STEP_5PERCENT_EN "5%" #define STEP_10PERCENT_EN "10%" -#define ZOFFSET_EN "Z Offset" -#define ZOFFSET_INC_EN "Add" -#define ZOFFSET_DEC_EN "Dec" - #define TITLE_READYPRINT_EN "ReadyPrint" #define TITLE_PREHEAT_EN "Preheat" #define TITLE_MOVE_EN "Move" @@ -455,7 +476,6 @@ #define TITLE_CLOUD_TEXT_EN "Cloud" #define TITLE_DIALOG_CONFIRM_EN "Confirm" #define TITLE_FILESYS_EN "FileSys" -#define TITLE_ZOFFSET_EN "Z Offset" #define AUTO_SHUTDOWN_EN "Auto" #define MANUAL_SHUTDOWN_EN "Manual" @@ -494,11 +514,9 @@ #define TEXT_WIFI_SYMBOL_EN "#+=" #define TEXT_WIFI_PASSWORD_EN "Password" -#define TEXT_WIFI_POINT_BOLD_EN "`" - -#define TEXT_WIFI_JOINING_EN "Joining\nNetwork..." -#define TEXT_WIFI_FAILED_JOIN_EN "Failed to\nJoin Wi-Fi" -#define TEXT_WIFI_WIFI_CONECTED_EN "Wi-Fi\nConnected" +#define TEXT_WIFI_JOINING_EN "Joining Network..." +#define TEXT_WIFI_FAILED_JOIN_EN "Failed to Join Wi-Fi" +#define TEXT_WIFI_WIFI_CONECTED_EN "Wi-Fi Connected" #define TEXT_BUTTON_DISCONECTED_EN "Disconnect" #define TEXT_WIFI_FORGET_EN "Forget Network" diff --git a/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_fr.h b/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_fr.h index 3fe95654b1..6944d6b235 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_fr.h +++ b/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_fr.h @@ -208,10 +208,6 @@ #define STEP_5PERCENT_FR "5%" #define STEP_10PERCENT_FR "10%" -#define ZOFFSET_FR "Z Offset" -#define ZOFFSET_INC_FR "Ajouter" -#define ZOFFSET_DEC_FR "Réduire" - #define TITLE_READYPRINT_FR "Prête" #define TITLE_PREHEAT_FR "Préchauffe" #define TITLE_MOVE_FR "Déplace" @@ -234,7 +230,6 @@ #define TITLE_CLOUD_TEXT_FR "Cloud" #define TITLE_DIALOG_CONFIRM_FR "Confirm" #define TITLE_FILESYS_FR "FileSys" -#define TITLE_ZOFFSET_FR "Z Offset" #define DIALOG_CLOSE_MACHINE_FR "Closing machine......" diff --git a/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_it.h b/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_it.h index aef6cfaf96..f64ca4df79 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_it.h +++ b/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_it.h @@ -205,10 +205,6 @@ #define STEP_5PERCENT_IT "5%" #define STEP_10PERCENT_IT "10%" -#define ZOFFSET_IT "Z Offset" -#define ZOFFSET_INC_IT "Add" -#define ZOFFSET_DEC_IT "Dec" - #define TITLE_READYPRINT_IT "Pronto" #define TITLE_PREHEAT_IT "Preris" #define TITLE_MOVE_IT "Muovi" @@ -231,7 +227,6 @@ #define TITLE_CLOUD_TEXT_IT "Cloud" #define TITLE_DIALOG_CONFIRM_IT "Confirm" #define TITLE_FILESYS_IT "FileSys" -#define TITLE_ZOFFSET_IT "Z Offset" #define AUTO_SHUTDOWN_IT "Auto" #define MANUAL_SHUTDOWN_IT "Manuale" diff --git a/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_ru.h b/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_ru.h index 2ec39ab016..9f695b376b 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_ru.h +++ b/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_ru.h @@ -205,10 +205,6 @@ #define STEP_5PERCENT_RU "5%" #define STEP_10PERCENT_RU "10%" -#define ZOFFSET_RU "Z Offset" -#define ZOFFSET_INC_RU "добавить" -#define ZOFFSET_DEC_RU "уменьшить" - #define TITLE_READYPRINT_RU "готов к" #define TITLE_PREHEAT_RU "движение" #define TITLE_MOVE_RU "движение" @@ -232,7 +228,6 @@ #define TITLE_CLOUD_TEXT_RU "Cloud" #define TITLE_DIALOG_CONFIRM_RU "Confirm" #define TITLE_FILESYS_RU "FileSys" -#define TITLE_ZOFFSET_RU "Z Offset" #define AUTO_SHUTDOWN_RU "авто-откл" #define MANUAL_SHUTDOWN_RU "ручн-откл" diff --git a/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_s_cn.h b/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_s_cn.h index ea481c89a2..1189927770 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_s_cn.h +++ b/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_s_cn.h @@ -31,8 +31,8 @@ #define MACHINE_PARA_TITLE_CN "机器参数" #define MACHINE_TYPE_CNOFIG_CN "机器设置" -#define TEMPERATURE_CONFIG_CN "温度设置" #define MOTOR_CONFIG_CN "电机设置" +#define MACHINE_LEVELING_CONFIG_CN "调平设置" #define ADVANCE_CONFIG_CN "高级设置" #define MACHINE_CONFIG_TITLE_CN "机器参数>机器配置" @@ -41,7 +41,6 @@ #define MACHINE_HOMEDIR_CN "归零方向" #define MACHINE_ENDSTOP_TYPE_CN "限位开关类型" #define MACHINE_FILAMENT_CONFIG_CN "换料设置" -#define MACHINE_LEVELING_CONFIG_CN "调平设置" #define MACHINE_TYPE_CONFIG_TITLE_CN "机器参数>机型选择" #define MACHINE_TYPE_XYZ_CN "XYZ机型" @@ -77,17 +76,17 @@ #define ENDSTOP_CLOSED_CN "常闭" #define FILAMENT_CONF_TITLE_CN "换料设置" -#define FILAMENT_IN_TEMPERATURE_CN "进料温度" #define FILAMENT_IN_LENGTH_CN "进料长度" #define FILAMENT_IN_SPEED_CN "进料速度" -#define FILAMENT_OUT_TEMPERATURE_CN "退料温度" +#define FILAMENT_TEMPERATURE_CN "换料温度" #define FILAMENT_OUT_LENGTH_CN "退料长度" #define FILAMENT_OUT_SPEED_CN "退料速度" -#define LEVELING_CONF_TITLE_CN "调平设置" +#define LEVELING_CONF_TITLE_CN "机器参数>调平设置" #define LEVELING_PARA_CONF_CN "调平设置" -#define LEVELING_DELTA_CN "delta机型设置" -#define LEVELING_XYZ_CN "手动调平坐标设置" +#define LEVELING_MANUAL_POS_CN "手动调平坐标设置" +#define LEVELING_AUTO_COMMAND_CN "自动调平指令设置" +#define LEVELING_AUTO_ZOFFSET_CN "挤出头与调平开关偏移设置" #define LEVELING_PARA_CONF_TITLE_CN "调平参数" #define AUTO_LEVELING_ENABLE_CN "自动调平" @@ -146,6 +145,7 @@ #define TMC_STEP_MODE_CN "TMC 驱动模式设置" #define MOTORDIRCONF_CN "电机方向设置" #define HOMEFEEDRATECONF_CN "归零速度设置" +#define HOMING_SENSITIVITY_CONF_CN "无限位回零灵敏度调节" #define MAXFEEDRATE_CONF_TITLE_CN "机器参数>最大速度" #define X_MAXFEEDRATE_CN "X轴最大速度" @@ -211,6 +211,8 @@ #define HAVE_UPS_CN "机器配备UPS电源" #define Z2_AND_Z2ENDSTOP_CONF_CN "双Z轴双限位功能设置" #define ENABLE_PINS_CONF_CN "电机使能脚电平设置" +#define WIFI_SETTINGS_CN "Wi-Fi参数设置" +#define ENCODER_SETTINGS_CN "旋钮设置" #define Z2_AND_Z2ENDSTOP_CONF_TITLE_CN "双z双限位设置" #define Z2_ENABLE_CN "启用Z2轴" @@ -223,10 +225,33 @@ #define Z_ENABLE_PINS_INVERT_CN "Z轴电机使能电平" #define E_ENABLE_PINS_INVERT_CN "E轴电机使能电平" -#define PAUSE_POSITION_CN "打印暂停位置设置" -#define PAUSE_POSITION_X_CN "X轴暂停位置(绝对位置,-1无效)" -#define PAUSE_POSITION_Y_CN "Y轴暂停位置(绝对位置,-1无效)" -#define PAUSE_POSITION_Z_CN "Z轴暂停位置(相对位置,-1无效)" +#define PAUSE_POSITION_CN "打印暂停位置设置" +#define PAUSE_POSITION_X_CN "X轴暂停位置(绝对位置,-1无效)" +#define PAUSE_POSITION_Y_CN "Y轴暂停位置(绝对位置,-1无效)" +#define PAUSE_POSITION_Z_CN "Z轴暂停位置(相对位置,-1无效)" +#define WIFI_SETTINGS_TITLE_CN "机器参数>Wi-Fi设置" +#define WIFI_SETTINGS_MODE_CN "Wi-Fi 模式" +#define WIFI_SETTINGS_NAME_CN "Wi-Fi 名称: " +#define WIFI_SETTINGS_PASSWORD_CN "Wi-Fi 密码: " +#define WIFI_SETTINGS_CLOUD_CN "是否使用云服务?" +#define WIFI_SETTINGS_CONFIG_CN "配置" +#define WIFI_SETTINGS_EDIT_CN "编辑" +#define WIFI_CONFIG_TIPS_CN "进行Wi-Fi配置?" + +#define OFFSET_TITLE_CN "机器参数>偏移设置" +#define OFFSET_X_CN "X轴与调平开关偏移" +#define OFFSET_Y_CN "Y轴与调平开关偏移" +#define OFFSET_Z_CN "Z轴与调平开关偏移" + +#define HOMING_SENSITIVITY_CONF_TITLE_CN "机器参数>灵敏度调节" +#define X_SENSITIVITY_CN "X轴灵敏度" +#define Y_SENSITIVITY_CN "Y轴灵敏度" +#define Z_SENSITIVITY_CN "Z轴灵敏度" +#define Z2_SENSITIVITY_CN "Z2轴灵敏度" + +#define ENCODER_CONF_TITLE_CN "机器参数>旋钮设置" +#define ENCODER_CONF_TEXT_CN "是否使用旋钮功能?" + #define TOOL_TEXT_CN "工具" #define PREHEAT_TEXT_CN "预热" #define MOVE_TEXT_CN "移动" @@ -395,10 +420,6 @@ #define STEP_5PERCENT_CN "5%" #define STEP_10PERCENT_CN "10%" -#define ZOFFSET_CN "Z Offset" -#define ZOFFSET_INC_CN "增加" -#define ZOFFSET_DEC_CN "减少" - #define TITLE_READYPRINT_CN "准备打印" #define TITLE_PREHEAT_CN "预热" #define TITLE_MOVE_CN "移动" @@ -421,7 +442,6 @@ #define TITLE_CLOUD_TEXT_CN "云服务" #define TITLE_DIALOG_CONFIRM_CN "确认" #define TITLE_FILESYS_CN "文件系统" -#define TITLE_ZOFFSET_CN "Z Offset" #define AUTO_SHUTDOWN_CN "自动关机" #define MANUAL_SHUTDOWN_CN "手动关机" diff --git a/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_sp.h b/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_sp.h index 289874c6ba..2babbaba93 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_sp.h +++ b/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_sp.h @@ -206,10 +206,6 @@ #define STEP_5PERCENT_SP "5%" #define STEP_10PERCENT_SP "10%" -#define ZOFFSET_SP "Z Offset" -#define ZOFFSET_INC_SP "Más" -#define ZOFFSET_DEC_SP "Menos" - #define TITLE_READYPRINT_SP "Inicio" #define TITLE_PREHEAT_SP "Precalentar" #define TITLE_MOVE_SP "Mover" @@ -233,7 +229,6 @@ #define TITLE_CLOUD_TEXT_SP "Cloud" #define TITLE_DIALOG_CONFIRM_SP "Confirmar" #define TITLE_FILESYS_SP "Puerto" -#define TITLE_ZOFFSET_SP "Z Offset" #define AUTO_SHUTDOWN_SP "Auto" #define MANUAL_SHUTDOWN_SP "manual" diff --git a/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_t_cn.h b/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_t_cn.h index 19bd511d9a..d956e14aad 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_t_cn.h +++ b/Marlin/src/lcd/extui/lib/mks_ui/tft_Language_t_cn.h @@ -31,8 +31,8 @@ #define MACHINE_PARA_TITLE_T_CN "機器參數" #define MACHINE_TYPE_CNOFIG_T_CN "機器設置" -#define TEMPERATURE_CONFIG_T_CN "溫度設置" #define MOTOR_CONFIG_T_CN "電機設置" +#define MACHINE_LEVELING_CONFIG_T_CN "調平設置" #define ADVANCE_CONFIG_T_CN "高級設置" #define MACHINE_CONFIG_TITLE_T_CN "機器參數>機器配置" @@ -41,7 +41,6 @@ #define MACHINE_HOMEDIR_T_CN "歸零方向" #define MACHINE_ENDSTOP_TYPE_T_CN "限位開關類型" #define MACHINE_FILAMENT_CONFIG_T_CN "換料設置" -#define MACHINE_LEVELING_CONFIG_T_CN "調平設置" #define MACHINE_TYPE_CONFIG_TITLE_T_CN "機器參數>機型選擇" #define MACHINE_TYPE_XYZ_T_CN "XYZ機型" @@ -77,17 +76,17 @@ #define ENDSTOP_CLOSED_T_CN "常閉" #define FILAMENT_CONF_TITLE_T_CN "換料設置" -#define FILAMENT_IN_TEMPERATURE_T_CN "進料溫度" #define FILAMENT_IN_LENGTH_T_CN "進料長度" #define FILAMENT_IN_SPEED_T_CN "進料速度" -#define FILAMENT_OUT_TEMPERATURE_T_CN "退料溫度" +#define FILAMENT_TEMPERATURE_T_CN "換料溫度" #define FILAMENT_OUT_LENGTH_T_CN "退料長度" #define FILAMENT_OUT_SPEED_T_CN "退料速度" -#define LEVELING_CONF_TITLE_T_CN "調平設置" +#define LEVELING_CONF_TITLE_T_CN "機器參數>調平設置" #define LEVELING_PARA_CONF_T_CN "調平設置" -#define LEVELING_DELTA_T_CN "delta機型設置" -#define LEVELING_XYZ_T_CN "手動調平坐標設置" +#define LEVELING_MANUAL_POS_T_CN "手動調平坐標設置" +#define LEVELING_AUTO_COMMAND_T_CN "自動調平指令設置" +#define LEVELING_AUTO_ZOFFSET_T_CN "擠出頭與調平開關偏移設置" #define LEVELING_PARA_CONF_TITLE_T_CN "調平參數" #define AUTO_LEVELING_ENABLE_T_CN "自動調平" @@ -146,6 +145,7 @@ #define TMC_STEP_MODE_T_CN "TMC 驅動模式設置" #define MOTORDIRCONF_T_CN "電機方向設置" #define HOMEFEEDRATECONF_T_CN "歸零速度設置" +#define HOMING_SENSITIVITY_CONF_T_CN "無限位回零靈敏度調節" #define MAXFEEDRATE_CONF_TITLE_T_CN "機器參數>最大速度" #define X_MAXFEEDRATE_T_CN "X軸最大速度" @@ -211,6 +211,8 @@ #define HAVE_UPS_T_CN "機器配備UPS電壓" #define Z2_AND_Z2ENDSTOP_CONF_T_CN "雙z軸雙限位功能設置" #define ENABLE_PINS_CONF_T_CN "電機使能腳電平設置" +#define WIFI_SETTINGS_T_CN "Wi-Fi參數設置" +#define ENCODER_SETTINGS_T_CN "旋鈕設置" #define Z2_AND_Z2ENDSTOP_CONF_TITLE_T_CN "雙z軸雙限位設置" #define Z2_ENABLE_T_CN "啟用Z2軸" @@ -223,10 +225,32 @@ #define Z_ENABLE_PINS_INVERT_T_CN "Z軸電機使能電平" #define E_ENABLE_PINS_INVERT_T_CN "E軸電機使能電平" -#define PAUSE_POSITION_T_CN "打印暫停位置設置" -#define PAUSE_POSITION_X_T_CN "X軸暫停位置(絕對位置,-1無效)" -#define PAUSE_POSITION_Y_T_CN "Y軸暫停位置(絕對位置,-1無效)" -#define PAUSE_POSITION_Z_T_CN "Z軸暫停位置(相對位置,-1無效)" +#define PAUSE_POSITION_T_CN "打印暫停位置設置" +#define PAUSE_POSITION_X_T_CN "X軸暫停位置(絕對位置,-1無效)" +#define PAUSE_POSITION_Y_T_CN "Y軸暫停位置(絕對位置,-1無效)" +#define PAUSE_POSITION_Z_T_CN "Z軸暫停位置(相對位置,-1無效)" +#define WIFI_SETTINGS_TITLE_T_CN "機器參數>Wi-Fi設置" +#define WIFI_SETTINGS_MODE_T_CN "Wi-Fi 模式" +#define WIFI_SETTINGS_NAME_T_CN "Wi-Fi 名稱: " +#define WIFI_SETTINGS_PASSWORD_T_CN "Wi-Fi 密碼: " +#define WIFI_SETTINGS_CLOUD_T_CN "是否使用雲服務?" +#define WIFI_SETTINGS_CONFIG_T_CN "配置" +#define WIFI_SETTINGS_EDIT_T_CN "編輯" +#define WIFI_CONFIG_TIPS_T_CN "進行Wi-Fi配置?" + +#define OFFSET_TITLE_T_CN "機器參數>偏移設置" +#define OFFSET_X_T_CN "X軸與調平開關偏移" +#define OFFSET_Y_T_CN "Y軸與調平開關偏移" +#define OFFSET_Z_T_CN "Z軸與調平開關偏移" + +#define HOMING_SENSITIVITY_CONF_TITLE_T_CN "機器參數>靈敏度調節" +#define X_SENSITIVITY_T_CN "X軸靈敏度" +#define Y_SENSITIVITY_T_CN "Y軸靈敏度" +#define Z_SENSITIVITY_T_CN "Z軸靈敏度" +#define Z2_SENSITIVITY_T_CN "Z2軸靈敏度" + +#define ENCODER_CONF_TITLE_T_CN "機器參數>旋鈕設置" +#define ENCODER_CONF_TEXT_T_CN "是否使用旋鈕功能?" #define TOOL_TEXT_T_CN "工具" #define PREHEAT_TEXT_T_CN "預熱" @@ -398,10 +422,6 @@ #define STEP_5PERCENT_T_CN "5%%" #define STEP_10PERCENT_T_CN "10%%" -#define ZOFFSET_T_CN "Z Offset" -#define ZOFFSET_INC_T_CN "增加" -#define ZOFFSET_DEC_T_CN "減少" - #define TITLE_READYPRINT_T_CN "準備打印" #define TITLE_PREHEAT_T_CN "預熱" #define TITLE_MOVE_T_CN "移動" @@ -424,7 +444,6 @@ #define TITLE_CLOUD_TEXT_T_CN "雲服務" #define TITLE_DIALOG_CONFIRM_T_CN "確認" #define TITLE_FILESYS_T_CN "文件系統" -#define TITLE_ZOFFSET_T_CN "Z Offset" #define AUTO_SHUTDOWN_T_CN "自動關機" #define MANUAL_SHUTDOWN_T_CN "手動關機" diff --git a/Marlin/src/lcd/extui/lib/mks_ui/tft_fsmc.h b/Marlin/src/lcd/extui/lib/mks_ui/tft_fsmc.h index f7b0e0d310..b2e19d66f8 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/tft_fsmc.h +++ b/Marlin/src/lcd/extui/lib/mks_ui/tft_fsmc.h @@ -22,9 +22,9 @@ #pragma once #ifdef __cplusplus -extern "C" { /* C-declarations for C++ */ + extern "C" { /* C-declarations for C++ */ #endif #ifdef __cplusplus -} /* C-declarations for C++ */ + } /* C-declarations for C++ */ #endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/tft_lvgl_configuration.cpp b/Marlin/src/lcd/extui/lib/mks_ui/tft_lvgl_configuration.cpp index 23072d27c7..c2ff2c4362 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/tft_lvgl_configuration.cpp +++ b/Marlin/src/lcd/extui/lib/mks_ui/tft_lvgl_configuration.cpp @@ -35,14 +35,18 @@ #include "tft_lvgl_configuration.h" #include "draw_ready_print.h" + #include "pic_manager.h" #include "mks_hardware_test.h" #include "draw_ui.h" +#include "SPIFlashStorage.h" #include +#include "../../../../MarlinCore.h" #include "../../../../inc/MarlinConfig.h" #include HAL_PATH(../../HAL, tft/xpt2046.h) +#include "../../../ultralcd.h" XPT2046 touch; #if ENABLED(POWER_LOSS_RECOVERY) @@ -63,6 +67,7 @@ XPT2046 touch; #endif static lv_disp_buf_t disp_buf; +lv_group_t* g; #if ENABLED(SDSUPPORT) extern void UpdateAssets(); #endif @@ -89,306 +94,349 @@ extern uint8_t sel_id; extern uint8_t gcode_preview_over, flash_preview_begin, default_preview_flg; +uint8_t bmp_public_buf[17 * 1024]; + void SysTick_Callback() { lv_tick_inc(1); print_time_count(); -} - -#if DISABLED(TFT_LVGL_UI_SPI) - -extern void LCD_IO_Init(uint8_t cs, uint8_t rs); -extern void LCD_IO_WriteData(uint16_t RegValue); -extern void LCD_IO_WriteReg(uint16_t Reg); - -extern void LCD_IO_WriteMultiple(uint16_t color, uint32_t count); -void tft_set_cursor(uint16_t x, uint16_t y) { - LCD_IO_WriteReg(0x002A); - LCD_IO_WriteData(x >> 8); - LCD_IO_WriteData(x & 0x00FF); - LCD_IO_WriteData(x >> 8); - LCD_IO_WriteData(x & 0x00FF); - //ILI9488_WriteData(0x01); - //ILI9488_WriteData(0xDF); - LCD_IO_WriteReg(0x002B); - LCD_IO_WriteData(y >> 8); - LCD_IO_WriteData(y & 0x00FF); - LCD_IO_WriteData(y >> 8); - LCD_IO_WriteData(y & 0x00FF); - //ILI9488_WriteData(0x01); - //ILI9488_WriteData(0x3F); -} - -void LCD_WriteRAM_Prepare(void) { - #if 0 - switch (DeviceCode) { - case 0x9325: case 0x9328: case 0x8989: { - ClrCs - LCD->LCD_REG = R34; - SetCs - } break; - default: LCD_WrtReg(0x002C); + #if ENABLED(USE_WIFI_FUNCTION) + if (tips_disp.timer == TIPS_TIMER_START) { + tips_disp.timer_count++; } - #else - LCD_IO_WriteReg(0x002C); #endif + if (uiCfg.filament_loading_time_flg == 1) { + uiCfg.filament_loading_time_cnt++; + uiCfg.filament_rate = (uint32_t)(((uiCfg.filament_loading_time_cnt / (uiCfg.filament_loading_time * 1000.0)) * 100.0) + 0.5); + if (uiCfg.filament_loading_time_cnt >= (uiCfg.filament_loading_time * 1000)) { + uiCfg.filament_loading_time_cnt = 0; + uiCfg.filament_loading_time_flg = 0; + uiCfg.filament_loading_completed = 1; + } + } + if (uiCfg.filament_unloading_time_flg == 1) { + uiCfg.filament_unloading_time_cnt++; + uiCfg.filament_rate = (uint32_t)(((uiCfg.filament_unloading_time_cnt / (uiCfg.filament_unloading_time * 1000.0)) * 100.0) + 0.5); + if (uiCfg.filament_unloading_time_cnt >= (uiCfg.filament_unloading_time * 1000)) { + uiCfg.filament_unloading_time_cnt = 0; + uiCfg.filament_unloading_time_flg = 0; + uiCfg.filament_unloading_completed = 1; + uiCfg.filament_rate = 100; + } + } } -void tft_set_point(uint16_t x, uint16_t y, uint16_t point) { - //if (DeviceCode == 0x9488) { - if (x > (TFT_WIDTH) || y > (TFT_HEIGHT)) return; - //} - tft_set_cursor(x, y); - - LCD_WriteRAM_Prepare(); - //LCD_WriteRAM(point); - LCD_IO_WriteData(point); -} - -void LCD_WriteReg(uint16_t LCD_Reg, uint16_t LCD_RegValue) { - /* Write 16-bit Index, then Write Reg */ - ClrCs - LCD_IO_WriteReg(LCD_Reg); - /* Write 16-bit Reg */ - LCD_IO_WriteData(LCD_RegValue); - SetCs -} +#if DISABLED(TFT_LVGL_UI_SPI) -void ili9320_SetWindows(uint16_t StartX, uint16_t StartY, uint16_t width, uint16_t heigh) { - uint16_t s_h, s_l, e_h, e_l; - uint16_t xEnd, yEnd; - xEnd = StartX + width; - yEnd = StartY + heigh - 1; - if (DeviceCode == 0x8989) { - /*LCD_WriteReg(0x0044, (StartX & 0xFF) | (xEnd << 8)); - LCD_WriteReg(0x0045, StartY); - LCD_WriteReg(0x0046, yEnd);*/ - LCD_WriteReg(0x0044, (StartY & 0xFF) | (yEnd << 8)); - LCD_WriteReg(0x0045, StartX); - LCD_WriteReg(0x0046, xEnd); - } - else if (DeviceCode == 0x9488) { - s_h = (StartX >> 8) & 0x00ff; - s_l = StartX & 0x00ff; - e_h = ((StartX + width - 1) >> 8) & 0x00ff; - e_l = (StartX + width - 1) & 0x00ff; + extern void LCD_IO_Init(uint8_t cs, uint8_t rs); + extern void LCD_IO_WriteData(uint16_t RegValue); + extern void LCD_IO_WriteReg(uint16_t Reg); + extern void LCD_IO_WriteMultiple(uint16_t color, uint32_t count); + void tft_set_cursor(uint16_t x, uint16_t y) { LCD_IO_WriteReg(0x002A); - LCD_IO_WriteData(s_h); - LCD_IO_WriteData(s_l); - LCD_IO_WriteData(e_h); - LCD_IO_WriteData(e_l); - - s_h = (StartY >> 8) & 0x00ff; - s_l = StartY & 0x00ff; - e_h = ((StartY + heigh - 1) >> 8) & 0x00ff; - e_l = (StartY + heigh - 1) & 0x00ff; - + LCD_IO_WriteData(x >> 8); + LCD_IO_WriteData(x & 0x00FF); + LCD_IO_WriteData(x >> 8); + LCD_IO_WriteData(x & 0x00FF); + //ILI9488_WriteData(0x01); + //ILI9488_WriteData(0xDF); LCD_IO_WriteReg(0x002B); - LCD_IO_WriteData(s_h); - LCD_IO_WriteData(s_l); - LCD_IO_WriteData(e_h); - LCD_IO_WriteData(e_l); + LCD_IO_WriteData(y >> 8); + LCD_IO_WriteData(y & 0x00FF); + LCD_IO_WriteData(y >> 8); + LCD_IO_WriteData(y & 0x00FF); + //ILI9488_WriteData(0x01); + //ILI9488_WriteData(0x3F); } - else if ((DeviceCode == 0x9325) || (DeviceCode == 0x9328) || (DeviceCode == 0x1505)) { - /* LCD_WriteReg(0x0050, StartX); - LCD_WriteReg(0x0052, StartY); - LCD_WriteReg(0x0051, xEnd); - LCD_WriteReg(0x0053, yEnd);*/ - LCD_WriteReg(0x0050, StartY); // Specify the start/end positions of the window address in the horizontal direction by an address unit - LCD_WriteReg(0x0051, yEnd); // Specify the start positions of the window address in the vertical direction by an address unit - LCD_WriteReg(0x0052, (TFT_HEIGHT) - xEnd); - LCD_WriteReg(0x0053, (TFT_HEIGHT) - StartX - 1); // Specify the end positions of the window address in the vertical direction by an address unit + void LCD_WriteRAM_Prepare(void) { + #if 0 + switch (DeviceCode) { + case 0x9325: case 0x9328: case 0x8989: { + ClrCs + LCD->LCD_REG = R34; + SetCs + } break; + default: LCD_WrtReg(0x002C); + } + #else + LCD_IO_WriteReg(0x002C); + #endif } - else { - s_h = (StartX >> 8) & 0xFF; - s_l = StartX & 0xFF; - e_h = ((StartX + width - 1) >> 8) & 0xFF; - e_l = (StartX + width - 1) & 0xFF; - - LCD_IO_WriteReg(0x2A); - LCD_IO_WriteData(s_h); - LCD_IO_WriteData(s_l); - LCD_IO_WriteData(e_h); - LCD_IO_WriteData(e_l); - - s_h = (StartY >> 8) & 0xFF; - s_l = StartY & 0xFF; - e_h = ((StartY + heigh - 1) >> 8) & 0xFF; - e_l = (StartY + heigh - 1) & 0xFF; - - LCD_IO_WriteReg(0x2B); - LCD_IO_WriteData(s_h); - LCD_IO_WriteData(s_l); - LCD_IO_WriteData(e_h); - LCD_IO_WriteData(e_l); - } -} -void LCD_Clear(uint16_t Color) { - uint32_t index = 0; - unsigned int count; + void tft_set_point(uint16_t x, uint16_t y, uint16_t point) { + //if (DeviceCode == 0x9488) { + if (x > (TFT_WIDTH) || y > (TFT_HEIGHT)) return; + //} + tft_set_cursor(x, y); - if (DeviceCode == 0x9488) { - tft_set_cursor(0, 0); - ili9320_SetWindows(0, 0, TFT_WIDTH, TFT_HEIGHT); LCD_WriteRAM_Prepare(); - #ifdef LCD_USE_DMA_FSMC - LCD_IO_WriteMultiple(Color, (TFT_WIDTH) * (TFT_HEIGHT)); - #else - //index = (TFT_HEIGHT) / 2 * (TFT_WIDTH); - for (index = 0; index < (TFT_HEIGHT) * (TFT_WIDTH); index++) - LCD_IO_WriteData(Color); - #endif - //LCD_IO_WriteMultiple(Color, (TFT_WIDTH) * (TFT_HEIGHT)); - //while(index --) LCD_IO_WriteData(Color); - } - else if (DeviceCode == 0x5761) { - LCD_IO_WriteReg(0x002a); - LCD_IO_WriteData(0); - LCD_IO_WriteData(0); - LCD_IO_WriteData(HDP >> 8); - LCD_IO_WriteData(HDP & 0x00ff); - LCD_IO_WriteReg(0x002b); - LCD_IO_WriteData(0); - LCD_IO_WriteData(0); - LCD_IO_WriteData(VDP >> 8); - LCD_IO_WriteData(VDP & 0x00ff); - LCD_IO_WriteReg(0x002c); - LCD_IO_WriteReg(0x002c); - for (count = 0; count < (HDP + 1) * (VDP + 1); count++) - LCD_IO_WriteData(Color); - } - else { - tft_set_cursor(0, 0); - LCD_WriteRAM_Prepare(); /* Prepare to write GRAM */ - for (index = 0; index < 76800; index++) - LCD_IO_WriteData(Color); + //LCD_WriteRAM(point); + LCD_IO_WriteData(point); } -} - -#include HAL_PATH(../../HAL, tft/tft_fsmc.h) -extern TFT_IO tftio; -void init_tft() { - uint16_t i; - TERN_(HAS_LCD_CONTRAST, refresh_contrast()); + void LCD_WriteReg(uint16_t LCD_Reg, uint16_t LCD_RegValue) { + /* Write 16-bit Index, then Write Reg */ + ClrCs + LCD_IO_WriteReg(LCD_Reg); + /* Write 16-bit Reg */ + LCD_IO_WriteData(LCD_RegValue); + SetCs + } - #ifdef LCD_USE_DMA_FSMC - dma_init(FSMC_DMA_DEV); - dma_disable(FSMC_DMA_DEV, FSMC_DMA_CHANNEL); - dma_set_priority(FSMC_DMA_DEV, FSMC_DMA_CHANNEL, DMA_PRIORITY_MEDIUM); - #endif + void LCD_setWindowArea(uint16_t StartX, uint16_t StartY, uint16_t width, uint16_t heigh) { + uint16_t s_h, s_l, e_h, e_l; + uint16_t xEnd, yEnd; + xEnd = StartX + width; + yEnd = StartY + heigh - 1; + if (DeviceCode == 0x8989) { + /*LCD_WriteReg(0x0044, (StartX & 0xFF) | (xEnd << 8)); + LCD_WriteReg(0x0045, StartY); + LCD_WriteReg(0x0046, yEnd);*/ + LCD_WriteReg(0x0044, (StartY & 0xFF) | (yEnd << 8)); + LCD_WriteReg(0x0045, StartX); + LCD_WriteReg(0x0046, xEnd); + } + else if (DeviceCode == 0x9488) { + s_h = (StartX >> 8) & 0x00ff; + s_l = StartX & 0x00ff; + e_h = ((StartX + width - 1) >> 8) & 0x00ff; + e_l = (StartX + width - 1) & 0x00ff; + + LCD_IO_WriteReg(0x002A); + LCD_IO_WriteData(s_h); + LCD_IO_WriteData(s_l); + LCD_IO_WriteData(e_h); + LCD_IO_WriteData(e_l); + + s_h = (StartY >> 8) & 0x00ff; + s_l = StartY & 0x00ff; + e_h = ((StartY + heigh - 1) >> 8) & 0x00ff; + e_l = (StartY + heigh - 1) & 0x00ff; + + LCD_IO_WriteReg(0x002B); + LCD_IO_WriteData(s_h); + LCD_IO_WriteData(s_l); + LCD_IO_WriteData(e_h); + LCD_IO_WriteData(e_l); + } + else if ((DeviceCode == 0x9325) || (DeviceCode == 0x9328) || (DeviceCode == 0x1505)) { + /* LCD_WriteReg(0x0050, StartX); + LCD_WriteReg(0x0052, StartY); + LCD_WriteReg(0x0051, xEnd); + LCD_WriteReg(0x0053, yEnd);*/ + LCD_WriteReg(0x0050, StartY); // Specify the start/end positions of the window address in the horizontal direction by an address unit + LCD_WriteReg(0x0051, yEnd); // Specify the start positions of the window address in the vertical direction by an address unit + LCD_WriteReg(0x0052, (TFT_HEIGHT) - xEnd); + LCD_WriteReg(0x0053, (TFT_HEIGHT) - StartX - 1); // Specify the end positions of the window address in the vertical direction by an address unit - LCD_IO_Init(FSMC_CS_PIN, FSMC_RS_PIN); - - _delay_ms(5); - - DeviceCode = tftio.GetID() & 0xFFFF; - // Chitu and others - if (DeviceCode == 0x8066) DeviceCode = 0x9488; - - if (DeviceCode == 0x9488) { - LCD_IO_WriteReg(0x00E0); - LCD_IO_WriteData(0x0000); - LCD_IO_WriteData(0x0007); - LCD_IO_WriteData(0x000f); - LCD_IO_WriteData(0x000D); - LCD_IO_WriteData(0x001B); - LCD_IO_WriteData(0x000A); - LCD_IO_WriteData(0x003c); - LCD_IO_WriteData(0x0078); - LCD_IO_WriteData(0x004A); - LCD_IO_WriteData(0x0007); - LCD_IO_WriteData(0x000E); - LCD_IO_WriteData(0x0009); - LCD_IO_WriteData(0x001B); - LCD_IO_WriteData(0x001e); - LCD_IO_WriteData(0x000f); - - LCD_IO_WriteReg(0x00E1); - LCD_IO_WriteData(0x0000); - LCD_IO_WriteData(0x0022); - LCD_IO_WriteData(0x0024); - LCD_IO_WriteData(0x0006); - LCD_IO_WriteData(0x0012); - LCD_IO_WriteData(0x0007); - LCD_IO_WriteData(0x0036); - LCD_IO_WriteData(0x0047); - LCD_IO_WriteData(0x0047); - LCD_IO_WriteData(0x0006); - LCD_IO_WriteData(0x000a); - LCD_IO_WriteData(0x0007); - LCD_IO_WriteData(0x0030); - LCD_IO_WriteData(0x0037); - LCD_IO_WriteData(0x000f); - - LCD_IO_WriteReg(0x00C0); - LCD_IO_WriteData(0x0010); - LCD_IO_WriteData(0x0010); - - LCD_IO_WriteReg(0x00C1); - LCD_IO_WriteData(0x0041); - - LCD_IO_WriteReg(0x00C5); - LCD_IO_WriteData(0x0000); - LCD_IO_WriteData(0x0022); - LCD_IO_WriteData(0x0080); - - LCD_IO_WriteReg(0x0036); - //ILI9488_WriteData(0x0068); - //if (gCfgItems.overturn_180 != 0xEE) { - LCD_IO_WriteData(0x0068); - //} - //else { - //ILI9488_WriteData(0x00A8); - //} + } + else { + s_h = (StartX >> 8) & 0xFF; + s_l = StartX & 0xFF; + e_h = ((StartX + width - 1) >> 8) & 0xFF; + e_l = (StartX + width - 1) & 0xFF; + + LCD_IO_WriteReg(0x2A); + LCD_IO_WriteData(s_h); + LCD_IO_WriteData(s_l); + LCD_IO_WriteData(e_h); + LCD_IO_WriteData(e_l); + + s_h = (StartY >> 8) & 0xFF; + s_l = StartY & 0xFF; + e_h = ((StartY + heigh - 1) >> 8) & 0xFF; + e_l = (StartY + heigh - 1) & 0xFF; + + LCD_IO_WriteReg(0x2B); + LCD_IO_WriteData(s_h); + LCD_IO_WriteData(s_l); + LCD_IO_WriteData(e_h); + LCD_IO_WriteData(e_l); + } + } - LCD_IO_WriteReg(0x003A); //Interface Mode Control - LCD_IO_WriteData(0x0055); + void LCD_Clear(uint16_t Color) { + uint32_t index = 0; + unsigned int count; - LCD_IO_WriteReg(0x00B0); //Interface Mode Control - LCD_IO_WriteData(0x0000); - LCD_IO_WriteReg(0x00B1); //Frame rate 70HZ - LCD_IO_WriteData(0x00B0); - LCD_IO_WriteData(0x0011); - LCD_IO_WriteReg(0x00B4); - LCD_IO_WriteData(0x0002); - LCD_IO_WriteReg(0x00B6); //RGB/MCU Interface Control - LCD_IO_WriteData(0x0002); - LCD_IO_WriteData(0x0042); + if (DeviceCode == 0x9488) { + tft_set_cursor(0, 0); + LCD_setWindowArea(0, 0, TFT_WIDTH, TFT_HEIGHT); + LCD_WriteRAM_Prepare(); + #ifdef LCD_USE_DMA_FSMC + LCD_IO_WriteMultiple(Color, (TFT_WIDTH) * (TFT_HEIGHT)); + #else + //index = (TFT_HEIGHT) / 2 * (TFT_WIDTH); + for (index = 0; index < (TFT_HEIGHT) * (TFT_WIDTH); index++) + LCD_IO_WriteData(Color); + #endif + //LCD_IO_WriteMultiple(Color, (TFT_WIDTH) * (TFT_HEIGHT)); + //while(index --) LCD_IO_WriteData(Color); + } + else if (DeviceCode == 0x5761) { + LCD_IO_WriteReg(0x002a); + LCD_IO_WriteData(0); + LCD_IO_WriteData(0); + LCD_IO_WriteData(HDP >> 8); + LCD_IO_WriteData(HDP & 0x00ff); + LCD_IO_WriteReg(0x002b); + LCD_IO_WriteData(0); + LCD_IO_WriteData(0); + LCD_IO_WriteData(VDP >> 8); + LCD_IO_WriteData(VDP & 0x00ff); + LCD_IO_WriteReg(0x002c); + LCD_IO_WriteReg(0x002c); + for (count = 0; count < (HDP + 1) * (VDP + 1); count++) + LCD_IO_WriteData(Color); + } + else { + tft_set_cursor(0, 0); + LCD_WriteRAM_Prepare(); /* Prepare to write GRAM */ + for (index = 0; index < 76800; index++) + LCD_IO_WriteData(Color); + } + } - LCD_IO_WriteReg(0x00B7); - LCD_IO_WriteData(0x00C6); + #include HAL_PATH(../../HAL, tft/tft_fsmc.h) + extern TFT_IO tftio; + void fsmc_tft_init() { + uint16_t i; - //WriteComm(0xBE); - //WriteData(0x00); - //WriteData(0x04); + TERN_(HAS_LCD_CONTRAST, refresh_contrast()); - LCD_IO_WriteReg(0x00E9); - LCD_IO_WriteData(0x0000); + #ifdef LCD_USE_DMA_FSMC + dma_init(FSMC_DMA_DEV); + dma_disable(FSMC_DMA_DEV, FSMC_DMA_CHANNEL); + dma_set_priority(FSMC_DMA_DEV, FSMC_DMA_CHANNEL, DMA_PRIORITY_MEDIUM); + #endif - LCD_IO_WriteReg(0x00F7); - LCD_IO_WriteData(0x00A9); - LCD_IO_WriteData(0x0051); - LCD_IO_WriteData(0x002C); - LCD_IO_WriteData(0x0082); + LCD_IO_Init(FSMC_CS_PIN, FSMC_RS_PIN); + + _delay_ms(5); + + DeviceCode = tftio.GetID() & 0xFFFF; + // Chitu and others + if (DeviceCode == 0x8066) DeviceCode = 0x9488; + + if (DeviceCode == 0x9488) { + LCD_IO_WriteReg(0x00E0); + LCD_IO_WriteData(0x0000); + LCD_IO_WriteData(0x0007); + LCD_IO_WriteData(0x000f); + LCD_IO_WriteData(0x000D); + LCD_IO_WriteData(0x001B); + LCD_IO_WriteData(0x000A); + LCD_IO_WriteData(0x003c); + LCD_IO_WriteData(0x0078); + LCD_IO_WriteData(0x004A); + LCD_IO_WriteData(0x0007); + LCD_IO_WriteData(0x000E); + LCD_IO_WriteData(0x0009); + LCD_IO_WriteData(0x001B); + LCD_IO_WriteData(0x001e); + LCD_IO_WriteData(0x000f); + + LCD_IO_WriteReg(0x00E1); + LCD_IO_WriteData(0x0000); + LCD_IO_WriteData(0x0022); + LCD_IO_WriteData(0x0024); + LCD_IO_WriteData(0x0006); + LCD_IO_WriteData(0x0012); + LCD_IO_WriteData(0x0007); + LCD_IO_WriteData(0x0036); + LCD_IO_WriteData(0x0047); + LCD_IO_WriteData(0x0047); + LCD_IO_WriteData(0x0006); + LCD_IO_WriteData(0x000a); + LCD_IO_WriteData(0x0007); + LCD_IO_WriteData(0x0030); + LCD_IO_WriteData(0x0037); + LCD_IO_WriteData(0x000f); + + LCD_IO_WriteReg(0x00C0); + LCD_IO_WriteData(0x0010); + LCD_IO_WriteData(0x0010); + + LCD_IO_WriteReg(0x00C1); + LCD_IO_WriteData(0x0041); + + LCD_IO_WriteReg(0x00C5); + LCD_IO_WriteData(0x0000); + LCD_IO_WriteData(0x0022); + LCD_IO_WriteData(0x0080); + + LCD_IO_WriteReg(0x0036); + LCD_IO_WriteData(TERN(GRAPHICAL_TFT_ROTATE_180, 0xE8, 0x0068)); + + LCD_IO_WriteReg(0x003A); //Interface Mode Control + LCD_IO_WriteData(0x0055); + + LCD_IO_WriteReg(0x00B0); //Interface Mode Control + LCD_IO_WriteData(0x0000); + LCD_IO_WriteReg(0x00B1); //Frame rate 70HZ + LCD_IO_WriteData(0x00B0); + LCD_IO_WriteData(0x0011); + LCD_IO_WriteReg(0x00B4); + LCD_IO_WriteData(0x0002); + LCD_IO_WriteReg(0x00B6); //RGB/MCU Interface Control + LCD_IO_WriteData(0x0002); + LCD_IO_WriteData(0x0042); + + LCD_IO_WriteReg(0x00B7); + LCD_IO_WriteData(0x00C6); + + //WriteComm(0xBE); + //WriteData(0x00); + //WriteData(0x04); + + LCD_IO_WriteReg(0x00E9); + LCD_IO_WriteData(0x0000); + + LCD_IO_WriteReg(0x00F7); + LCD_IO_WriteData(0x00A9); + LCD_IO_WriteData(0x0051); + LCD_IO_WriteData(0x002C); + LCD_IO_WriteData(0x0082); + + LCD_IO_WriteReg(0x0011); + for (i = 0; i < 65535; i++) { /* do nothing */ } + LCD_IO_WriteReg(0x0029); + + LCD_setWindowArea(0, 0, TFT_WIDTH, TFT_HEIGHT); + + OUT_WRITE(LCD_BACKLIGHT_PIN, LOW); + LCD_Clear(0x0000); + + TERN_(HAS_LOGO_IN_FLASH, lcd_draw_logo()); + + OUT_WRITE(LCD_BACKLIGHT_PIN, HIGH); + delay(2000); + } + } - LCD_IO_WriteReg(0x0011); - for (i = 0; i < 65535; i++); - LCD_IO_WriteReg(0x0029); + extern void LCD_IO_WriteSequence(uint16_t *data, uint16_t length); - ili9320_SetWindows(0, 0, TFT_WIDTH, TFT_HEIGHT); - LCD_Clear(0x0000); + void lcd_draw_logo() { + LCD_setWindowArea(0, 0, TFT_WIDTH, TFT_HEIGHT); + LCD_WriteRAM_Prepare(); - OUT_WRITE(LCD_BACKLIGHT_PIN, HIGH); + for (uint16_t i = 0; i < (TFT_HEIGHT); i ++) { + Pic_Logo_Read((uint8_t *)"", (uint8_t *)bmp_public_buf, (TFT_WIDTH) * 2); + #ifdef LCD_USE_DMA_FSMC + LCD_IO_WriteSequence((uint16_t *)bmp_public_buf, TFT_WIDTH); + #else + int index = 0;,x_off = 0; + for (x_off = 0; x_off < TFT_WIDTH; x_off++) { + LCD_IO_WriteData((uint16_t)bmp_public_buf[index]); + index += 2; + } + #endif + } } -} #endif // !TFT_LVGL_UI_SPI -extern uint8_t bmp_public_buf[17 * 1024]; - void tft_lvgl_init() { //uint16_t test_id=0; @@ -404,16 +452,15 @@ void tft_lvgl_init() { SPI_TFT.spi_init(SPI_FULL_SPEED); SPI_TFT.LCD_init(); #else - init_tft(); + fsmc_tft_init(); #endif + //spi_flash_read_test(); #if ENABLED(SDSUPPORT) UpdateAssets(); #endif mks_test_get(); - //spi_flash_read_test(); - touch.Init(); lv_init(); @@ -432,6 +479,36 @@ void tft_lvgl_init() { indev_drv.read_cb = my_touchpad_read; /*Set your driver function*/ lv_indev_drv_register(&indev_drv); /*Finally register the driver*/ + #if HAS_ROTARY_ENCODER + g = lv_group_create(); + lv_indev_drv_t enc_drv; + lv_indev_drv_init(&enc_drv); + enc_drv.type = LV_INDEV_TYPE_ENCODER; + enc_drv.read_cb = my_mousewheel_read; + lv_indev_t * enc_indev = lv_indev_drv_register(&enc_drv); + lv_indev_set_group(enc_indev, g); + #endif + + lv_fs_drv_t spi_flash_drv; + lv_fs_drv_init(&spi_flash_drv); + spi_flash_drv.letter = 'F'; + spi_flash_drv.open_cb = spi_flash_open_cb; + spi_flash_drv.close_cb = spi_flash_close_cb; + spi_flash_drv.read_cb = spi_flash_read_cb; + spi_flash_drv.seek_cb = spi_flash_seek_cb; + spi_flash_drv.tell_cb = spi_flash_tell_cb; + lv_fs_drv_register(&spi_flash_drv); + + lv_fs_drv_t sd_drv; + lv_fs_drv_init(&sd_drv); + sd_drv.letter = 'S'; + sd_drv.open_cb = sd_open_cb; + sd_drv.close_cb = sd_close_cb; + sd_drv.read_cb = sd_read_cb; + sd_drv.seek_cb = sd_seek_cb; + sd_drv.tell_cb = sd_tell_cb; + lv_fs_drv_register(&sd_drv); + systick_attach_callback(SysTick_Callback); #if HAS_SPI_FLASH_FONT @@ -442,7 +519,10 @@ void tft_lvgl_init() { filament_pin_setup(); + lv_encoder_pin_init(); + #if ENABLED(POWER_LOSS_RECOVERY) + recovery.load(); if (recovery.valid()) { if (gCfgItems.from_flash_pic == 1) flash_preview_begin = 1; @@ -486,16 +566,16 @@ void my_disp_flush(lv_disp_drv_t * disp, const lv_area_t * area, lv_color_t * co #if 1 uint16_t i, width, height; - uint16_t clr_temp; + //uint16_t clr_temp; width = area->x2 - area->x1 + 1; height = area->y2 - area->y1 + 1; - ili9320_SetWindows((uint16_t)area->x1, (uint16_t)area->y1, width, height); + LCD_setWindowArea((uint16_t)area->x1, (uint16_t)area->y1, width, height); LCD_WriteRAM_Prepare(); for (i = 0; i < width * height - 2; i++) { - clr_temp = (uint16_t)(((uint16_t)color_p->ch.red << 11) - | ((uint16_t)color_p->ch.green << 5) - | ((uint16_t)color_p->ch.blue)); - LCD_IO_WriteData(clr_temp); + //clr_temp = (uint16_t)(((uint16_t)color_p->ch.red << 11) + //| ((uint16_t)color_p->ch.green << 5) + //| ((uint16_t)color_p->ch.blue)); + LCD_IO_WriteData(color_p->full); color_p++; } @@ -507,8 +587,6 @@ void my_disp_flush(lv_disp_drv_t * disp, const lv_area_t * area, lv_color_t * co #define TICK_CYCLE 1 -static int32_t touch_time1 = 0; - unsigned int getTickDiff(unsigned int curTick, unsigned int lastTick) { return TICK_CYCLE * (lastTick <= curTick ? (curTick - lastTick) : (0xFFFFFFFF - lastTick + curTick)); } @@ -522,15 +600,17 @@ static bool get_point(int16_t *x, int16_t *y) { } #if ENABLED(GRAPHICAL_TFT_ROTATE_180) - x = (TFT_WIDTH) - x; - y = (TFT_HEIGHT) - y; + *x = int16_t((TFT_WIDTH) - (int)(*x)); + *y = int16_t((TFT_HEIGHT) - (int)(*y)); #endif return is_touched; } -static int16_t last_x = 0, last_y = 0; bool my_touchpad_read(lv_indev_drv_t * indev_driver, lv_indev_data_t * data) { + static int16_t last_x = 0, last_y = 0; + static uint8_t last_touch_state = LV_INDEV_STATE_REL; + static int32_t touch_time1 = 0; uint32_t tmpTime, diffTime = 0; tmpTime = millis(); @@ -540,9 +620,10 @@ bool my_touchpad_read(lv_indev_drv_t * indev_driver, lv_indev_data_t * data) { //if (data->state == LV_INDEV_STATE_PR) ADS7843_Rd_Addata((u16 *)&last_x, (u16 *)&last_y); //touchpad_get_xy(&last_x, &last_y); /*Save the pressed coordinates and the state*/ - if (diffTime > 10) { + if (diffTime > 20) { if (get_point(&last_x, &last_y)) { + if (last_touch_state == LV_INDEV_STATE_PR) return false; data->state = LV_INDEV_STATE_PR; // Set the coordinates (if released use the last-pressed coordinates) @@ -551,9 +632,13 @@ bool my_touchpad_read(lv_indev_drv_t * indev_driver, lv_indev_data_t * data) { data->point.y = last_y; last_x = last_y = 0; + last_touch_state = LV_INDEV_STATE_PR; + } + else { + if (last_touch_state == LV_INDEV_STATE_PR) + data->state = LV_INDEV_STATE_REL; + last_touch_state = LV_INDEV_STATE_REL; } - else - data->state = LV_INDEV_STATE_REL; touch_time1 = tmpTime; } @@ -561,4 +646,234 @@ bool my_touchpad_read(lv_indev_drv_t * indev_driver, lv_indev_data_t * data) { return false; // Return `false` since no data is buffering or left to read } +int16_t enc_diff = 0; +lv_indev_state_t state = LV_INDEV_STATE_REL; + +bool my_mousewheel_read(lv_indev_drv_t * indev_drv, lv_indev_data_t * data) { + (void) indev_drv; /*Unused*/ + + data->state = state; + data->enc_diff = enc_diff; + enc_diff = 0; + + return false; /*No more data to read so return false*/ +} + +extern uint8_t currentFlashPage; + +//spi_flash +uint32_t pic_read_base_addr = 0, pic_read_addr_offset = 0; +lv_fs_res_t spi_flash_open_cb (lv_fs_drv_t * drv, void * file_p, const char * path, lv_fs_mode_t mode) { + static char last_path_name[30]; + if (strcasecmp(last_path_name,path) != 0) { + pic_read_base_addr = lv_get_pic_addr((uint8_t *)path); + ZERO(last_path_name); + strcpy(last_path_name,path); + } + else { + W25QXX.init(SPI_QUARTER_SPEED); + currentFlashPage = 0; + } + pic_read_addr_offset = pic_read_base_addr; + return LV_FS_RES_OK; +} + +lv_fs_res_t spi_flash_close_cb (lv_fs_drv_t * drv, void * file_p) { + lv_fs_res_t res = LV_FS_RES_OK; + /* Add your code here*/ + pic_read_addr_offset = pic_read_base_addr; + return res; +} + +lv_fs_res_t spi_flash_read_cb (lv_fs_drv_t * drv, void * file_p, void * buf, uint32_t btr, uint32_t * br) { + lv_pic_test((uint8_t *)buf, pic_read_addr_offset, btr); + *br = btr; + return LV_FS_RES_OK; +} + +lv_fs_res_t spi_flash_seek_cb(lv_fs_drv_t * drv, void * file_p, uint32_t pos) { + #if HAS_SPI_FLASH_COMPRESSION + if (pos == 4) { + uint8_t bmp_header[4]; + SPIFlash.beginRead(pic_read_base_addr); + SPIFlash.readData(bmp_header, 4); + currentFlashPage = 1; + } + pic_read_addr_offset = pic_read_base_addr; + #else + pic_read_addr_offset = pic_read_base_addr + pos; + #endif + return LV_FS_RES_OK; +} + +lv_fs_res_t spi_flash_tell_cb(lv_fs_drv_t * drv, void * file_p, uint32_t * pos_p) { + *pos_p = pic_read_addr_offset - pic_read_base_addr; + return LV_FS_RES_OK; +} + +//sd +char *cur_namefff; +uint32_t sd_read_base_addr = 0,sd_read_addr_offset = 0; +lv_fs_res_t sd_open_cb (lv_fs_drv_t * drv, void * file_p, const char * path, lv_fs_mode_t mode) { + //cur_namefff = strrchr(path, '/'); + char name_buf[100]; + ZERO(name_buf); + strcat(name_buf,"/"); + strcat(name_buf,path); + char *temp = strstr(name_buf,".bin"); + if (temp) { strcpy(temp,".GCO"); } + sd_read_base_addr = lv_open_gcode_file((char *)name_buf); + sd_read_addr_offset = sd_read_base_addr; + if (sd_read_addr_offset == 0) return LV_FS_RES_NOT_EX; + return LV_FS_RES_OK; +} + +lv_fs_res_t sd_close_cb (lv_fs_drv_t * drv, void * file_p) { + /* Add your code here*/ + lv_close_gcode_file(); + return LV_FS_RES_OK; +} + +lv_fs_res_t sd_read_cb (lv_fs_drv_t * drv, void * file_p, void * buf, uint32_t btr, uint32_t * br) { + if (btr == 200) { + lv_gcode_file_read((uint8_t *)buf); + //pic_read_addr_offset += 208; + *br = 200; + } + else if (btr == 4) { + uint8_t header_pic[4] = { 0x04, 0x90, 0x81, 0x0C }; + memcpy(buf, header_pic, 4); + //pic_read_addr_offset += 4; + *br = 4; + } + return LV_FS_RES_OK; +} + +lv_fs_res_t sd_seek_cb(lv_fs_drv_t * drv, void * file_p, uint32_t pos) { + sd_read_addr_offset = sd_read_base_addr + (pos - 4) / 200 * 409; + lv_gcode_file_seek(sd_read_addr_offset); + return LV_FS_RES_OK; +} + +lv_fs_res_t sd_tell_cb(lv_fs_drv_t * drv, void * file_p, uint32_t * pos_p) { + if (sd_read_addr_offset) *pos_p = 0; + else *pos_p = (sd_read_addr_offset - sd_read_base_addr) / 409 * 200 + 4; + return LV_FS_RES_OK; +} + +void lv_encoder_pin_init() { + #if 1 // HAS_DIGITAL_BUTTONS + + #if BUTTON_EXISTS(EN1) + SET_INPUT_PULLUP(BTN_EN1); + #endif + #if BUTTON_EXISTS(EN2) + SET_INPUT_PULLUP(BTN_EN2); + #endif + #if BUTTON_EXISTS(ENC) + SET_INPUT_PULLUP(BTN_ENC); + #endif + + #if BUTTON_EXISTS(BACK) + SET_INPUT_PULLUP(BTN_BACK); + #endif + + #if BUTTON_EXISTS(UP) + SET_INPUT(BTN_UP); + #endif + #if BUTTON_EXISTS(DWN) + SET_INPUT(BTN_DWN); + #endif + #if BUTTON_EXISTS(LFT) + SET_INPUT(BTN_LFT); + #endif + #if BUTTON_EXISTS(RT) + SET_INPUT(BTN_RT); + #endif + + #endif // HAS_DIGITAL_BUTTONS +} + +#if 1 // HAS_ENCODER_ACTION + + //static const int8_t encoderDirection = 1; + //static int16_t enc_Direction; + void lv_update_encoder() { + static uint8_t buttons; + static uint32_t encoder_time1; + uint32_t tmpTime, diffTime = 0; + tmpTime = millis(); + diffTime = getTickDiff(tmpTime, encoder_time1); + if (diffTime > 50) { + + #if ANY_BUTTON(EN1, EN2, ENC, BACK) + + uint8_t newbutton = 0; + + #if BUTTON_EXISTS(EN1) + if (BUTTON_PRESSED(EN1)) newbutton |= EN_A; + #endif + #if BUTTON_EXISTS(EN2) + if (BUTTON_PRESSED(EN2)) newbutton |= EN_B; + #endif + #if BUTTON_EXISTS(ENC) + if (BUTTON_PRESSED(ENC)) newbutton |= EN_C; + #endif + #if BUTTON_EXISTS(BACK) + if (BUTTON_PRESSED(BACK)) newbutton |= EN_D; + #endif + + #else + + constexpr uint8_t newbutton = 0; + + #endif + + buttons = newbutton; + + #if HAS_ENCODER_WHEEL + static uint8_t lastEncoderBits; + + #define encrot0 0 + #define encrot1 1 + #define encrot2 2 + + // Manage encoder rotation + //#define ENCODER_SPIN(_E1, _E2) switch (lastEncoderBits) { case _E1: enc_Direction += encoderDirection; break; case _E2: enc_Direction -= encoderDirection; } + + uint8_t enc = 0; + if (buttons & EN_A) enc |= B01; + if (buttons & EN_B) enc |= B10; + if (enc != lastEncoderBits) { + switch (enc) { + case encrot1: + if (lastEncoderBits == encrot0) { + enc_diff--; + encoder_time1 = tmpTime; + } + break; + case encrot2: + if (lastEncoderBits == encrot0) { + enc_diff++; + encoder_time1 = tmpTime; + } + break; + } + lastEncoderBits = enc; + } + static uint8_t last_button_state = LV_INDEV_STATE_REL; + const uint8_t enc_c = (buttons & EN_C) ? LV_INDEV_STATE_PR : LV_INDEV_STATE_REL; + if (enc_c != last_button_state) { + state = enc_c ? LV_INDEV_STATE_PR : LV_INDEV_STATE_REL; + + last_button_state = enc_c; + } + + #endif // HAS_ENCODER_WHEEL + + } // next_button_update_ms + } + +#endif // HAS_ENCODER_ACTION + #endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/tft_lvgl_configuration.h b/Marlin/src/lcd/extui/lib/mks_ui/tft_lvgl_configuration.h index 1b33d6e6bf..7e24f948fd 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/tft_lvgl_configuration.h +++ b/Marlin/src/lcd/extui/lib/mks_ui/tft_lvgl_configuration.h @@ -22,25 +22,44 @@ #pragma once /** - * @file tft_lvgl_configuration.h - * @date 2020-02-21 - * */ + * @file lcd/extui/lib/mks_ui/tft_lvgl_configuration.h + * @date 2020-02-21 + */ -//#ifdef __cplusplus -//extern "C" { -//#endif +#ifdef __cplusplus + extern "C" { /* C-declarations for C++ */ +#endif #include -void tft_lvgl_init(); -void my_disp_flush(lv_disp_drv_t * disp, const lv_area_t * area, lv_color_t * color_p); -bool my_touchpad_read(lv_indev_drv_t * indev_driver, lv_indev_data_t * data); +//#define GRAPHICAL_TFT_ROTATE_180 +#define USE_WIFI_FUNCTION 0 + +extern void tft_lvgl_init(); +extern void my_disp_flush(lv_disp_drv_t * disp, const lv_area_t * area, lv_color_t * color_p); +extern bool my_touchpad_read(lv_indev_drv_t * indev_driver, lv_indev_data_t * data); +extern bool my_mousewheel_read(lv_indev_drv_t * indev_drv, lv_indev_data_t * data); + +extern void LCD_Clear(uint16_t Color); +extern void tft_set_point(uint16_t x, uint16_t y, uint16_t point); +extern void LCD_setWindowArea(uint16_t StartX, uint16_t StartY, uint16_t width, uint16_t heigh); +extern void LCD_WriteRAM_Prepare(void); +extern void lcd_draw_logo(); +extern void lv_encoder_pin_init(); +extern void lv_update_encoder(); + +extern lv_fs_res_t spi_flash_open_cb (lv_fs_drv_t * drv, void * file_p, const char * path, lv_fs_mode_t mode); +extern lv_fs_res_t spi_flash_close_cb (lv_fs_drv_t * drv, void * file_p); +extern lv_fs_res_t spi_flash_read_cb (lv_fs_drv_t * drv, void * file_p, void * buf, uint32_t btr, uint32_t * br); +extern lv_fs_res_t spi_flash_seek_cb(lv_fs_drv_t * drv, void * file_p, uint32_t pos); +extern lv_fs_res_t spi_flash_tell_cb(lv_fs_drv_t * drv, void * file_p, uint32_t * pos_p); -void LCD_Clear(uint16_t Color); -void tft_set_point(uint16_t x, uint16_t y, uint16_t point); -void ili9320_SetWindows(uint16_t StartX, uint16_t StartY, uint16_t width, uint16_t heigh); -void LCD_WriteRAM_Prepare(void); +extern lv_fs_res_t sd_open_cb (lv_fs_drv_t * drv, void * file_p, const char * path, lv_fs_mode_t mode); +extern lv_fs_res_t sd_close_cb (lv_fs_drv_t * drv, void * file_p); +extern lv_fs_res_t sd_read_cb (lv_fs_drv_t * drv, void * file_p, void * buf, uint32_t btr, uint32_t * br); +extern lv_fs_res_t sd_seek_cb(lv_fs_drv_t * drv, void * file_p, uint32_t pos); +extern lv_fs_res_t sd_tell_cb(lv_fs_drv_t * drv, void * file_p, uint32_t * pos_p); -//#ifdef __cplusplus -//} /* extern "C" */ -//#endif +#ifdef __cplusplus + } /* C-declarations for C++ */ +#endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/tft_multi_language.cpp b/Marlin/src/lcd/extui/lib/mks_ui/tft_multi_language.cpp index 1ea47cef2d..e230195eab 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/tft_multi_language.cpp +++ b/Marlin/src/lcd/extui/lib/mks_ui/tft_multi_language.cpp @@ -54,11 +54,8 @@ dialog_menu_def dialog_menu; language_menu_def language_menu; print_file_dialog_menu_def print_file_dialog_menu; filesys_menu_def filesys_menu; -zoffset_menu_def zoffset_menu; tool_menu_def tool_menu; MachinePara_menu_def MachinePara_menu; -MachineSettings_menu_def MachineSettings_menu; -TemperatureSettings_menu_def TemperatureSettings_menu; pause_msg_def pause_msg_menu; eeprom_def eeprom_menu; @@ -67,8 +64,8 @@ void machine_setting_disp() { if (gCfgItems.language == LANG_SIMPLE_CHINESE) { MachinePara_menu.title = MACHINE_PARA_TITLE_CN; MachinePara_menu.MachineSetting = MACHINE_TYPE_CNOFIG_CN; - MachinePara_menu.TemperatureSetting = TEMPERATURE_CONFIG_CN; MachinePara_menu.MotorSetting = MOTOR_CONFIG_CN; + MachinePara_menu.leveling = MACHINE_LEVELING_CONFIG_CN; MachinePara_menu.AdvanceSetting = ADVANCE_CONFIG_CN; machine_menu.default_value = DEFAULT_CN; @@ -81,7 +78,6 @@ void machine_setting_disp() { machine_menu.HomeDir = MACHINE_HOMEDIR_CN; machine_menu.EndStopType = MACHINE_ENDSTOP_TYPE_CN; machine_menu.FilamentConf = MACHINE_FILAMENT_CONFIG_CN; - machine_menu.LevelingConf = MACHINE_LEVELING_CONFIG_CN; machine_menu.MachineTypeConfTitle = MACHINE_TYPE_CONFIG_TITLE_CN; machine_menu.xyz = MACHINE_TYPE_XYZ_CN; @@ -116,18 +112,18 @@ void machine_setting_disp() { machine_menu.opened = ENDSTOP_OPENED_CN; machine_menu.closed = ENDSTOP_CLOSED_CN; - machine_menu.FilamentConfTitle = FILAMENT_CONF_TITLE_CN; - machine_menu.InTemperature = FILAMENT_IN_TEMPERATURE_CN; - machine_menu.InLength = FILAMENT_IN_LENGTH_CN; - machine_menu.InSpeed = FILAMENT_IN_SPEED_CN; - machine_menu.OutTemperature = FILAMENT_OUT_TEMPERATURE_CN; - machine_menu.OutLength = FILAMENT_OUT_LENGTH_CN; - machine_menu.OutSpeed = FILAMENT_OUT_SPEED_CN; + machine_menu.FilamentConfTitle = FILAMENT_CONF_TITLE_CN; + machine_menu.InLength = FILAMENT_IN_LENGTH_CN; + machine_menu.InSpeed = FILAMENT_IN_SPEED_CN; + machine_menu.FilamentTemperature = FILAMENT_TEMPERATURE_CN; + machine_menu.OutLength = FILAMENT_OUT_LENGTH_CN; + machine_menu.OutSpeed = FILAMENT_OUT_SPEED_CN; - machine_menu.LevelingParaConfTitle = LEVELING_CONF_TITLE_CN; - machine_menu.LevelingParaConf = LEVELING_PARA_CONF_CN; - machine_menu.DeltaLevelConf = LEVELING_DELTA_CN; - machine_menu.XYZLevelconf = LEVELING_XYZ_CN; + machine_menu.LevelingParaConfTitle = LEVELING_CONF_TITLE_CN; + machine_menu.LevelingParaConf = LEVELING_PARA_CONF_CN; + machine_menu.LevelingManuPosConf = LEVELING_MANUAL_POS_CN; + machine_menu.LevelingAutoCommandConf = LEVELING_AUTO_COMMAND_CN; + machine_menu.LevelingAutoZoffsetConf = LEVELING_AUTO_ZOFFSET_CN; machine_menu.LevelingSubConfTitle = LEVELING_PARA_CONF_TITLE_CN; machine_menu.AutoLevelEnable = AUTO_LEVELING_ENABLE_CN; @@ -177,16 +173,19 @@ void machine_setting_disp() { machine_menu.HotbedMinTemperature = HOTBED_MIN_TEMPERATURE_CN; machine_menu.HotbedMaxTemperature = HOTBED_MAX_TEMPERATURE_CN; - machine_menu.MotorConfTitle = MOTOR_CONF_TITLE_CN; - machine_menu.MaxFeedRateConf = MAXFEEDRATE_CONF_CN; - machine_menu.AccelerationConf = ACCELERATION_CONF_CN; - machine_menu.JerkConf = JERKCONF_CN; - machine_menu.StepsConf = STEPSCONF_CN; - machine_menu.TMCcurrentConf = TMC_CURRENT_CN; - machine_menu.TMCStepModeConf = TMC_STEP_MODE_CN; - machine_menu.MotorDirConf = MOTORDIRCONF_CN; - machine_menu.HomeFeedRateConf = HOMEFEEDRATECONF_CN; - machine_menu.PausePosition = PAUSE_POSITION_CN; + machine_menu.MotorConfTitle = MOTOR_CONF_TITLE_CN; + machine_menu.MaxFeedRateConf = MAXFEEDRATE_CONF_CN; + machine_menu.AccelerationConf = ACCELERATION_CONF_CN; + machine_menu.JerkConf = JERKCONF_CN; + machine_menu.StepsConf = STEPSCONF_CN; + machine_menu.TMCcurrentConf = TMC_CURRENT_CN; + machine_menu.TMCStepModeConf = TMC_STEP_MODE_CN; + machine_menu.MotorDirConf = MOTORDIRCONF_CN; + machine_menu.HomeFeedRateConf = HOMEFEEDRATECONF_CN; + machine_menu.PausePosition = PAUSE_POSITION_CN; + machine_menu.WifiSettings = WIFI_SETTINGS_CN; + machine_menu.HomingSensitivityConf = HOMING_SENSITIVITY_CONF_CN; + machine_menu.EncoderSettings = ENCODER_SETTINGS_CN; machine_menu.MaxFeedRateConfTitle = MAXFEEDRATE_CONF_TITLE_CN; machine_menu.XMaxFeedRate = X_MAXFEEDRATE_CN; @@ -268,16 +267,38 @@ void machine_setting_disp() { machine_menu.key_reset = KEY_REST_CN; machine_menu.key_confirm = KEY_CONFIRM_CN; - machine_menu.PausePosText = PAUSE_POSITION_CN; - machine_menu.xPos = PAUSE_POSITION_X_CN; - machine_menu.yPos = PAUSE_POSITION_Y_CN; - machine_menu.zPos = PAUSE_POSITION_Z_CN; + machine_menu.PausePosText = PAUSE_POSITION_CN; + machine_menu.xPos = PAUSE_POSITION_X_CN; + machine_menu.yPos = PAUSE_POSITION_Y_CN; + machine_menu.zPos = PAUSE_POSITION_Z_CN; + machine_menu.WifiConfTitle = WIFI_SETTINGS_TITLE_CN; + machine_menu.wifiMode = WIFI_SETTINGS_MODE_CN; + machine_menu.wifiName = WIFI_SETTINGS_NAME_CN; + machine_menu.wifiPassWord = WIFI_SETTINGS_PASSWORD_CN; + machine_menu.wifiCloud = WIFI_SETTINGS_CLOUD_CN; + machine_menu.wifiConfig = WIFI_SETTINGS_CONFIG_CN; + machine_menu.wifiEdit = WIFI_SETTINGS_EDIT_CN; + machine_menu.wifiConfigTips = WIFI_CONFIG_TIPS_CN; + + machine_menu.OffsetConfTitle = OFFSET_TITLE_CN; + machine_menu.Xoffset = OFFSET_X_CN; + machine_menu.Yoffset = OFFSET_Y_CN; + machine_menu.Zoffset = OFFSET_Z_CN; + + machine_menu.HomingSensitivityConfTitle = HOMING_SENSITIVITY_CONF_TITLE_CN; + machine_menu.X_Sensitivity = X_SENSITIVITY_CN; + machine_menu.Y_Sensitivity = Y_SENSITIVITY_CN; + machine_menu.Z_Sensitivity = Z_SENSITIVITY_CN; + machine_menu.Z2_Sensitivity = Z2_SENSITIVITY_CN; + + machine_menu.EncoderConfTitle = ENCODER_CONF_TITLE_CN; + machine_menu.EncoderConfText = ENCODER_CONF_TEXT_CN; } else if (gCfgItems.language == LANG_COMPLEX_CHINESE) { MachinePara_menu.title = MACHINE_PARA_TITLE_T_CN; MachinePara_menu.MachineSetting = MACHINE_TYPE_CNOFIG_T_CN; - MachinePara_menu.TemperatureSetting = TEMPERATURE_CONFIG_T_CN; MachinePara_menu.MotorSetting = MOTOR_CONFIG_T_CN; + MachinePara_menu.leveling = MACHINE_LEVELING_CONFIG_T_CN; MachinePara_menu.AdvanceSetting = ADVANCE_CONFIG_T_CN; machine_menu.default_value = DEFAULT_T_CN; @@ -290,7 +311,6 @@ void machine_setting_disp() { machine_menu.HomeDir = MACHINE_HOMEDIR_T_CN; machine_menu.EndStopType = MACHINE_ENDSTOP_TYPE_T_CN; machine_menu.FilamentConf = MACHINE_FILAMENT_CONFIG_T_CN; - machine_menu.LevelingConf = MACHINE_LEVELING_CONFIG_T_CN; machine_menu.MachineTypeConfTitle = MACHINE_TYPE_CONFIG_TITLE_T_CN; machine_menu.xyz = MACHINE_TYPE_XYZ_T_CN; @@ -325,18 +345,18 @@ void machine_setting_disp() { machine_menu.opened = ENDSTOP_OPENED_T_CN; machine_menu.closed = ENDSTOP_CLOSED_T_CN; - machine_menu.FilamentConfTitle = FILAMENT_CONF_TITLE_T_CN; - machine_menu.InTemperature = FILAMENT_IN_TEMPERATURE_T_CN; - machine_menu.InLength = FILAMENT_IN_LENGTH_T_CN; - machine_menu.InSpeed = FILAMENT_IN_SPEED_T_CN; - machine_menu.OutTemperature = FILAMENT_OUT_TEMPERATURE_T_CN; - machine_menu.OutLength = FILAMENT_OUT_LENGTH_T_CN; - machine_menu.OutSpeed = FILAMENT_OUT_SPEED_T_CN; + machine_menu.FilamentConfTitle = FILAMENT_CONF_TITLE_T_CN; + machine_menu.InLength = FILAMENT_IN_LENGTH_T_CN; + machine_menu.InSpeed = FILAMENT_IN_SPEED_T_CN; + machine_menu.FilamentTemperature = FILAMENT_TEMPERATURE_T_CN; + machine_menu.OutLength = FILAMENT_OUT_LENGTH_T_CN; + machine_menu.OutSpeed = FILAMENT_OUT_SPEED_T_CN; - machine_menu.LevelingParaConfTitle = LEVELING_CONF_TITLE_T_CN; - machine_menu.LevelingParaConf = LEVELING_PARA_CONF_T_CN; - machine_menu.DeltaLevelConf = LEVELING_DELTA_T_CN; - machine_menu.XYZLevelconf = LEVELING_XYZ_T_CN; + machine_menu.LevelingParaConfTitle = LEVELING_CONF_TITLE_T_CN; + machine_menu.LevelingParaConf = LEVELING_PARA_CONF_T_CN; + machine_menu.LevelingManuPosConf = LEVELING_MANUAL_POS_T_CN; + machine_menu.LevelingAutoCommandConf = LEVELING_AUTO_COMMAND_T_CN; + machine_menu.LevelingAutoZoffsetConf = LEVELING_AUTO_ZOFFSET_T_CN; machine_menu.LevelingSubConfTitle = LEVELING_PARA_CONF_TITLE_T_CN; machine_menu.AutoLevelEnable = AUTO_LEVELING_ENABLE_T_CN; @@ -386,16 +406,19 @@ void machine_setting_disp() { machine_menu.HotbedMinTemperature = HOTBED_MIN_TEMPERATURE_T_CN; machine_menu.HotbedMaxTemperature = HOTBED_MAX_TEMPERATURE_T_CN; - machine_menu.MotorConfTitle = MOTOR_CONF_TITLE_T_CN; - machine_menu.MaxFeedRateConf = MAXFEEDRATE_CONF_T_CN; - machine_menu.AccelerationConf = ACCELERATION_CONF_T_CN; - machine_menu.JerkConf = JERKCONF_T_CN; - machine_menu.StepsConf = STEPSCONF_T_CN; - machine_menu.TMCcurrentConf = TMC_CURRENT_T_CN; - machine_menu.TMCStepModeConf = TMC_STEP_MODE_T_CN; - machine_menu.MotorDirConf = MOTORDIRCONF_T_CN; - machine_menu.HomeFeedRateConf = HOMEFEEDRATECONF_T_CN; - machine_menu.PausePosition = PAUSE_POSITION_T_CN; + machine_menu.MotorConfTitle = MOTOR_CONF_TITLE_T_CN; + machine_menu.MaxFeedRateConf = MAXFEEDRATE_CONF_T_CN; + machine_menu.AccelerationConf = ACCELERATION_CONF_T_CN; + machine_menu.JerkConf = JERKCONF_T_CN; + machine_menu.StepsConf = STEPSCONF_T_CN; + machine_menu.TMCcurrentConf = TMC_CURRENT_T_CN; + machine_menu.TMCStepModeConf = TMC_STEP_MODE_T_CN; + machine_menu.MotorDirConf = MOTORDIRCONF_T_CN; + machine_menu.HomeFeedRateConf = HOMEFEEDRATECONF_T_CN; + machine_menu.PausePosition = PAUSE_POSITION_T_CN; + machine_menu.WifiSettings = WIFI_SETTINGS_T_CN; + machine_menu.HomingSensitivityConf = HOMING_SENSITIVITY_CONF_T_CN; + machine_menu.EncoderSettings = ENCODER_SETTINGS_T_CN; machine_menu.MaxFeedRateConfTitle = MAXFEEDRATE_CONF_TITLE_T_CN; machine_menu.XMaxFeedRate = X_MAXFEEDRATE_T_CN; @@ -484,12 +507,34 @@ void machine_setting_disp() { machine_menu.yPos = PAUSE_POSITION_Y_T_CN; machine_menu.zPos = PAUSE_POSITION_Z_T_CN; + machine_menu.WifiConfTitle = WIFI_SETTINGS_TITLE_T_CN; + machine_menu.wifiMode = WIFI_SETTINGS_MODE_T_CN; + machine_menu.wifiName = WIFI_SETTINGS_NAME_T_CN; + machine_menu.wifiPassWord = WIFI_SETTINGS_PASSWORD_T_CN; + machine_menu.wifiCloud = WIFI_SETTINGS_CLOUD_T_CN; + machine_menu.wifiConfig = WIFI_SETTINGS_CONFIG_T_CN; + machine_menu.wifiEdit = WIFI_SETTINGS_EDIT_T_CN; + machine_menu.wifiConfigTips = WIFI_CONFIG_TIPS_T_CN; + + machine_menu.OffsetConfTitle = OFFSET_TITLE_T_CN; + machine_menu.Xoffset = OFFSET_X_T_CN; + machine_menu.Yoffset = OFFSET_Y_T_CN; + machine_menu.Zoffset = OFFSET_Z_T_CN; + + machine_menu.HomingSensitivityConfTitle = HOMING_SENSITIVITY_CONF_TITLE_T_CN; + machine_menu.X_Sensitivity = X_SENSITIVITY_T_CN; + machine_menu.Y_Sensitivity = Y_SENSITIVITY_T_CN; + machine_menu.Z_Sensitivity = Z_SENSITIVITY_T_CN; + machine_menu.Z2_Sensitivity = Z2_SENSITIVITY_T_CN; + + machine_menu.EncoderConfTitle = ENCODER_CONF_TITLE_T_CN; + machine_menu.EncoderConfText = ENCODER_CONF_TEXT_T_CN; } else { MachinePara_menu.title = MACHINE_PARA_TITLE_EN; MachinePara_menu.MachineSetting = MACHINE_TYPE_CNOFIG_EN; - MachinePara_menu.TemperatureSetting = TEMPERATURE_CONFIG_EN; MachinePara_menu.MotorSetting = MOTOR_CONFIG_EN; + MachinePara_menu.leveling = MACHINE_LEVELING_CONFIG_EN; MachinePara_menu.AdvanceSetting = ADVANCE_CONFIG_EN; machine_menu.default_value = DEFAULT_EN; @@ -502,7 +547,6 @@ void machine_setting_disp() { machine_menu.HomeDir = MACHINE_HOMEDIR_EN; machine_menu.EndStopType = MACHINE_ENDSTOP_TYPE_EN; machine_menu.FilamentConf = MACHINE_FILAMENT_CONFIG_EN; - machine_menu.LevelingConf = MACHINE_LEVELING_CONFIG_EN; machine_menu.MachineTypeConfTitle = MACHINE_TYPE_CONFIG_TITLE_EN; machine_menu.xyz = MACHINE_TYPE_XYZ_EN; @@ -537,18 +581,18 @@ void machine_setting_disp() { machine_menu.opened = ENDSTOP_OPENED_EN; machine_menu.closed = ENDSTOP_CLOSED_EN; - machine_menu.FilamentConfTitle = FILAMENT_CONF_TITLE_EN; - machine_menu.InTemperature = FILAMENT_IN_TEMPERATURE_EN; - machine_menu.InLength = FILAMENT_IN_LENGTH_EN; - machine_menu.InSpeed = FILAMENT_IN_SPEED_EN; - machine_menu.OutTemperature = FILAMENT_OUT_TEMPERATURE_EN; - machine_menu.OutLength = FILAMENT_OUT_LENGTH_EN; - machine_menu.OutSpeed = FILAMENT_OUT_SPEED_EN; + machine_menu.FilamentConfTitle = FILAMENT_CONF_TITLE_EN; + machine_menu.InLength = FILAMENT_IN_LENGTH_EN; + machine_menu.InSpeed = FILAMENT_IN_SPEED_EN; + machine_menu.FilamentTemperature = FILAMENT_TEMPERATURE_EN; + machine_menu.OutLength = FILAMENT_OUT_LENGTH_EN; + machine_menu.OutSpeed = FILAMENT_OUT_SPEED_EN; - machine_menu.LevelingParaConfTitle = LEVELING_CONF_TITLE_EN; - machine_menu.LevelingParaConf = LEVELING_PARA_CONF_EN; - machine_menu.DeltaLevelConf = LEVELING_DELTA_EN; - machine_menu.XYZLevelconf = LEVELING_XYZ_EN; + machine_menu.LevelingParaConfTitle = LEVELING_CONF_TITLE_EN; + machine_menu.LevelingParaConf = LEVELING_PARA_CONF_EN; + machine_menu.LevelingManuPosConf = LEVELING_MANUAL_POS_EN; + machine_menu.LevelingAutoCommandConf = LEVELING_AUTO_COMMAND_EN; + machine_menu.LevelingAutoZoffsetConf = LEVELING_AUTO_ZOFFSET_EN; machine_menu.LevelingSubConfTitle = LEVELING_PARA_CONF_TITLE_EN; machine_menu.AutoLevelEnable = AUTO_LEVELING_ENABLE_EN; @@ -598,16 +642,19 @@ void machine_setting_disp() { machine_menu.HotbedMinTemperature = HOTBED_MIN_TEMPERATURE_EN; machine_menu.HotbedMaxTemperature = HOTBED_MAX_TEMPERATURE_EN; - machine_menu.MotorConfTitle = MOTOR_CONF_TITLE_EN; - machine_menu.MaxFeedRateConf = MAXFEEDRATE_CONF_EN; - machine_menu.AccelerationConf = ACCELERATION_CONF_EN; - machine_menu.JerkConf = JERKCONF_EN; - machine_menu.StepsConf = STEPSCONF_EN; - machine_menu.TMCcurrentConf = TMC_CURRENT_EN; - machine_menu.TMCStepModeConf = TMC_STEP_MODE_EN; - machine_menu.MotorDirConf = MOTORDIRCONF_EN; - machine_menu.HomeFeedRateConf = HOMEFEEDRATECONF_EN; - machine_menu.PausePosition = PAUSE_POSITION_EN; + machine_menu.MotorConfTitle = MOTOR_CONF_TITLE_EN; + machine_menu.MaxFeedRateConf = MAXFEEDRATE_CONF_EN; + machine_menu.AccelerationConf = ACCELERATION_CONF_EN; + machine_menu.JerkConf = JERKCONF_EN; + machine_menu.StepsConf = STEPSCONF_EN; + machine_menu.TMCcurrentConf = TMC_CURRENT_EN; + machine_menu.TMCStepModeConf = TMC_STEP_MODE_EN; + machine_menu.MotorDirConf = MOTORDIRCONF_EN; + machine_menu.HomeFeedRateConf = HOMEFEEDRATECONF_EN; + machine_menu.PausePosition = PAUSE_POSITION_EN; + machine_menu.WifiSettings = WIFI_SETTINGS_EN; + machine_menu.HomingSensitivityConf = HOMING_SENSITIVITY_CONF_EN; + machine_menu.EncoderSettings = ENCODER_SETTINGS_EN; machine_menu.MaxFeedRateConfTitle = MAXFEEDRATE_CONF_TITLE_EN; machine_menu.XMaxFeedRate = X_MAXFEEDRATE_EN; @@ -692,10 +739,32 @@ void machine_setting_disp() { machine_menu.high_level = MOTOR_EN_HIGH_LEVEL_EN; machine_menu.low_level = MOTOR_EN_LOW_LEVEL_EN; - machine_menu.PausePosText = PAUSE_POSITION_EN; - machine_menu.xPos = PAUSE_POSITION_X_EN; - machine_menu.yPos = PAUSE_POSITION_Y_EN; - machine_menu.zPos = PAUSE_POSITION_Z_EN; + machine_menu.PausePosText = PAUSE_POSITION_EN; + machine_menu.xPos = PAUSE_POSITION_X_EN; + machine_menu.yPos = PAUSE_POSITION_Y_EN; + machine_menu.zPos = PAUSE_POSITION_Z_EN; + machine_menu.WifiConfTitle = WIFI_SETTINGS_TITLE_EN; + machine_menu.wifiMode = WIFI_SETTINGS_MODE_EN; + machine_menu.wifiName = WIFI_SETTINGS_NAME_EN; + machine_menu.wifiPassWord = WIFI_SETTINGS_PASSWORD_EN; + machine_menu.wifiCloud = WIFI_SETTINGS_CLOUD_EN; + machine_menu.wifiConfig = WIFI_SETTINGS_CONFIG_EN; + machine_menu.wifiEdit = WIFI_SETTINGS_EDIT_EN; + machine_menu.wifiConfigTips = WIFI_CONFIG_TIPS_EN; + + machine_menu.OffsetConfTitle = OFFSET_TITLE_EN; + machine_menu.Xoffset = OFFSET_X_EN; + machine_menu.Yoffset = OFFSET_Y_EN; + machine_menu.Zoffset = OFFSET_Z_EN; + + machine_menu.HomingSensitivityConfTitle = HOMING_SENSITIVITY_CONF_TITLE_EN; + machine_menu.X_Sensitivity = X_SENSITIVITY_EN; + machine_menu.Y_Sensitivity = Y_SENSITIVITY_EN; + machine_menu.Z_Sensitivity = Z_SENSITIVITY_EN; + machine_menu.Z2_Sensitivity = Z2_SENSITIVITY_EN; + + machine_menu.EncoderConfTitle = ENCODER_CONF_TITLE_EN; + machine_menu.EncoderConfText = ENCODER_CONF_TEXT_EN; } } @@ -771,10 +840,6 @@ void disp_language_init() { filament_menu.stat_temp = TEXT_VALUE; - zoffset_menu.step001 = ZOFFSET_STEP001; - zoffset_menu.step01 = ZOFFSET_STEP01; - zoffset_menu.step1 = ZOFFSET_STEP1; - machine_menu.key_0 = KEYBOARD_KEY0_EN; machine_menu.key_1 = KEYBOARD_KEY1_EN; machine_menu.key_2 = KEYBOARD_KEY2_EN; @@ -788,22 +853,15 @@ void disp_language_init() { machine_menu.key_point = KEYBOARD_KEY_POINT_EN; machine_menu.negative = KEYBOARD_KEY_NEGATIVE_EN; // wifi-list - #if 0 - list_menu.title = TEXT_WIFI_MENU_TITLE_EN; - list_menu.file_pages = FILE_PAGES_EN; - // keyboard - keyboard_menu.apply = MANUAL_IP_APPLY_EN; - keyboard_menu.password = TEXT_WIFI_PASSWORD_EN; - keyboard_menu.space = TEXT_WIFI_SAPCE_EN; - keyboard_menu.letter = TEXT_WIFI_LETTER_EN; - keyboard_menu.digital = TEXT_WIFI_DIGITAL_EN; - keyboard_menu.symbol = TEXT_WIFI_SYMBOL_EN; + #if ENABLED(USE_WIFI_FUNCTION) + list_menu.title = TEXT_WIFI_MENU_TITLE_EN; + list_menu.file_pages = FILE_PAGES_EN; + // tips - tips_menu.pointBold = TEXT_WIFI_POINT_BOLD_EN; tips_menu.joining = TEXT_WIFI_JOINING_EN; tips_menu.failedJoin = TEXT_WIFI_FAILED_JOIN_EN; tips_menu.wifiConected = TEXT_WIFI_WIFI_CONECTED_EN; - #endif + #endif //USE_WIFI_FUNCTION machine_setting_disp(); operation_menu.babystep = TEXT_BABY_STEP_EN; @@ -904,7 +962,6 @@ void disp_language_init() { filesys_menu.usb_sys = U_DISK_TEXT_CN; // more_menu.title = TITLE_MORE_CN; - more_menu.zoffset = ZOFFSET_CN; // WIFI wifi_menu.title = WIFI_TEXT; // wifi_menu.key = WIFI_KEY_TEXT_CN; @@ -1016,11 +1073,6 @@ void disp_language_init() { print_file_dialog_menu.reprint = DIALOG_REPRINT_CN; print_file_dialog_menu.wifi_enable_tips = DIALOG_WIFI_ENABLE_TIPS_CN; - // ZOFFSET - zoffset_menu.title = TITLE_ZOFFSET_CN; - zoffset_menu.inc = ZOFFSET_INC_CN; - zoffset_menu.dec = ZOFFSET_DEC_CN; - pause_msg_menu.pausing = MESSAGE_PAUSING_CN; pause_msg_menu.changing = MESSAGE_CHANGING_CN; pause_msg_menu.unload = MESSAGE_UNLOAD_CN; @@ -1092,7 +1144,6 @@ void disp_language_init() { preheat_menu.step_10c = TEXT_10C_T_CN; // move_menu.title = MOVE_TEXT_T_CN; - more_menu.zoffset = ZOFFSET_T_CN; // home_menu.title = TITLE_HOME_T_CN; home_menu.stopmove = HOME_STOPMOVE_T_CN; @@ -1249,10 +1300,6 @@ void disp_language_init() { print_file_dialog_menu.print_time = DIALOG_PRINT_TIME_T_CN; print_file_dialog_menu.reprint = DIALOG_REPRINT_T_CN; print_file_dialog_menu.wifi_enable_tips = DIALOG_WIFI_ENABLE_TIPS_T_CN; - // ZOFFSET - zoffset_menu.title = TITLE_ZOFFSET_T_CN; - zoffset_menu.inc = ZOFFSET_INC_T_CN; - zoffset_menu.dec = ZOFFSET_DEC_T_CN; pause_msg_menu.pausing = MESSAGE_PAUSING_T_CN; pause_msg_menu.changing = MESSAGE_CHANGING_T_CN; @@ -1359,7 +1406,6 @@ void disp_language_init() { set_menu.machine_para = MACHINE_PARA_EN; set_menu.eepromSet = EEPROM_SETTINGS_EN; more_menu.title = TITLE_MORE_EN; - more_menu.zoffset = ZOFFSET_EN; // filesys_menu.title = TITLE_FILESYS_EN; filesys_menu.sd_sys = SD_CARD_TEXT_EN; @@ -1469,10 +1515,6 @@ void disp_language_init() { print_file_dialog_menu.print_time = DIALOG_PRINT_TIME_EN; print_file_dialog_menu.reprint = DIALOG_REPRINT_EN; print_file_dialog_menu.wifi_enable_tips = DIALOG_WIFI_ENABLE_TIPS_EN; - // ZOFFSET - zoffset_menu.title = TITLE_ZOFFSET_EN; - zoffset_menu.inc = ZOFFSET_INC_EN; - zoffset_menu.dec = ZOFFSET_DEC_EN; pause_msg_menu.pausing = MESSAGE_PAUSING_EN; pause_msg_menu.changing = MESSAGE_CHANGING_EN; @@ -1579,7 +1621,6 @@ void disp_language_init() { set_menu.machine_para = MACHINE_PARA_RU; set_menu.eepromSet = EEPROM_SETTINGS_RU; more_menu.title = TITLE_MORE_RU; - more_menu.zoffset = ZOFFSET_RU; // filesys_menu.title = TITLE_FILESYS_RU; filesys_menu.sd_sys = SD_CARD_TEXT_RU; @@ -1689,10 +1730,6 @@ void disp_language_init() { print_file_dialog_menu.print_time = DIALOG_PRINT_TIME_RU; print_file_dialog_menu.reprint = DIALOG_REPRINT_RU; print_file_dialog_menu.wifi_enable_tips = DIALOG_WIFI_ENABLE_TIPS_RU; - // ZOFFSET - zoffset_menu.title = TITLE_ZOFFSET_RU; - zoffset_menu.inc = ZOFFSET_INC_RU; - zoffset_menu.dec = ZOFFSET_DEC_RU; pause_msg_menu.pausing = MESSAGE_PAUSING_RU; pause_msg_menu.changing = MESSAGE_CHANGING_RU; @@ -1803,7 +1840,6 @@ void disp_language_init() { set_menu.machine_para = MACHINE_PARA_SP; set_menu.eepromSet = EEPROM_SETTINGS_SP; more_menu.title = TITLE_MORE_SP; - more_menu.zoffset = ZOFFSET_SP; // filesys_menu.title = TITLE_FILESYS_SP; filesys_menu.sd_sys = SD_CARD_TEXT_SP; @@ -1914,10 +1950,6 @@ void disp_language_init() { print_file_dialog_menu.print_time = DIALOG_PRINT_TIME_SP; print_file_dialog_menu.reprint = DIALOG_REPRINT_SP; print_file_dialog_menu.wifi_enable_tips = DIALOG_WIFI_ENABLE_TIPS_SP; - // ZOFFSET - zoffset_menu.title = TITLE_ZOFFSET_SP; - zoffset_menu.inc = ZOFFSET_INC_SP; - zoffset_menu.dec = ZOFFSET_DEC_SP; pause_msg_menu.pausing = MESSAGE_PAUSING_SP; pause_msg_menu.changing = MESSAGE_CHANGING_SP; @@ -2025,7 +2057,6 @@ void disp_language_init() { set_menu.machine_para = MACHINE_PARA_FR; set_menu.eepromSet = EEPROM_SETTINGS_FR; more_menu.title = TITLE_MORE_FR; - more_menu.zoffset = ZOFFSET_FR; // filesys_menu.title = TITLE_FILESYS_FR; filesys_menu.sd_sys = SD_CARD_TEXT_FR; @@ -2137,10 +2168,6 @@ void disp_language_init() { print_file_dialog_menu.print_time = DIALOG_PRINT_TIME_FR; print_file_dialog_menu.reprint = DIALOG_REPRINT_FR; print_file_dialog_menu.wifi_enable_tips = DIALOG_WIFI_ENABLE_TIPS_FR; - // ZOFFSET - zoffset_menu.title = TITLE_ZOFFSET_FR; - zoffset_menu.inc = ZOFFSET_INC_FR; - zoffset_menu.dec = ZOFFSET_DEC_FR; pause_msg_menu.pausing = MESSAGE_PAUSING_FR; pause_msg_menu.changing = MESSAGE_CHANGING_FR; @@ -2249,7 +2276,6 @@ void disp_language_init() { set_menu.machine_para = MACHINE_PARA_IT; set_menu.eepromSet = EEPROM_SETTINGS_IT; more_menu.title = TITLE_MORE_IT; - more_menu.zoffset = ZOFFSET_IT; // filesys_menu.title = TITLE_FILESYS_IT; filesys_menu.sd_sys = SD_CARD_TEXT_IT; @@ -2358,10 +2384,6 @@ void disp_language_init() { print_file_dialog_menu.print_time = DIALOG_PRINT_TIME_IT; print_file_dialog_menu.reprint = DIALOG_REPRINT_IT; print_file_dialog_menu.wifi_enable_tips = DIALOG_WIFI_ENABLE_TIPS_IT; - // ZOFFSET - zoffset_menu.title = TITLE_ZOFFSET_IT; - zoffset_menu.inc = ZOFFSET_INC_IT; - zoffset_menu.dec = ZOFFSET_DEC_IT; pause_msg_menu.pausing = MESSAGE_PAUSING_IT; pause_msg_menu.changing = MESSAGE_CHANGING_IT; @@ -2472,7 +2494,6 @@ void disp_language_init() { set_menu.eepromSet = EEPROM_SETTINGS_EN; // more_menu.title = TITLE_MORE_EN; - more_menu.zoffset = ZOFFSET_EN; // filesys_menu.title = TITLE_FILESYS_EN; filesys_menu.sd_sys = SD_CARD_TEXT_EN; @@ -2582,10 +2603,6 @@ void disp_language_init() { print_file_dialog_menu.print_time = DIALOG_PRINT_TIME_EN; print_file_dialog_menu.reprint = DIALOG_REPRINT_EN; print_file_dialog_menu.wifi_enable_tips = DIALOG_WIFI_ENABLE_TIPS_EN; - // ZOFFSET - zoffset_menu.title = TITLE_ZOFFSET_EN; - zoffset_menu.inc = ZOFFSET_INC_EN; - zoffset_menu.dec = ZOFFSET_DEC_EN; pause_msg_menu.pausing = MESSAGE_PAUSING_EN; pause_msg_menu.changing = MESSAGE_CHANGING_EN; diff --git a/Marlin/src/lcd/extui/lib/mks_ui/tft_multi_language.h b/Marlin/src/lcd/extui/lib/mks_ui/tft_multi_language.h index 5851009356..675fd41f16 100644 --- a/Marlin/src/lcd/extui/lib/mks_ui/tft_multi_language.h +++ b/Marlin/src/lcd/extui/lib/mks_ui/tft_multi_language.h @@ -60,7 +60,6 @@ typedef struct machine_common_disp{ const char *HomeDir; const char *EndStopType; const char *FilamentConf; - const char *LevelingConf; const char *MachineTypeConfTitle; const char *xyz; @@ -96,17 +95,17 @@ typedef struct machine_common_disp{ const char *closed; const char *FilamentConfTitle; - const char *InTemperature; const char *InLength; const char *InSpeed; - const char *OutTemperature; + const char *FilamentTemperature; const char *OutLength; const char *OutSpeed; const char *LevelingParaConfTitle; const char *LevelingParaConf; - const char *DeltaLevelConf; - const char *XYZLevelconf; + const char *LevelingManuPosConf; + const char *LevelingAutoCommandConf; + const char *LevelingAutoZoffsetConf; const char *LevelingSubConfTitle; const char *AutoLevelEnable; @@ -165,6 +164,7 @@ typedef struct machine_common_disp{ const char *HomeFeedRateConf; const char *TMCcurrentConf; const char *TMCStepModeConf; + const char *HomingSensitivityConf; const char *MaxFeedRateConfTitle; const char *XMaxFeedRate; @@ -210,6 +210,12 @@ typedef struct machine_common_disp{ const char *E0_StepMode; const char *E1_StepMode; + const char *HomingSensitivityConfTitle; + const char *X_Sensitivity; + const char *Y_Sensitivity; + const char *Z_Sensitivity; + const char *Z2_Sensitivity; + const char *MotorDirConfTitle; const char *X_MotorDir; const char *Y_MotorDir; @@ -231,6 +237,8 @@ typedef struct machine_common_disp{ const char *Z2andZ2Endstop; const char *EnablePinsInvert; const char *PausePosition; + const char *WifiSettings; + const char *EncoderSettings; const char *Z2ConfTitle; const char *Z2Enable; @@ -266,6 +274,23 @@ typedef struct machine_common_disp{ const char *yPos; const char *zPos; + const char *WifiConfTitle; + const char *wifiMode; + const char *wifiName; + const char *wifiPassWord; + const char *wifiCloud; + const char *wifiConfig; + const char *wifiEdit; + const char *wifiConfigTips; + + const char *OffsetConfTitle; + const char *Xoffset; + const char *Yoffset; + const char *Zoffset; + + const char *EncoderConfTitle; + const char *EncoderConfText; + } machine_common_def; extern machine_common_def machine_menu; @@ -435,7 +460,6 @@ extern filesys_menu_def filesys_menu; typedef struct more_menu_disp { const char *title; - const char *zoffset; const char *back; } more_menu_def; @@ -661,18 +685,6 @@ typedef struct print_file_dialog_disp { extern print_file_dialog_menu_def print_file_dialog_menu; -typedef struct zoffset_menu_disp { - const char *title; - const char *inc; - const char *dec; - const char *step001; - const char *step01; - const char *step1; - const char *back; -} zoffset_menu_def; - -extern zoffset_menu_def zoffset_menu; - typedef struct tool_menu_disp { const char *title; const char *preheat; @@ -691,37 +703,13 @@ extern tool_menu_def tool_menu; typedef struct MachinePara_menu_disp { const char *title; const char *MachineSetting; - const char *TemperatureSetting; const char *MotorSetting; + const char *leveling; const char *AdvanceSetting; - //const char *back; } MachinePara_menu_def; extern MachinePara_menu_def MachinePara_menu; -typedef struct MachineSettings_menu_disp { - const char *title; - const char *Machine; - const char *Stroke; - const char *HomeDir; - const char *EndStopType; - const char *filamet; - const char *leveling; - const char *back; -} MachineSettings_menu_def; - -extern MachineSettings_menu_def MachineSettings_menu; - -typedef struct TemperatureSettings_menu_disp { - const char *title; - const char *nozzle; - const char *hotbed; - const char *preheat; - const char *back; -} TemperatureSettings_menu_def; - -extern TemperatureSettings_menu_def TemperatureSettings_menu; - typedef struct pause_msg_disp { const char *pausing; const char *changing; @@ -842,6 +830,7 @@ extern eeprom_def eeprom_menu; #define DIALOG_UPLOAD_SPEED_EN "Speed" #define DIALOG_UPDATE_WIFI_FIRMWARE_EN "Updating wifi model firmware" #define DIALOG_UPDATE_WIFI_WEB_EN "Updating wifi model web data" +#define DIALOG_UPDATE_NO_DEVICE_EN "please check \nwether memory device insert!" #define ZOFFSET_STEP001 "0.01mm" #define ZOFFSET_STEP01 "0.1mm" diff --git a/Marlin/src/lcd/extui/lib/mks_ui/wifiSerial.cpp b/Marlin/src/lcd/extui/lib/mks_ui/wifiSerial.cpp new file mode 100644 index 0000000000..01c86ad7cb --- /dev/null +++ b/Marlin/src/lcd/extui/lib/mks_ui/wifiSerial.cpp @@ -0,0 +1,120 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "draw_ui.h" +#include "wifiSerial.h" + +#if ENABLED(USE_WIFI_FUNCTION) + +#include +#include +#include +#include +#include + +#include "../../../../MarlinCore.h" + +DEFINE_WFSERIAL(WifiSerial1, 1); + +WifiSerial::WifiSerial(usart_dev *usart_device, uint8 tx_pin, uint8 rx_pin) { + this->usart_device = usart_device; + this->tx_pin = tx_pin; + this->rx_pin = rx_pin; +} + +/** + * Set up / tear down + */ +#if STM32_MCU_SERIES == STM32_SERIES_F1 + /* F1 MCUs have no GPIO_AFR[HL], so turn off PWM if there's a conflict + * on this GPIO bit. */ + static void disable_timer_if_necessary(timer_dev *dev, uint8 ch) { + if (dev != nullptr) timer_set_mode(dev, ch, TIMER_DISABLED); + } +#elif STM32_MCU_SERIES == STM32_SERIES_F2 || STM32_MCU_SERIES == STM32_SERIES_F4 + #define disable_timer_if_necessary(dev, ch) ((void)0) +#else + #warning "Unsupported STM32 series; timer conflicts are possible" +#endif + +void WifiSerial::begin(uint32 baud) { begin(baud, SERIAL_8N1); } + +/** + * Roger Clark. + * Note. The config parameter is not currently used. This is a work in progress. + * Code needs to be written to set the config of the hardware serial control register in question. + */ + +void WifiSerial::begin(uint32 baud, uint8_t config) { + //ASSERT(baud <= this->usart_device->max_baud); // Roger Clark. Assert doesn't do anything useful, we may as well save the space in flash and ram etc + + if (baud > this->usart_device->max_baud) return; + + const stm32_pin_info *txi = &PIN_MAP[this->tx_pin], + *rxi = &PIN_MAP[this->rx_pin]; + + disable_timer_if_necessary(txi->timer_device, txi->timer_channel); + + usart_init(this->usart_device); + + // Reinitialize the receive buffer, mks_esp8266 fixed data frame length is 1k bytes + rb_init(this->usart_device->rb, WIFI_RX_BUF_SIZE, wifiRxBuf); + + usart_config_gpios_async(this->usart_device, + rxi->gpio_device, rxi->gpio_bit, + txi->gpio_device, txi->gpio_bit, + config); + usart_set_baud_rate(this->usart_device, USART_USE_PCLK, baud); + usart_enable(this->usart_device); +} + +void WifiSerial::end(void) { + usart_disable(this->usart_device); +} + +int WifiSerial::available(void) { + return usart_data_available(this->usart_device); +} + +// +// I/O +// + +int WifiSerial::read(void) { + if (usart_data_available(usart_device) <= 0) return -1; + return usart_getc(usart_device); +} + +int WifiSerial::write(unsigned char ch) { + usart_putc(this->usart_device, ch); + return 1; +} + +int WifiSerial::wifi_rb_is_full(void) { + return rb_is_full(this->usart_device->rb); +} + +#endif // USE_WIFI_FUNCTION +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/wifiSerial.h b/Marlin/src/lcd/extui/lib/mks_ui/wifiSerial.h new file mode 100644 index 0000000000..9d3946fee7 --- /dev/null +++ b/Marlin/src/lcd/extui/lib/mks_ui/wifiSerial.h @@ -0,0 +1,102 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#include "tft_lvgl_configuration.h" + +#if ENABLED(USE_WIFI_FUNCTION) + +#if SERIAL_PORT_2 != -1 + #error "SERIAL_PORT_2 must be set to -1 with HAS_TFT_LVGL_UI and USE_WIFI_FUNCTION." +#endif + +#define WIFI_BAUDRATE 115200 +#define WIFI_UPLOAD_BAUDRATE 1958400 +#define USART_SAFE_INSERT + +#define WIFI_RX_BUF_SIZE (1024+1) + +#include +#include +#include +#include +#include +#include + +#define DEFINE_WFSERIAL(name, n)\ + WifiSerial name(USART##n, \ + BOARD_USART##n##_TX_PIN, \ + BOARD_USART##n##_RX_PIN) + +class WifiSerial { + public: + uint8 wifiRxBuf[WIFI_RX_BUF_SIZE]; + + public: + WifiSerial(struct usart_dev *usart_device, uint8 tx_pin, uint8 rx_pin); + + /* Set up/tear down */ + void begin(uint32 baud); + void begin(uint32 baud,uint8_t config); + void end(); + int available(void); + int read(void); + int write(uint8_t); + inline void wifi_usart_irq(usart_reg_map *regs) { + /* Handling RXNEIE and TXEIE interrupts. + * RXNE signifies availability of a byte in DR. + * + * See table 198 (sec 27.4, p809) in STM document RM0008 rev 15. + * We enable RXNEIE. + */ + if ((regs->CR1 & USART_CR1_RXNEIE) && (regs->SR & USART_SR_RXNE)) { + #ifdef USART_SAFE_INSERT + /* If the buffer is full and the user defines USART_SAFE_INSERT, + * ignore new bytes. */ + rb_safe_insert(this->usart_device->rb, (uint8)regs->DR); + #else + /* By default, push bytes around in the ring buffer. */ + rb_push_insert(this->usart_device->rb, (uint8)regs->DR); + #endif + } + /* TXE signifies readiness to send a byte to DR. */ + if ((regs->CR1 & USART_CR1_TXEIE) && (regs->SR & USART_SR_TXE)) { + if (!rb_is_empty(this->usart_device->wb)) + regs->DR=rb_remove(this->usart_device->wb); + else + regs->CR1 &= ~((uint32)USART_CR1_TXEIE); // disable TXEIE + } + } + + int wifi_rb_is_full(void); + + private: + struct usart_dev *usart_device; + uint8 tx_pin; + uint8 rx_pin; +}; + +extern WifiSerial WifiSerial1; + +#define WIFISERIAL WifiSerial1 + +#endif // USE_WIFI_FUNCTION diff --git a/Marlin/src/lcd/extui/lib/mks_ui/wifi_module.cpp b/Marlin/src/lcd/extui/lib/mks_ui/wifi_module.cpp new file mode 100644 index 0000000000..5c025f13f9 --- /dev/null +++ b/Marlin/src/lcd/extui/lib/mks_ui/wifi_module.cpp @@ -0,0 +1,1927 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "draw_ui.h" +#include "wifi_module.h" +#include "wifi_upload.h" + +#if ENABLED(USE_WIFI_FUNCTION) + +#include "../../../../MarlinCore.h" +#include "../../../../module/temperature.h" +#include "../../../../gcode/queue.h" +#include "../../../../gcode/gcode.h" +#include "../../../../lcd/ultralcd.h" +#include "../../../../sd/cardreader.h" +#include "../../../../module/planner.h" +#if ENABLED(POWER_LOSS_RECOVERY) + #include "../../../../feature/powerloss.h" +#endif +#if ENABLED(PARK_HEAD_ON_PAUSE) + #include "../../../../feature/pause.h" +#endif + +#define WIFI_SET() WRITE(WIFI_RESET_PIN, HIGH); +#define WIFI_RESET() WRITE(WIFI_RESET_PIN, LOW); +#define WIFI_IO1_SET() WRITE(WIFI_IO1_PIN, HIGH); +#define WIFI_IO1_RESET() WRITE(WIFI_IO1_PIN, LOW); + +extern uint8_t Explore_Disk (char* path , uint8_t recu_level); + +extern uint8_t commands_in_queue; +extern uint8_t sel_id; + +int usartFifoAvailable(SZ_USART_FIFO *fifo); +int readUsartFifo(SZ_USART_FIFO *fifo, int8_t *buf, int32_t len); +int writeUsartFifo(SZ_USART_FIFO * fifo, int8_t * buf, int32_t len); +extern unsigned int getTickDiff(unsigned int curTick, unsigned int lastTick); + +volatile SZ_USART_FIFO WifiRxFifo; + +#define WAIT_ESP_TRANS_TIMEOUT_TICK 10500 + +int cfg_cloud_flag = 0; + +extern PRINT_TIME print_time; + +char wifi_firm_ver[20] = {0}; +WIFI_GCODE_BUFFER espGcodeFifo; +extern uint8_t pause_resum; + +uint8_t wifi_connect_flg = 0; +extern volatile uint8_t get_temp_flag; + + +#define WIFI_MODE 2 +#define WIFI_AP_MODE 3 + +int upload_result = 0; + +uint32_t upload_time = 0; +uint32_t upload_size = 0; + +volatile WIFI_STATE wifi_link_state; +WIFI_PARA wifiPara; +IP_PARA ipPara; +CLOUD_PARA cloud_para; + +char wifi_check_time = 0; + +extern uint8_t gCurDir[100]; + +extern uint32_t wifi_loop_cycle; + +volatile TRANSFER_STATE esp_state; + +uint8_t left_to_send = 0; +uint8_t left_to_save[96] = {0}; + +volatile WIFI_DMA_RCV_FIFO wifiDmaRcvFifo; + +volatile WIFI_TRANS_ERROR wifiTransError; + +static bool need_ok_later = false; + +extern volatile WIFI_STATE wifi_link_state; +extern WIFI_PARA wifiPara; +extern IP_PARA ipPara; +extern CLOUD_PARA cloud_para; + +extern uint8_t once_flag; +extern uint8_t flash_preview_begin; +extern uint8_t default_preview_flg; +extern uint8_t gcode_preview_over; + +extern uint8_t bmp_public_buf[17 * 1024]; + +uint32_t getWifiTick() { + return millis(); +} + +uint32_t getWifiTickDiff(int32_t lastTick, int32_t curTick) { + if (lastTick <= curTick) { + return (curTick - lastTick) * TICK_CYCLE; + } + else { + return (0xffffffff - lastTick + curTick) * TICK_CYCLE; + } +} + +void wifi_delay(int n) { + uint32_t begin = getWifiTick(); + uint32_t end = begin; + + while (getWifiTickDiff(begin, end) < (uint32_t)n) { + end = getWifiTick(); + } +} + +void wifi_reset() { + uint32_t start, now; + start = getWifiTick(); + now = start; + WIFI_RESET(); + while (getWifiTickDiff(start, now) < 500) { + now = getWifiTick(); + } + WIFI_SET(); + +} + +void mount_file_sys(uint8_t disk_type) { + if (disk_type == FILE_SYS_SD) { + card.mount(); + } + else if (disk_type == FILE_SYS_USB) { + + } +} + +static void dma_init() { + #if 0 + __HAL_RCC_DMA1_CLK_ENABLE(); + + //HAL_NVIC_SetPriorityGrouping(NVIC_PRIORITYGROUP_0); + HAL_NVIC_SetPriority(DMA1_Channel5_IRQn, 4, 0); + HAL_NVIC_EnableIRQ(DMA1_Channel5_IRQn); + + hdma_usart1_rx.Instance = DMA1_Channel5; + //hdma_usart1_rx.Init.Channel = DMA_CHANNEL_4; + hdma_usart1_rx.Init.Direction = DMA_PERIPH_TO_MEMORY; + hdma_usart1_rx.Init.PeriphInc = DMA_PINC_DISABLE; + hdma_usart1_rx.Init.MemInc = DMA_MINC_ENABLE; + hdma_usart1_rx.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE; + hdma_usart1_rx.Init.MemDataAlignment = DMA_PDATAALIGN_BYTE; + hdma_usart1_rx.Init.Mode = DMA_NORMAL; + hdma_usart1_rx.Init.Priority = DMA_PRIORITY_VERY_HIGH; + if (HAL_DMA_Init((DMA_HandleTypeDef *)&hdma_usart1_rx) != HAL_OK) { + Error_Handler(); + } + + + HAL_DMA_Start_IT((DMA_HandleTypeDef *)&hdma_usart1_rx, + (uint32_t)&huart1.Instance->DR, + (uint32_t)(&WifiRxFifo.uartTxBuffer[0]), + UART_RX_BUFFER_SIZE); + + //HAL_UART_Receive_DMA(&huart1,(uint8_t*)&WifiRxFifo.uartTxBuffer[0], UART_RX_BUFFER_SIZE); + + /* Enable the DMA transfer for the receiver request by setting the DMAR bit + in the UART CR3 register */ + SET_BIT(huart1.Instance->CR3, USART_CR3_DMAR); + + #endif + for (uint8_t i = 0; i < TRANS_RCV_FIFO_BLOCK_NUM; i++) { + wifiDmaRcvFifo.bufferAddr[i] = &bmp_public_buf[1024 * i]; + wifiDmaRcvFifo.state[i] = udisk_buf_empty; + } + + memset(wifiDmaRcvFifo.bufferAddr[0], 0, 1024 * TRANS_RCV_FIFO_BLOCK_NUM); + wifiDmaRcvFifo.read_cur = 0; + wifiDmaRcvFifo.write_cur = 0; + +} + +static void wifi_deInit() { + #if 0 + HAL_DMA_Abort((DMA_HandleTypeDef *)&hdma_usart1_rx); + HAL_DMA_DeInit((DMA_HandleTypeDef *)&hdma_usart1_rx); + __HAL_DMA_DISABLE((DMA_HandleTypeDef *)&hdma_usart1_rx); + #endif +} + +extern uint8_t mksUsart1Rx; + +void esp_port_begin(uint8_t interrupt) { + WifiRxFifo.uart_read_point = 0; + WifiRxFifo.uart_write_point = 0; + #if 0 + NVIC_InitTypeDef NVIC_InitStructure; + + USART_InitTypeDef USART_InitStructure; + GPIO_InitTypeDef GPIO_InitStruct; + + WifiRxFifo.uart_read_point = 0; + WifiRxFifo.uart_write_point = 0; + memset((uint8_t*)WifiRxFifo.uartTxBuffer, 0, sizeof(WifiRxFifo.uartTxBuffer)); + + if (interrupt) { + #if TAN + wifi_deInit (); + + //SZ_STM32_COMInit(COM1, 115200); + __HAL_UART_ENABLE_IT(USART1, USART_IT_RXNE); + + USART_InitStructure.USART_BaudRate = 115200; //���ڵIJ����ʣ�����115200 ��ߴ�4.5Mbits/s + USART_InitStructure.USART_WordLength = USART_WordLength_8b; //�����ֳ���(8λ��9λ) + USART_InitStructure.USART_StopBits = USART_StopBits_1; //�����õ�ֹͣλ-֧��1��2��ֹͣλ + USART_InitStructure.USART_Parity = USART_Parity_No; //����żУ�� + USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None; //��Ӳ�������� + USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx; //˫��ģʽ��ʹ�ܷ��ͺͽ��� + + __HAL_RCC_USART1_CLK_ENABLE(); + + GPIO_InitStruct.Pin = TFT_WIFI_TX_Pin|TFT_WIFI_RX_Pin; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_PULLUP; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; + GPIO_InitStruct.Alternate = GPIO_AF7_USART1; + HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + GPIO_InitStruct.Mode = GPIO_MODE_INPUT; + GPIO_InitStruct.Pin = TFT_WIFI_RX_Pin; + HAL_GPIO_Init(GPIOA,&GPIO_InitStruct); + + USART_Init(USART1, &USART_InitStructure); + + NVIC_InitStructure.NVIC_IRQChannel = USART1_IRQn; + // NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0; + // NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0; + NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 3; + NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0; + NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; + + NVIC_Init(&NVIC_InitStructure); + #else + HAL_UART_DeInit(&huart1); + MX_USART1_UART_Init(3); + //__HAL_UART_ENABLE_IT(&huart1, UART_IT_RXNE); + HAL_UART_Receive_IT(&huart1,&mksUsart1Rx,1); + #endif + } + else{ + #if 0 + NVIC_DisableIRQ(SZ_STM32_COM1_IRQn); + + USART_Cmd(SZ_STM32_COM1, DISABLE); + + RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1, DISABLE); + RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1, ENABLE); + + SZ_STM32_COMInit(COM1, 1958400); + + USART_Cmd(SZ_STM32_COM1, ENABLE); + + wifi_delay(10); + + dma_init(); + #endif + HAL_UART_DeInit(&huart1); + MX_USART1_UART_Init(5); + //dma1_5_IRQ_sel = 1; + dma_init(); + } + #endif + if (interrupt) { + #if ENABLED(USE_WIFI_FUNCTION) + WIFISERIAL.end(); + for (uint16_t i = 0; i < 65535; i++); + WIFISERIAL.begin(WIFI_BAUDRATE); + uint32_t serial_connect_timeout = millis() + 1000UL; + while (/*!WIFISERIAL && */PENDING(millis(), serial_connect_timeout)) { /*nada*/ } + //for(uint8_t i=0;i<100;i++)WIFISERIAL.write(0x33); + #endif + } + else { + #if ENABLED(USE_WIFI_FUNCTION) + WIFISERIAL.end(); + for (uint16_t i = 0; i < 65535; i++); + WIFISERIAL.begin(WIFI_UPLOAD_BAUDRATE); + uint32_t serial_connect_timeout = millis() + 1000UL; + while (/*!WIFISERIAL && */PENDING(millis(), serial_connect_timeout)) { /*nada*/ } + //for(uint16_t i=0;i<65535;i++);//WIFISERIAL.write(0x33); + #endif + dma_init(); + } +} + +#if ENABLED(USE_WIFI_FUNCTION) + +int raw_send_to_wifi(char *buf, int len) { + if (buf == 0 || len <= 0) return 0; + + for (int i = 0; i < len; i++) + WIFISERIAL.write(*(buf + i)); + + return len; +} + +#endif // USE_WIFI_FUNCTION + +void wifi_ret_ack() {} + +char buf_to_wifi[256]; +int index_to_wifi = 0; +int package_to_wifi(WIFI_RET_TYPE type,char *buf, int len) { + char wifi_ret_head = 0xa5; + char wifi_ret_tail = 0xfc; + + if (type == WIFI_PARA_SET) { + int data_offset = 4; + int apLen = strlen((const char *)uiCfg.wifi_name); + int keyLen = strlen((const char *)uiCfg.wifi_key); + + memset(buf_to_wifi, 0, sizeof(buf_to_wifi)); + index_to_wifi = 0; + + buf_to_wifi[data_offset] = gCfgItems.wifi_mode_sel; + buf_to_wifi[data_offset + 1] = apLen; + strncpy(&buf_to_wifi[data_offset + 2], (const char *)uiCfg.wifi_name, apLen); + buf_to_wifi[data_offset + apLen + 2] = keyLen; + strncpy(&buf_to_wifi[data_offset + apLen + 3], (const char *)uiCfg.wifi_key, keyLen); + buf_to_wifi[data_offset + apLen + keyLen + 3] = wifi_ret_tail; + + index_to_wifi = apLen + keyLen + 3; + + buf_to_wifi[0] = wifi_ret_head; + buf_to_wifi[1] = type; + buf_to_wifi[2] = index_to_wifi & 0xff; + buf_to_wifi[3] = (index_to_wifi >> 8) & 0xff; + + raw_send_to_wifi(buf_to_wifi, 5 + index_to_wifi); + + memset(buf_to_wifi, 0, sizeof(buf_to_wifi)); + index_to_wifi = 0; + + } + else if (type == WIFI_TRANS_INF) { + if (len > (int)(sizeof(buf_to_wifi) - index_to_wifi - 5)) { + memset(buf_to_wifi, 0, sizeof(buf_to_wifi)); + index_to_wifi = 0; + return 0; + } + + if (len > 0) { + memcpy(&buf_to_wifi[4 + index_to_wifi], buf, len); + index_to_wifi += len; + + if (index_to_wifi < 1) + return 0; + + if (buf_to_wifi[index_to_wifi + 3] == '\n') { + //mask "wait" "busy" "X:" + if (((buf_to_wifi[4] == 'w') && (buf_to_wifi[5] == 'a') && (buf_to_wifi[6] == 'i') && (buf_to_wifi[7] == 't') ) + || ((buf_to_wifi[4] == 'b') && (buf_to_wifi[5] == 'u') && (buf_to_wifi[6] == 's') && (buf_to_wifi[7] == 'y') ) + || ((buf_to_wifi[4] == 'X') && (buf_to_wifi[5] == ':') ) + ) { + memset(buf_to_wifi, 0, sizeof(buf_to_wifi)); + index_to_wifi = 0; + return 0; + } + + buf_to_wifi[0] = wifi_ret_head; + buf_to_wifi[1] = type; + buf_to_wifi[2] = index_to_wifi & 0xff; + buf_to_wifi[3] = (index_to_wifi >> 8) & 0xff; + buf_to_wifi[4 + index_to_wifi] = wifi_ret_tail; + + raw_send_to_wifi(buf_to_wifi, 5 + index_to_wifi); + + memset(buf_to_wifi, 0, sizeof(buf_to_wifi)); + index_to_wifi = 0; + } + } + } + else if (type == WIFI_EXCEP_INF) { + memset(buf_to_wifi, 0, sizeof(buf_to_wifi)); + + buf_to_wifi[0] = wifi_ret_head; + buf_to_wifi[1] = type; + buf_to_wifi[2] = 1; + buf_to_wifi[3] = 0; + buf_to_wifi[4] = *buf; + buf_to_wifi[5] = wifi_ret_tail; + + raw_send_to_wifi(buf_to_wifi, 6); + + memset(buf_to_wifi, 0, sizeof(buf_to_wifi)); + index_to_wifi = 0; + } + else if (type == WIFI_CLOUD_CFG) { + int data_offset = 4; + int urlLen = strlen((const char *)uiCfg.cloud_hostUrl); + + memset(buf_to_wifi, 0, sizeof(buf_to_wifi)); + index_to_wifi = 0; + + if (gCfgItems.cloud_enable == true) + buf_to_wifi[data_offset] = 0x0a; + else + buf_to_wifi[data_offset] = 0x05; + + buf_to_wifi[data_offset + 1] = urlLen; + strncpy(&buf_to_wifi[data_offset + 2], (const char *)uiCfg.cloud_hostUrl, urlLen); + buf_to_wifi[data_offset + urlLen + 2] = uiCfg.cloud_port & 0xff; + buf_to_wifi[data_offset + urlLen + 3] = (uiCfg.cloud_port >> 8) & 0xff; + buf_to_wifi[data_offset + urlLen + 4] = wifi_ret_tail; + + index_to_wifi = urlLen + 4; + + buf_to_wifi[0] = wifi_ret_head; + buf_to_wifi[1] = type; + buf_to_wifi[2] = index_to_wifi & 0xff; + buf_to_wifi[3] = (index_to_wifi >> 8) & 0xff; + + raw_send_to_wifi(buf_to_wifi, 5 + index_to_wifi); + + memset(buf_to_wifi, 0, sizeof(buf_to_wifi)); + index_to_wifi = 0; + } + else if (type == WIFI_CLOUD_UNBIND) { + memset(buf_to_wifi, 0, sizeof(buf_to_wifi)); + + buf_to_wifi[0] = wifi_ret_head; + buf_to_wifi[1] = type; + buf_to_wifi[2] = 0; + buf_to_wifi[3] = 0; + buf_to_wifi[4] = wifi_ret_tail; + + raw_send_to_wifi(buf_to_wifi, 5); + + memset(buf_to_wifi, 0, sizeof(buf_to_wifi)); + index_to_wifi = 0; + } +} + + +int send_to_wifi(char *buf, int len) { return package_to_wifi(WIFI_TRANS_INF, buf, len); } + +void set_cur_file_sys(int fileType) { + gCfgItems.fileSysType = fileType; +} + +void get_file_list(char *path) { + if ( path == 0) { + return; + } + + if (gCfgItems.fileSysType == FILE_SYS_SD) { + #if ENABLED(SDSUPPORT) + card.mount(); + #endif + } + else if (gCfgItems.fileSysType == FILE_SYS_USB) { + //udisk + } + Explore_Disk(path, 0); +} + +char wait_ip_back_flag = 0; + +typedef struct { + char write_buf[513]; + int write_index; + uint8_t saveFileName[30]; + uint32_t fileLen; + uint32_t tick_begin; + uint32_t tick_end; +} FILE_WRITER; + +FILE_WRITER file_writer; + +int32_t lastFragment = 0; + +char lastBinaryCmd[50] = {0}; + +int total_write = 0; +char binary_head[2] = {0, 0}; +unsigned char binary_data_len = 0; + +int write_to_file(char *buf, int len) { + int i; + int res; + + for (i = 0; i < len; i++) { + file_writer.write_buf[file_writer.write_index++] = buf[i]; + if (file_writer.write_index >= 512) { + res = card.write(file_writer.write_buf, file_writer.write_index); + if (res == -1) { + return -1; + } + memset(file_writer.write_buf, 0, sizeof(file_writer.write_buf)); + file_writer.write_index = 0; + } + } + return 0; +} + +#define ESP_PROTOC_HEAD (uint8_t)0xa5 +#define ESP_PROTOC_TAIL (uint8_t)0xfc + +#define ESP_TYPE_NET (uint8_t)0x0 +#define ESP_TYPE_GCODE (uint8_t)0x1 +#define ESP_TYPE_FILE_FIRST (uint8_t)0x2 +#define ESP_TYPE_FILE_FRAGMENT (uint8_t)0x3 + +#define ESP_TYPE_WIFI_LIST (uint8_t)0x4 + +uint8_t esp_msg_buf[UART_RX_BUFFER_SIZE] = {0}; +uint16_t esp_msg_index = 0; + +typedef struct { + uint8_t head; + uint8_t type; + uint16_t dataLen; + uint8_t *data; + uint8_t tail; +} ESP_PROTOC_FRAME; + + +static int cut_msg_head(uint8_t *msg, uint16_t msgLen, uint16_t cutLen) { + if (msgLen < cutLen) return 0; + + else if (msgLen == cutLen) { + memset(msg, 0, msgLen); + return 0; + } + + for (int i = 0; i < (msgLen - cutLen); i++) + msg[i] = msg[cutLen + i]; + + memset(&msg[msgLen - cutLen], 0, cutLen); + + return msgLen - cutLen; +} + + +uint8_t Explore_Disk (char* path , uint8_t recu_level) { + char tmp[200]; + char Fstream[200]; + + if (path == 0)return 0; + + const uint8_t fileCnt = card.get_num_Files(); + + for (uint8_t i = 0; i < fileCnt; i++) { + const uint16_t nr = + #if ENABLED(SDCARD_RATHERRECENTFIRST) && DISABLED(SDCARD_SORT_ALPHA) + fileCnt - 1 - + #endif + i; + + #if ENABLED(SDCARD_SORT_ALPHA) + card.getfilename_sorted(nr); + #else + card.getfilename_sorted(nr); + #endif + memset(tmp, 0, sizeof(tmp)); + //if (card.longFilename[0] == 0) + strcpy(tmp, card.filename); + //else + //strcpy(tmp, card.longFilename); + + memset(Fstream, 0, sizeof(Fstream)); + strcpy(Fstream, tmp); + + if (card.flag.filenameIsDir && (recu_level <= 10)) { + strcat(Fstream, ".DIR\r\n"); + send_to_wifi(Fstream, strlen(Fstream)); + } + else { + strcat(Fstream, "\r\n"); + send_to_wifi(Fstream, strlen(Fstream)); + } + } + + return fileCnt; +} + +static void wifi_gcode_exec(uint8_t *cmd_line) { + int8_t tempBuf[100] = {0}; + uint8_t *tmpStr = 0; + int cmd_value; + volatile int print_rate; + if ((strstr((char *)&cmd_line[0], "\n") != 0) && ((strstr((char *)&cmd_line[0], "G") != 0) || (strstr((char *)&cmd_line[0], "M") != 0) || (strstr((char *)&cmd_line[0], "T") != 0) )) { + + tmpStr = (uint8_t *)strstr((char *)&cmd_line[0], "\n"); + if (tmpStr) { + *tmpStr = '\0'; + } + tmpStr = (uint8_t *)strstr((char *)&cmd_line[0], "\r"); + if (tmpStr) { + *tmpStr = '\0'; + } + tmpStr = (uint8_t *)strstr((char *)&cmd_line[0], "*"); + if (tmpStr) { + *tmpStr = '\0'; + } + tmpStr = (uint8_t *)strstr((char *)&cmd_line[0], "M"); + if ( tmpStr) { + cmd_value = atoi((char *)(tmpStr + 1)); + tmpStr = (uint8_t *)strstr((char *)tmpStr, " "); + + switch (cmd_value) { + + case 20: //print sd / udisk file + if (uiCfg.print_state == IDLE) { + int index = 0; + + if (tmpStr == 0) { + gCfgItems.fileSysType = FILE_SYS_SD; + send_to_wifi((char *)"Begin file list\r\n", strlen("Begin file list\r\n")); + + get_file_list((char *)"0:/"); + + send_to_wifi((char *)"End file list\r\n", strlen("End file list\r\n")); + + send_to_wifi((char *)"ok\r\n", strlen("ok\r\n")); + break; + } + + while (tmpStr[index] == ' ') + index++; + + if (gCfgItems.wifi_type == ESP_WIFI) { + char *path = (char *)tempBuf; + + if (strlen((char *)&tmpStr[index]) < 80) { + send_to_wifi((char *)"Begin file list\r\n", strlen("Begin file list\r\n")); + + if (strncmp((char *)&tmpStr[index], "1:", 2) == 0) { + gCfgItems.fileSysType = FILE_SYS_SD; + + } + else if (strncmp((char *)&tmpStr[index], "0:", 2) == 0) { + gCfgItems.fileSysType = FILE_SYS_USB; + } + strcpy((char *)path, (char *)&tmpStr[index]); + get_file_list(path); + send_to_wifi((char *)"End file list\r\n", strlen("End file list\r\n")); + } + send_to_wifi((char *)"ok\r\n", strlen("ok\r\n")); + } + } + break; + + case 21: + /*init sd card*/ + send_to_wifi((char *)"ok\r\n", strlen("ok\r\n")); + break; + + case 23: + /*select the file*/ + if (uiCfg.print_state == IDLE) { + int index = 0; + while (tmpStr[index] == ' ') + index++; + + if (strstr((char *)&tmpStr[index], ".g") || strstr((char *)&tmpStr[index], ".G")) { + if (strlen((char *)&tmpStr[index]) < 80) { + memset(list_file.file_name[sel_id], 0, sizeof(list_file.file_name[sel_id])); + + if (gCfgItems.wifi_type == ESP_WIFI) { + if (strncmp((char *)&tmpStr[index], "1:", 2) == 0) { + gCfgItems.fileSysType = FILE_SYS_SD; + + } + else if (strncmp((char *)&tmpStr[index], "0:", 2) == 0) { + gCfgItems.fileSysType = FILE_SYS_USB; + } + else { + if (tmpStr[index] != '/') + strcat((char *)list_file.file_name[0], "/"); + } + strcat((char *)list_file.file_name[sel_id], (char *)&tmpStr[index]); + + } + else { + strcpy(list_file.file_name[sel_id], (char *)&tmpStr[index]); + } + + char *cur_name=strrchr(list_file.file_name[sel_id],'/'); + + card.openFileRead(cur_name); + + if (card.isFileOpen()) { + send_to_wifi((char *)"File selected\r\n", strlen("File selected\r\n")); + + } + else { + send_to_wifi((char *)"file.open failed\r\n", strlen("file.open failed\r\n")); + strcpy(list_file.file_name[sel_id], "notValid"); + } + send_to_wifi((char *)"ok\r\n", strlen("ok\r\n")); + + } + + + } + } + break; + + case 24: + if (strcmp(list_file.file_name[sel_id], "notValid") != 0) { + if (uiCfg.print_state == IDLE) { + clear_cur_ui(); + reset_print_time(); + start_print_time(); + preview_gcode_prehandle(list_file.file_name[sel_id]); + uiCfg.print_state = WORKING; + lv_draw_printing(); + + if (gcode_preview_over != 1) { + #if ENABLED(SDSUPPORT) + char *cur_name; + cur_name=strrchr(list_file.file_name[sel_id],'/'); + + SdFile file; + SdFile *curDir; + card.endFilePrint(); + const char * const fname = card.diveToFile(true, curDir, cur_name); + if (!fname) return; + if (file.open(curDir, fname, O_READ)) { + gCfgItems.curFilesize = file.fileSize(); + file.close(); + update_spi_flash(); + } + card.openFileRead(cur_name); + if (card.isFileOpen()) { + feedrate_percentage = 100; + //saved_feedrate_percentage = feedrate_percentage; + planner.flow_percentage[0] = 100; + planner.e_factor[0]= planner.flow_percentage[0]*0.01; + if (EXTRUDERS==2) { + planner.flow_percentage[1] = 100; + planner.e_factor[1]= planner.flow_percentage[1]*0.01; + } + card.startFileprint(); + #if ENABLED(POWER_LOSS_RECOVERY) + recovery.prepare(); + #endif + once_flag = 0; + } + #endif + + } + } + else if (uiCfg.print_state == PAUSED) { + uiCfg.print_state = RESUMING; + clear_cur_ui(); + start_print_time(); + + if (gCfgItems.from_flash_pic==1) + flash_preview_begin = 1; + else + default_preview_flg = 1; + lv_draw_printing(); + } + else if (uiCfg.print_state == REPRINTING) { + uiCfg.print_state = REPRINTED; + clear_cur_ui(); + start_print_time(); + if (gCfgItems.from_flash_pic==1) + flash_preview_begin = 1; + else + default_preview_flg = 1; + lv_draw_printing(); + } + } + send_to_wifi((char *)"ok\r\n", strlen("ok\r\n")); + break; + + case 25: + /*pause print file*/ + if (uiCfg.print_state == WORKING) { + stop_print_time(); + + clear_cur_ui(); + + #if ENABLED(SDSUPPORT) + card.pauseSDPrint(); + uiCfg.print_state = PAUSING; + #endif + if (gCfgItems.from_flash_pic==1) + flash_preview_begin = 1; + else + default_preview_flg = 1; + lv_draw_printing(); + send_to_wifi((char *)"ok\r\n", strlen("ok\r\n")); + } + break; + + case 26: + /*stop print file*/ + if ((uiCfg.print_state == WORKING) || (uiCfg.print_state == PAUSED) || (uiCfg.print_state == REPRINTING)) { + stop_print_time(); + + clear_cur_ui(); + #if ENABLED(SDSUPPORT) + uiCfg.print_state = IDLE; + card.flag.abort_sd_printing = true; + #endif + + lv_draw_ready_print(); + + send_to_wifi((char *)"ok\r\n", strlen("ok\r\n")); + } + break; + + case 27: + /*report print rate*/ + if ((uiCfg.print_state == WORKING) || (uiCfg.print_state == PAUSED)|| (uiCfg.print_state == REPRINTING)) { + print_rate = uiCfg.totalSend; + + memset((char *)tempBuf, 0, sizeof(tempBuf)); + + sprintf((char *)tempBuf, "M27 %d\r\n", print_rate); + + send_to_wifi((char *)tempBuf, strlen((char *)tempBuf)); + + } + + break; + + case 28: + /*begin to transfer file to filesys*/ + if (uiCfg.print_state == IDLE) { + + int index = 0; + while (tmpStr[index] == ' ') + index++; + + if (strstr((char *)&tmpStr[index], ".g") || strstr((char *)&tmpStr[index], ".G")) { + strcpy((char *)file_writer.saveFileName, (char *)&tmpStr[index]); + + if (gCfgItems.fileSysType == FILE_SYS_SD) { + memset(tempBuf, 0, sizeof(tempBuf)); + sprintf((char *)tempBuf, "%s", file_writer.saveFileName); + } + else if (gCfgItems.fileSysType == FILE_SYS_USB) { + memset(tempBuf, 0, sizeof(tempBuf)); + sprintf((char *)tempBuf, "%s", (char *)file_writer.saveFileName); + } + mount_file_sys(gCfgItems.fileSysType); + + #if ENABLED(SDSUPPORT) + char *cur_name=strrchr(list_file.file_name[sel_id],'/'); + card.openFileWrite(cur_name); + if (card.isFileOpen()) { + memset(file_writer.saveFileName, 0, sizeof(file_writer.saveFileName)); + strcpy((char *)file_writer.saveFileName, (char *)&tmpStr[index]); + memset(tempBuf, 0, sizeof(tempBuf)); + sprintf((char *)tempBuf, "Writing to file: %s\r\n", (char *)file_writer.saveFileName); + wifi_ret_ack(); + send_to_wifi((char *)tempBuf, strlen((char *)tempBuf)); + + total_write = 0; + wifi_link_state = WIFI_WAIT_TRANS_START; + + } + else{ + wifi_link_state = WIFI_CONNECTED; + clear_cur_ui(); + lv_draw_dialog(DIALOG_TRANSFER_NO_DEVICE); + } + #endif + + } + + } + break; + case 105: + case 991: + memset(tempBuf, 0, sizeof(tempBuf)); + if (cmd_value == 105) { + send_to_wifi((char *)"ok\r\n", strlen("ok\r\n")); + sprintf((char *)tempBuf,"T:%.1f /%.1f B:%.1f /%.1f T0:%.1f /%.1f T1:%.1f /%.1f @:0 B@:0\r\n", + + (float)thermalManager.temp_hotend[0].celsius,(float)thermalManager.temp_hotend[0].target, + #if HAS_HEATED_BED + (float)thermalManager.temp_bed.celsius,(float)thermalManager.temp_bed.target, + #else + (float)0,(float)0, + #endif + (float)thermalManager.temp_hotend[0].celsius,(float)thermalManager.temp_hotend[0].target, + #if !defined(SINGLENOZZLE) && HAS_MULTI_EXTRUDER + (float)thermalManager.temp_hotend[1].celsius,(float)thermalManager.temp_hotend[1].target + #else + (float)0,(float)0 + #endif + ); + } + else { + sprintf((char *)tempBuf,"T:%d /%d B:%d /%d T0:%d /%d T1:%d /%d @:0 B@:0\r\n", + + (int)thermalManager.temp_hotend[0].celsius,(int)thermalManager.temp_hotend[0].target, + #if HAS_HEATED_BED + (int)thermalManager.temp_bed.celsius,(int)thermalManager.temp_bed.target, + #else + 0,0, + #endif + (int)thermalManager.temp_hotend[0].celsius,(int)thermalManager.temp_hotend[0].target, + #if !defined(SINGLENOZZLE) && HAS_MULTI_EXTRUDER + (int)thermalManager.temp_hotend[1].celsius,(int)thermalManager.temp_hotend[1].target + #else + 0,0 + #endif + ); + } + + send_to_wifi((char *)tempBuf, strlen((char *)tempBuf)); + + queue.enqueue_one_P(PSTR("M105")); + + break; + case 992: + if ((uiCfg.print_state == WORKING) || (uiCfg.print_state == PAUSED)) { + memset(tempBuf,0,sizeof(tempBuf)); + sprintf((char *)tempBuf, "M992 %d%d:%d%d:%d%d\r\n", print_time.hours/10, print_time.hours%10, print_time.minutes/10, print_time.minutes%10, print_time.seconds/10, print_time.seconds%10); + wifi_ret_ack(); + send_to_wifi((char *)tempBuf, strlen((char *)tempBuf)); + } + + break; + case 994: + if ((uiCfg.print_state == WORKING) || (uiCfg.print_state == PAUSED)) { + memset(tempBuf,0,sizeof(tempBuf)); + if (strlen((char *)list_file.file_name[sel_id]) > (100-1)) { + return; + } + sprintf((char *)tempBuf, "M994 %s;%d\n", list_file.file_name[sel_id],(int)gCfgItems.curFilesize); + wifi_ret_ack(); + send_to_wifi((char *)tempBuf, strlen((char *)tempBuf)); + } + break; + case 997: + if (uiCfg.print_state == IDLE) { + wifi_ret_ack(); + send_to_wifi((char *)"M997 IDLE\r\n", strlen("M997 IDLE\r\n")); + } + else if (uiCfg.print_state == WORKING) { + wifi_ret_ack(); + send_to_wifi((char *)"M997 PRINTING\r\n", strlen("M997 PRINTING\r\n")); + } + else if (uiCfg.print_state == PAUSED) { + wifi_ret_ack(); + send_to_wifi((char *)"M997 PAUSE\r\n", strlen("M997 PAUSE\r\n")); + } + else if (uiCfg.print_state == REPRINTING) { + wifi_ret_ack(); + send_to_wifi((char *)"M997 PAUSE\r\n", strlen("M997 PAUSE\r\n")); + } + if (uiCfg.command_send == 0) get_wifi_list_command_send(); + break; + + case 998: + if (uiCfg.print_state == IDLE) { + if (atoi((char *)tmpStr) == 0) { + set_cur_file_sys(0); + } + else if (atoi((char *)tmpStr) == 1) { + set_cur_file_sys(1); + } + wifi_ret_ack(); + } + break; + + case 115: + memset(tempBuf,0,sizeof(tempBuf)); + send_to_wifi((char *)"ok\r\n", strlen("ok\r\n")); + send_to_wifi((char *)"FIRMWARE_NAME:Robin_nano\r\n", strlen("FIRMWARE_NAME:Robin_nano\r\n")); + break; + + default: + strcat((char *)cmd_line, "\n"); + + uint32_t left; + + if (espGcodeFifo.wait_tick> 5) { + + if (espGcodeFifo.r > espGcodeFifo.w) + left = espGcodeFifo.r - espGcodeFifo.w - 1; + else + left = WIFI_GCODE_BUFFER_SIZE + espGcodeFifo.r - espGcodeFifo.w - 1; + if (left >= strlen((const char *)cmd_line)) { + uint32_t index = 0; + while (index < strlen((const char *)cmd_line)) { + espGcodeFifo.Buffer[espGcodeFifo.w] = cmd_line[index] ; + espGcodeFifo.w = (espGcodeFifo.w + 1) % WIFI_GCODE_BUFFER_SIZE; + index++; + } + if (left - WIFI_GCODE_BUFFER_LEAST_SIZE >= strlen((const char *)cmd_line)) + send_to_wifi((char *)"ok\r\n", strlen("ok\r\n")); + else + need_ok_later = true; + + } + + } + break; + + } + } + else{ + strcat((char *)cmd_line, "\n"); + uint32_t left_g; + + if (espGcodeFifo.wait_tick > 5) { + + if (espGcodeFifo.r > espGcodeFifo.w) + left_g = espGcodeFifo.r - espGcodeFifo.w - 1; + else + left_g = WIFI_GCODE_BUFFER_SIZE + espGcodeFifo.r - espGcodeFifo.w - 1; + if (left_g >= strlen((const char *)cmd_line)) { + uint32_t index = 0; + while (index < strlen((const char *)cmd_line)) { + espGcodeFifo.Buffer[espGcodeFifo.w] = cmd_line[index] ; + espGcodeFifo.w = (espGcodeFifo.w + 1) % WIFI_GCODE_BUFFER_SIZE; + index++; + } + if (left_g - WIFI_GCODE_BUFFER_LEAST_SIZE >= strlen((const char *)cmd_line)) + send_to_wifi((char *)"ok\r\n", strlen("ok\r\n")); + else + need_ok_later = true; + + } + } + } + } +} + +static int32_t charAtArray(const uint8_t *_array, uint32_t _arrayLen, uint8_t _char) { + for (uint32_t i = 0; i < _arrayLen; i++) + if (*(_array + i) == _char) return i; + return -1; +} + +void get_wifi_list_command_send() { + char buf[6] = {0}; + buf[0] = 0xA5; + buf[1] = 0x07; + buf[2] = 0x00; + buf[3] = 0x00; + buf[4] = 0xFC; + raw_send_to_wifi(buf, 5); +} + +static void net_msg_handle(uint8_t * msg, uint16_t msgLen) { + int wifiNameLen, wifiKeyLen, hostLen, id_len, ver_len; + + if (msgLen <= 0) return; + //ip + sprintf(ipPara.ip_addr, "%d.%d.%d.%d", msg[0], msg[1], msg[2], msg[3]); + + //port + //connect state + if (msg[6] == 0x0A) + wifi_link_state = WIFI_CONNECTED; + else if (msg[6] == 0x0E) + wifi_link_state = WIFI_EXCEPTION; + else + wifi_link_state = WIFI_NOT_CONFIG; + + //mode + wifiPara.mode = msg[7]; + + + //wifi name + wifiNameLen = msg[8]; + wifiKeyLen = msg[9 + wifiNameLen]; + if (wifiNameLen < 32) { + memset(wifiPara.ap_name, 0, sizeof(wifiPara.ap_name)); + memcpy(wifiPara.ap_name, &msg[9], wifiNameLen); + + memset(&wifi_list.wifiConnectedName,0,sizeof(wifi_list.wifiConnectedName)); + memcpy(&wifi_list.wifiConnectedName,&msg[9],wifiNameLen); + + //wifi key + if (wifiKeyLen < 64) { + memset(wifiPara.keyCode, 0, sizeof(wifiPara.keyCode)); + memcpy(wifiPara.keyCode, &msg[10 + wifiNameLen], wifiKeyLen); + } + } + + + cloud_para.state =msg[10 + wifiNameLen + wifiKeyLen]; + hostLen = msg[11 + wifiNameLen + wifiKeyLen]; + if (cloud_para.state) { + if (hostLen < 96) { + memset(cloud_para.hostUrl, 0, sizeof(cloud_para.hostUrl)); + memcpy(cloud_para.hostUrl, &msg[12 + wifiNameLen + wifiKeyLen], hostLen); + } + cloud_para.port = msg[12 + wifiNameLen + wifiKeyLen + hostLen] + (msg[13 + wifiNameLen + wifiKeyLen + hostLen] << 8); + + } + + // id + id_len = msg[14 + wifiNameLen + wifiKeyLen + hostLen]; + if (id_len == 20) { + memset(cloud_para.id, 0, sizeof(cloud_para.id)); + memcpy(cloud_para.id, (const char *)&msg[15 + wifiNameLen + wifiKeyLen + hostLen], id_len); + } + ver_len = msg[15 + wifiNameLen + wifiKeyLen + hostLen + id_len]; + if (ver_len < 20) { + memset(wifi_firm_ver, 0, sizeof(wifi_firm_ver)); + memcpy(wifi_firm_ver, (const char *)&msg[16 + wifiNameLen + wifiKeyLen + hostLen + id_len], ver_len); + } + + if (uiCfg.configWifi == 1) { + if ((wifiPara.mode != gCfgItems.wifi_mode_sel) + || (strncmp(wifiPara.ap_name, (const char *)uiCfg.wifi_name, 32) != 0) + || (strncmp(wifiPara.keyCode, (const char *)uiCfg.wifi_key, 64) != 0)) { + package_to_wifi(WIFI_PARA_SET, (char *)0, 0); + } + else uiCfg.configWifi = 0; + } + if (cfg_cloud_flag == 1) { + if (((cloud_para.state >> 4) != (char)gCfgItems.cloud_enable) + || (strncmp(cloud_para.hostUrl, (const char *)uiCfg.cloud_hostUrl, 96) != 0) + || (cloud_para.port != uiCfg.cloud_port)) { + package_to_wifi(WIFI_CLOUD_CFG, (char *)0, 0); + } + else cfg_cloud_flag = 0; + } +} + +static void wifi_list_msg_handle(uint8_t * msg, uint16_t msgLen) { + int wifiNameLen,wifiMsgIdex=1; + int8_t wifi_name_is_same=0; + int8_t i,j; + int8_t wifi_name_num=0; + uint8_t *str=0; + int8_t valid_name_num; + + if (msgLen <= 0) + return; + if (disp_state == KEY_BOARD_UI) + return; + + wifi_list.getNameNum = msg[0]; + + if (wifi_list.getNameNum < 20) { + uiCfg.command_send = 1; + + memset(wifi_list.wifiName,0,sizeof(wifi_list.wifiName)); + + wifi_name_num = wifi_list.getNameNum; + + valid_name_num=0; + str = wifi_list.wifiName[valid_name_num]; + + if (wifi_list.getNameNum > 0) wifi_list.currentWifipage = 1; + + for (i = 0; i 0x80) { + wifi_name_is_same = 1; + //break; + } + //} + } + if (wifi_name_is_same == 1) { + wifi_name_is_same = 0; + wifiMsgIdex += wifiNameLen; + //wifi_list.RSSI[i] = msg[wifiMsgIdex]; + wifiMsgIdex += 1; + wifi_name_num--; + //i--; + continue; + } + if (i < WIFI_TOTAL_NUMBER-1) { + str = wifi_list.wifiName[++valid_name_num]; + } + } + wifiMsgIdex += wifiNameLen; + wifi_list.RSSI[i] = msg[wifiMsgIdex]; + wifiMsgIdex += 1; + } + wifi_list.getNameNum = wifi_name_num; + if (wifi_list.getNameNum % NUMBER_OF_PAGE == 0) { + wifi_list.getPage = wifi_list.getNameNum/NUMBER_OF_PAGE; + } + else { + wifi_list.getPage = wifi_list.getNameNum/NUMBER_OF_PAGE + 1; + } + wifi_list.nameIndex = 0; + if (disp_state == WIFI_LIST_UI) + disp_wifi_list(); + } +} + +static void gcode_msg_handle(uint8_t * msg, uint16_t msgLen) { + uint8_t gcodeBuf[100] = {0}; + char *index_s; + char *index_e; + + if (msgLen <= 0) + return; + + index_s = (char *)msg; + index_e = (char *)strstr((char *)msg, "\n"); + if (*msg == 'N') { + index_s = (char *)strstr((char *)msg, " "); + while ((*index_s) == ' ') { + index_s++; + } + } + while ((index_e != 0) && ((int)index_s < (int)index_e)) { + if ((int)(index_e - index_s) < (int)sizeof(gcodeBuf)) { + memset(gcodeBuf, 0, sizeof(gcodeBuf)); + + memcpy(gcodeBuf, index_s, index_e - index_s + 1); + + wifi_gcode_exec(gcodeBuf); + } + while ((*index_e == '\r') || (*index_e == '\n')) + index_e++; + + index_s = index_e; + index_e = (char *)strstr(index_s, "\n"); + } +} + +void utf8_2_unicode(uint8_t *source,uint8_t Len) { + uint8_t i=0,char_i=0,char_byte_num=0; + uint16_t u16_h,u16_m,u16_l,u16_value; + uint8_t FileName_unicode[30]; + + memset(FileName_unicode, 0, sizeof(FileName_unicode)); + + while (1) { + char_byte_num = source[i] & 0xF0; + if (source[i] < 0X80) { + //ASCII --1byte + FileName_unicode[char_i] = source[i]; + i += 1; + char_i += 1; + } + else if (char_byte_num == 0XC0 || char_byte_num == 0XD0) { + //--2byte + + u16_h = (((uint16_t)source[i] <<8) & 0x1f00) >> 2; + u16_l = ((uint16_t)source[i+1] & 0x003f); + u16_value = (u16_h | u16_l); + FileName_unicode[char_i] = (uint8_t)((u16_value & 0xff00) >> 8); + FileName_unicode[char_i + 1] = (uint8_t)(u16_value & 0x00ff); + i += 2; + char_i += 2; + } + else if (char_byte_num == 0XE0) { + //--3byte + u16_h = (((uint16_t)source[i] <<8 ) & 0x0f00) << 4; + u16_m = (((uint16_t)source[i+1] << 8) & 0x3f00) >> 2; + u16_l = ((uint16_t)source[i+2] & 0x003f); + u16_value = (u16_h | u16_m | u16_l); + FileName_unicode[char_i] = (uint8_t)((u16_value & 0xff00) >> 8); + FileName_unicode[char_i + 1] = (uint8_t)(u16_value & 0x00ff); + i += 3; + char_i += 2; + } + else if (char_byte_num == 0XF0) { + //--4byte + i += 4; + //char_i += 3; + } + else { + break; + } + if (i >= Len || i >= 255)break; + } + memcpy(source, FileName_unicode, sizeof(FileName_unicode)); +} + +char saveFilePath[50]; + +static bool longName2DosName(const char* longName, uint8_t* dosName) { + uint8_t i = 11; + while (i--) dosName[i] = '\0'; + while (*longName) { + uint8_t c = *longName++; + if (c == '.') { // For a dot... + if (i == 0) return false; + else { strcat((char *)dosName,".GCO"); return dosName[0] != '\0'; } + } + else { + // Fail for illegal characters + PGM_P p = PSTR("|<>^+=?/[];,*\"\\"); + while (uint8_t b = pgm_read_byte(p++)) if (b == c) return false; + if (c < 0x21 || c == 0x7F) return false; // Check size, non-printable characters + dosName[i++] = (c < 'a' || c > 'z') ? (c) : (c + ('A' - 'a')); // Uppercase required for 8.3 name + } + if (i >= 5) strcat((char *)dosName,"~1.GCO"); + } + return dosName[0] != '\0'; // Return true if any name was set +} + +static void file_first_msg_handle(uint8_t * msg, uint16_t msgLen) { + uint8_t fileNameLen = *msg; + + if (msgLen != fileNameLen + 5) return; + + file_writer.fileLen = *((uint32_t *)(msg + 1)); + memset(file_writer.saveFileName, 0, sizeof(file_writer.saveFileName)); + + memcpy(file_writer.saveFileName, msg + 5, fileNameLen); + + utf8_2_unicode(file_writer.saveFileName,fileNameLen); + + memset(file_writer.write_buf, 0, sizeof(file_writer.write_buf)); + + if (strlen((const char *)file_writer.saveFileName) > sizeof(saveFilePath)) + return; + + memset(saveFilePath, 0, sizeof(saveFilePath)); + + if (gCfgItems.fileSysType == FILE_SYS_SD) { + //sprintf((char *)saveFilePath, "/%s", file_writer.saveFileName); + card.mount(); + + //ZERO(list_file.long_name[sel_id]); + //memcpy(list_file.long_name[sel_id],file_writer.saveFileName,sizeof(list_file.long_name[sel_id])); + } + else if (gCfgItems.fileSysType == FILE_SYS_USB) { + + } + file_writer.write_index = 0; + lastFragment = -1; + + wifiTransError.flag = 0; + wifiTransError.start_tick = 0; + wifiTransError.now_tick = 0; + + TERN_(SDSUPPORT, card.closefile()); + + wifi_delay(1000); + + #if ENABLED(SDSUPPORT) + + uint8_t dosName[FILENAME_LENGTH]; + + if (!longName2DosName((const char *)file_writer.saveFileName,dosName)) { + clear_cur_ui(); + upload_result = 2; + wifiTransError.flag = 1; + wifiTransError.start_tick = getWifiTick(); + lv_draw_dialog(DIALOG_TYPE_UPLOAD_FILE); + return; + } + sprintf((char *)saveFilePath, "/%s", dosName); + + ZERO(list_file.long_name[sel_id]); + memcpy(list_file.long_name[sel_id],dosName,sizeof(dosName)); + + char *cur_name=strrchr((const char *)saveFilePath,'/'); + + SdFile file; + SdFile *curDir; + card.endFilePrint(); + const char * const fname = card.diveToFile(true, curDir, cur_name); + if (!fname) return; + if (file.open(curDir, fname, O_CREAT | O_APPEND | O_WRITE | O_TRUNC)) { + gCfgItems.curFilesize = file.fileSize(); + } + else { + clear_cur_ui(); + upload_result = 2; + wifiTransError.flag = 1; + wifiTransError.start_tick = getWifiTick(); + lv_draw_dialog(DIALOG_TYPE_UPLOAD_FILE); + return; + } + #endif + + wifi_link_state = WIFI_TRANS_FILE; + + upload_result = 1; + + clear_cur_ui(); + lv_draw_dialog(DIALOG_TYPE_UPLOAD_FILE); + + lv_task_handler(); + + file_writer.tick_begin = getWifiTick(); +} + +#define FRAG_MASK _BV32(31) + +static void file_fragment_msg_handle(uint8_t * msg, uint16_t msgLen) { + uint32_t frag = *((uint32_t *)msg); + + if ((frag & FRAG_MASK) != (uint32_t)(lastFragment + 1)) { + memset(file_writer.write_buf, 0, sizeof(file_writer.write_buf)); + file_writer.write_index = 0; + wifi_link_state = WIFI_CONNECTED; + upload_result = 2; + } + else { + if (write_to_file((char *)msg + 4, msgLen - 4) < 0) { + memset(file_writer.write_buf, 0, sizeof(file_writer.write_buf)); + file_writer.write_index = 0; + wifi_link_state = WIFI_CONNECTED; + upload_result = 2; + return; + } + lastFragment = frag; + + if ((frag & (~FRAG_MASK))) { + int res = card.write(file_writer.write_buf, file_writer.write_index); + if (res == -1) { + memset(file_writer.write_buf, 0, sizeof(file_writer.write_buf)); + file_writer.write_index = 0; + wifi_link_state = WIFI_CONNECTED; + upload_result = 2; + return; + } + memset(file_writer.write_buf, 0, sizeof(file_writer.write_buf)); + file_writer.write_index = 0; + file_writer.tick_end = getWifiTick(); + upload_time = getWifiTickDiff(file_writer.tick_begin, file_writer.tick_end) / 1000; + upload_size = gCfgItems.curFilesize; + wifi_link_state = WIFI_CONNECTED; + upload_result = 3; + } + + } +} + +void esp_data_parser(char *cmdRxBuf, int len) { + int32_t head_pos; + int32_t tail_pos; + uint16_t cpyLen; + int16_t leftLen = len; + bool loop_again = false; + + ESP_PROTOC_FRAME esp_frame; + + while (leftLen > 0 || loop_again) { + loop_again = false; + + if (esp_msg_index != 0) { + head_pos = 0; + cpyLen = (leftLen < (int16_t)((sizeof(esp_msg_buf) - esp_msg_index)) ? leftLen : sizeof(esp_msg_buf) - esp_msg_index); + + memcpy(&esp_msg_buf[esp_msg_index], cmdRxBuf + len - leftLen, cpyLen); + + esp_msg_index += cpyLen; + + leftLen = leftLen - cpyLen; + tail_pos = charAtArray(esp_msg_buf, esp_msg_index, ESP_PROTOC_TAIL); + + if (tail_pos == -1) { + if (esp_msg_index >= sizeof(esp_msg_buf)) { + memset(esp_msg_buf, 0, sizeof(esp_msg_buf)); + esp_msg_index = 0; + } + return; + } + } + else { + head_pos = charAtArray((uint8_t const *)&cmdRxBuf[len - leftLen], leftLen, ESP_PROTOC_HEAD); + if (head_pos == -1) return; + + memset(esp_msg_buf, 0, sizeof(esp_msg_buf)); + memcpy(esp_msg_buf, &cmdRxBuf[len - leftLen + head_pos], leftLen - head_pos); + + esp_msg_index = leftLen - head_pos; + + leftLen = 0; + head_pos = 0; + tail_pos = charAtArray(esp_msg_buf, esp_msg_index, ESP_PROTOC_TAIL); + if (tail_pos == -1) { + if (esp_msg_index >= sizeof(esp_msg_buf)) { + memset(esp_msg_buf, 0, sizeof(esp_msg_buf)); + esp_msg_index = 0; + } + return; + } + } + + esp_frame.type = esp_msg_buf[1]; + if ((esp_frame.type != ESP_TYPE_NET) && (esp_frame.type != ESP_TYPE_GCODE) + && (esp_frame.type != ESP_TYPE_FILE_FIRST) && (esp_frame.type != ESP_TYPE_FILE_FRAGMENT) + &&(esp_frame.type != ESP_TYPE_WIFI_LIST)) { + memset(esp_msg_buf, 0, sizeof(esp_msg_buf)); + esp_msg_index = 0; + return; + } + + esp_frame.dataLen = esp_msg_buf[2] + (esp_msg_buf[3] << 8); + + if ((int)(4 + esp_frame.dataLen) > (int)(sizeof(esp_msg_buf))) { + memset(esp_msg_buf, 0, sizeof(esp_msg_buf)); + esp_msg_index = 0; + return; + } + + if (esp_msg_buf[4 + esp_frame.dataLen] != ESP_PROTOC_TAIL) { + if (esp_msg_index >= sizeof(esp_msg_buf)) { + memset(esp_msg_buf, 0, sizeof(esp_msg_buf)); + esp_msg_index = 0; + } + return; + } + + esp_frame.data = &esp_msg_buf[4]; + switch (esp_frame.type) { + case ESP_TYPE_NET: + net_msg_handle(esp_frame.data, esp_frame.dataLen); + break; + case ESP_TYPE_GCODE: + gcode_msg_handle(esp_frame.data, esp_frame.dataLen); + break; + case ESP_TYPE_FILE_FIRST: + file_first_msg_handle(esp_frame.data, esp_frame.dataLen); + break; + case ESP_TYPE_FILE_FRAGMENT: + file_fragment_msg_handle(esp_frame.data, esp_frame.dataLen); + break; + case ESP_TYPE_WIFI_LIST: + wifi_list_msg_handle(esp_frame.data, esp_frame.dataLen); + break; + default: break; + } + + esp_msg_index = cut_msg_head(esp_msg_buf, esp_msg_index, esp_frame.dataLen + 5); + if (esp_msg_index > 0) { + if (charAtArray(esp_msg_buf, esp_msg_index, ESP_PROTOC_HEAD) == -1) { + memset(esp_msg_buf, 0, sizeof(esp_msg_buf)); + esp_msg_index = 0; + return; + } + + if ((charAtArray(esp_msg_buf, esp_msg_index, ESP_PROTOC_HEAD) != -1) && (charAtArray(esp_msg_buf, esp_msg_index, ESP_PROTOC_TAIL) != -1)) + loop_again = true; + } + } +} + +int32_t tick_net_time1, tick_net_time2; + +int storeRcvData(int32_t len) { + unsigned char tmpW = wifiDmaRcvFifo.write_cur; + if (len <= UDISKBUFLEN && wifiDmaRcvFifo.state[tmpW] == udisk_buf_empty) { + for (uint16_t i = 0; i < len; i++) + wifiDmaRcvFifo.bufferAddr[tmpW][i] = WIFISERIAL.read(); + wifiDmaRcvFifo.state[tmpW] = udisk_buf_full; + wifiDmaRcvFifo.write_cur = (tmpW + 1) % TRANS_RCV_FIFO_BLOCK_NUM; + return 1; + } + return 0; +} + +int32_t readWifiFifo(uint8_t *retBuf, uint32_t bufLen) { + unsigned char tmpR = wifiDmaRcvFifo.read_cur; + if (bufLen >= UDISKBUFLEN && wifiDmaRcvFifo.state[tmpR] == udisk_buf_full) { + memcpy(retBuf, (unsigned char *)wifiDmaRcvFifo.bufferAddr[tmpR], UDISKBUFLEN); + wifiDmaRcvFifo.state[tmpR] = udisk_buf_empty; + wifiDmaRcvFifo.read_cur = (tmpR + 1) % TRANS_RCV_FIFO_BLOCK_NUM; + return UDISKBUFLEN; + } + return 0; +} + +void stopEspTransfer() { + if (wifi_link_state == WIFI_TRANS_FILE) + wifi_link_state = WIFI_CONNECTED; + + TERN_(SDSUPPORT, card.closefile()); + + if (upload_result != 3) { + wifiTransError.flag = 1; + wifiTransError.start_tick = getWifiTick(); + card.removeFile((const char *)saveFilePath); + } + else { + } + wifi_delay(200); + WIFI_IO1_SET(); + //exchangeFlashMode(1); //change spi flash to use dma mode + esp_port_begin(1); + if (wifiTransError.flag != 0x1) WIFI_IO1_RESET(); +} + +void wifi_rcv_handle() { + int32_t len = 0; + uint8_t ucStr[(UART_RX_BUFFER_SIZE) + 1] = {0}; + int8_t getDataF = 0; + + if (wifi_link_state == WIFI_TRANS_FILE) { + #if 0 + if (WIFISERIAL.available() == UART_RX_BUFFER_SIZE) { + for (uint16_t i=0;i 0) { + esp_data_parser((char *)ucStr, len); + if (wifi_link_state == WIFI_CONNECTED) { + clear_cur_ui(); + lv_draw_dialog(DIALOG_TYPE_UPLOAD_FILE); + stopEspTransfer(); + } + getDataF = 1; + } + if (esp_state == TRANSFER_STORE) { + if (storeRcvData(UART_RX_BUFFER_SIZE)) { + esp_state = TRANSFERING; + //esp_dma_pre(); + if (wifiTransError.flag != 0x1) WIFI_IO1_RESET(); + } + else + WIFI_IO1_SET(); + } + } + else { + //len = readUsartFifo((SZ_USART_FIFO *)&WifiRxFifo, (int8_t *)ucStr, UART_RX_BUFFER_SIZE); + len = readWifiBuf((int8_t *)ucStr, UART_RX_BUFFER_SIZE); + if (len > 0) { + esp_data_parser((char *)ucStr, len); + + if (wifi_link_state == WIFI_TRANS_FILE) { + //exchangeFlashMode(0); //change spi flash not use dma mode + wifi_delay(10); + esp_port_begin(0); + wifi_delay(10); + tick_net_time1 = 0; + } + if (wifiTransError.flag != 0x1) WIFI_IO1_RESET(); + getDataF = 1; + } + if (need_ok_later && (queue.length < BUFSIZE)) { + need_ok_later = false; + send_to_wifi((char *)"ok\r\n", strlen("ok\r\n")); + } + } + + if (getDataF == 1) { + tick_net_time1 = getWifiTick(); + } + else { + tick_net_time2 = getWifiTick(); + + if (wifi_link_state == WIFI_TRANS_FILE) { + if ((tick_net_time1 != 0) && (getWifiTickDiff(tick_net_time1, tick_net_time2) > 4500)) { + wifi_link_state = WIFI_CONNECTED; + upload_result = 2; + clear_cur_ui(); + stopEspTransfer(); + lv_draw_dialog(DIALOG_TYPE_UPLOAD_FILE); + } + } + + if ((tick_net_time1 != 0) && (getWifiTickDiff(tick_net_time1, tick_net_time2) > 10000)) + wifi_link_state = WIFI_NOT_CONFIG; + + if ((tick_net_time1 != 0) && (getWifiTickDiff(tick_net_time1, tick_net_time2) > 120000)) { + wifi_link_state = WIFI_NOT_CONFIG; + wifi_reset(); + tick_net_time1 = getWifiTick(); + } + } + + if (wifiTransError.flag == 0x1) { + wifiTransError.now_tick = getWifiTick(); + if (getWifiTickDiff(wifiTransError.start_tick, wifiTransError.now_tick) > WAIT_ESP_TRANS_TIMEOUT_TICK) { + wifiTransError.flag = 0; + WIFI_IO1_RESET(); + } + } +} + +void wifi_looping() { + do { wifi_rcv_handle(); } while (wifi_link_state == WIFI_TRANS_FILE); +} + +void mks_esp_wifi_init() { + wifi_link_state = WIFI_NOT_CONFIG; + + SET_OUTPUT(WIFI_RESET_PIN); + WIFI_SET(); + SET_OUTPUT(WIFI_IO1_PIN); + SET_INPUT_PULLUP(WIFI_IO0_PIN); + WIFI_IO1_SET(); + + esp_state = TRANSFER_IDLE; + esp_port_begin(1); + + wifi_reset(); + + #if 0 + res = f_open(&esp_upload.uploadFile, ESP_FIRMWARE_FILE, FA_OPEN_EXISTING | FA_READ); + + if (res == FR_OK) { + f_close(&esp_upload.uploadFile); + + wifi_delay(2000); + + if (usartFifoAvailable((SZ_USART_FIFO *)&WifiRxFifo) < 20) { + return; + } + + clear_cur_ui(); + + draw_dialog(DIALOG_TYPE_UPDATE_ESP_FIRMARE); + + if (wifi_upload(0) >= 0) { + + f_unlink("1:/MKS_WIFI_CUR"); + f_rename(ESP_FIRMWARE_FILE,"/MKS_WIFI_CUR"); + } + draw_return_ui(); + + update_flag = 1; + } + if (update_flag == 0) { + res = f_open(&esp_upload.uploadFile, ESP_WEB_FIRMWARE_FILE, FA_OPEN_EXISTING | FA_READ); + + if (res == FR_OK) { + f_close(&esp_upload.uploadFile); + + wifi_delay(2000); + + if (usartFifoAvailable((SZ_USART_FIFO *)&WifiRxFifo) < 20) { + return; + } + + clear_cur_ui(); + + draw_dialog(DIALOG_TYPE_UPDATE_ESP_FIRMARE); + if (wifi_upload(1) >= 0) { + + f_unlink("1:/MKS_WIFI_CUR"); + f_rename(ESP_WEB_FIRMWARE_FILE,"/MKS_WIFI_CUR"); + } + draw_return_ui(); + update_flag = 1; + } + + } + if (update_flag == 0) { + res = f_open(&esp_upload.uploadFile, ESP_WEB_FILE, FA_OPEN_EXISTING | FA_READ); + if (res == FR_OK) { + f_close(&esp_upload.uploadFile); + + wifi_delay(2000); + + if (usartFifoAvailable((SZ_USART_FIFO *)&WifiRxFifo) < 20) { + return; + } + + clear_cur_ui(); + + draw_dialog(DIALOG_TYPE_UPDATE_ESP_DATA); + + if (wifi_upload(2) >= 0) { + + f_unlink("1:/MKS_WEB_CONTROL_CUR"); + f_rename(ESP_WEB_FILE,"/MKS_WEB_CONTROL_CUR"); + } + draw_return_ui(); + } + } + #endif + wifiPara.decodeType = WIFI_DECODE_TYPE; + wifiPara.baud = 115200; + wifi_link_state = WIFI_NOT_CONFIG; +} + +#define BUF_INC_POINTER(p) ((p + 1 == UART_FIFO_BUFFER_SIZE) ? 0 : (p + 1)) + +int usartFifoAvailable(SZ_USART_FIFO *fifo) { + int diff = fifo->uart_write_point - fifo->uart_read_point; + if (diff < 0) diff += UART_FIFO_BUFFER_SIZE; + return diff; +} + +int readUsartFifo(SZ_USART_FIFO *fifo, int8_t *buf, int32_t len) { + int i = 0 ; + while (i < len && fifo->uart_read_point != fifo->uart_write_point) { + buf[i++] = fifo->uartTxBuffer[fifo->uart_read_point]; + fifo->uart_read_point = BUF_INC_POINTER(fifo->uart_read_point); + } + return i; +} + +int writeUsartFifo(SZ_USART_FIFO *fifo, int8_t *buf, int32_t len) { + if (buf == 0 || len <= 0) return -1; + + int i = 0 ; + while (i < len && fifo->uart_read_point != BUF_INC_POINTER(fifo->uart_write_point)) { + fifo->uartTxBuffer[fifo->uart_write_point] = buf[i++]; + fifo->uart_write_point = BUF_INC_POINTER(fifo->uart_write_point); + } + return i; +} + +void get_wifi_commands() { + static char wifi_line_buffer[MAX_CMD_SIZE]; + static bool wifi_comment_mode = false; + static int wifi_read_count = 0; + + if (espGcodeFifo.wait_tick > 5) { + while ((queue.length < BUFSIZE) && (espGcodeFifo.r != espGcodeFifo.w)) { + + espGcodeFifo.wait_tick = 0; + + char wifi_char = espGcodeFifo.Buffer[espGcodeFifo.r]; + + espGcodeFifo.r = (espGcodeFifo.r + 1) % WIFI_GCODE_BUFFER_SIZE; + + /** + * If the character ends the line + */ + if (wifi_char == '\n' || wifi_char == '\r') { + + wifi_comment_mode = false; // end of line == end of comment + + if (!wifi_read_count) continue; // skip empty lines + + wifi_line_buffer[wifi_read_count] = 0; // terminate string + wifi_read_count = 0; //reset buffer + + char* command = wifi_line_buffer; + while (*command == ' ') command++; // skip any leading spaces + + // Movement commands alert when stopped + if (IsStopped()) { + char* gpos = strchr(command, 'G'); + if (gpos) { + switch (strtol(gpos + 1, nullptr, 10)) { + case 0 ... 1: + #if ENABLED(ARC_SUPPORT) + case 2 ... 3: + #endif + #if ENABLED(BEZIER_CURVE_SUPPORT) + case 5: + #endif + SERIAL_ECHOLNPGM(STR_ERR_STOPPED); + LCD_MESSAGEPGM(MSG_STOPPED); + break; + } + } + } + + #if DISABLED(EMERGENCY_PARSER) + // Process critical commands early + if (strcmp(command, "M108") == 0) { + wait_for_heatup = false; + TERN_(HAS_LCD_MENU, wait_for_user = false); + } + if (strcmp(command, "M112") == 0) kill(M112_KILL_STR, nullptr, true); + if (strcmp(command, "M410") == 0) quickstop_stepper(); + #endif + + // Add the command to the queue + queue.enqueue_one_P(wifi_line_buffer); + } + else if (wifi_read_count >= MAX_CMD_SIZE - 1) { + + } + else { // it's not a newline, carriage return or escape char + if (wifi_char == ';') wifi_comment_mode = true; + if (!wifi_comment_mode) wifi_line_buffer[wifi_read_count++] = wifi_char; + } + } + }// queue has space, serial has data + else { + espGcodeFifo.wait_tick++; + } +} + +int readWifiBuf(int8_t *buf, int32_t len) { + int i = 0; + while (i < len && WIFISERIAL.available()) + buf[i++] = WIFISERIAL.read(); + return i; +} + +#endif // USE_WIFI_FUNCTION +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/wifi_module.h b/Marlin/src/lcd/extui/lib/mks_ui/wifi_module.h new file mode 100644 index 0000000000..0b402a3adb --- /dev/null +++ b/Marlin/src/lcd/extui/lib/mks_ui/wifi_module.h @@ -0,0 +1,202 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#ifdef __cplusplus + extern "C" { /* C-declarations for C++ */ +#endif + +#include "../../inc/MarlinConfigPre.h" + +#include +#include +#include + +#define UART_RX_BUFFER_SIZE 1024 +#define UART_FIFO_BUFFER_SIZE 1024 + +#define ESP_WIFI 0x02 + +#define AP_MODEL 0x01 +#define STA_MODEL 0x02 + +#define WIFI_DECODE_TYPE 1 + +#define IP_DHCP_FLAG 1 + +#define WIFI_AP_NAME "TP-LINK_MKS" +#define WIFI_KEY_CODE "makerbase" + +#define IP_ADDR "192.168.3.100" +#define IP_MASK "255.255.255.0" +#define IP_GATE "192.168.3.1" +#define IP_DNS "192.168.3.1" + +#define AP_IP_DHCP_FLAG 1 +#define AP_IP_ADDR "192.168.3.100" +#define AP_IP_MASK "255.255.255.0" +#define AP_IP_GATE "192.168.3.1" +#define AP_IP_DNS "192.168.3.1" +#define IP_START_IP "192.168.3.1" +#define IP_END_IP "192.168.3.255" + +#define UDISKBUFLEN 1024 + +typedef enum{ + udisk_buf_empty = 0, + udisk_buf_full, +} UDISK_DATA_BUFFER_STATE; + +#define TRANS_RCV_FIFO_BLOCK_NUM 8 + +typedef struct { + unsigned char *bufferAddr[TRANS_RCV_FIFO_BLOCK_NUM]; + unsigned char *p; + UDISK_DATA_BUFFER_STATE state[TRANS_RCV_FIFO_BLOCK_NUM]; + unsigned char read_cur; + unsigned char write_cur; +} WIFI_DMA_RCV_FIFO; + +typedef struct { + uint8_t flag; // 0x0: no error; 0x01: error + uint32_t start_tick; //error start time + uint32_t now_tick; +} WIFI_TRANS_ERROR; + +extern volatile WIFI_TRANS_ERROR wifiTransError; + +typedef struct { + char ap_name[32]; //wifi-name + char keyCode[64]; //wifi password + int decodeType; + int baud; + int mode; +} WIFI_PARA; + +typedef struct { + char state; + char hostUrl[96]; + int port; + char id[21]; +} CLOUD_PARA; + +typedef struct { + char dhcp_flag; + char ip_addr[16]; + char mask[16]; + char gate[16]; + char dns[16]; + + char dhcpd_flag; + char dhcpd_ip[16]; + char dhcpd_mask[16]; + char dhcpd_gate[16]; + char dhcpd_dns[16]; + char start_ip_addr[16]; + char end_ip_addr[16]; +} IP_PARA; + +typedef enum { + WIFI_NOT_CONFIG, + WIFI_CONFIG_MODE, + WIFI_CONFIG_DHCP, + WIFI_CONFIG_AP, + WIFI_CONFIG_IP_INF, + WIFI_CONFIG_DNS, + WIFI_CONFIG_TCP, + WIFI_CONFIG_SERVER, + WIFI_CONFIG_REMOTE_PORT, + WIFI_CONFIG_BAUD, + WIFI_CONFIG_COMMINT, + WIFI_CONFIG_OK, + WIFI_GET_IP_OK, + WIFI_RECONN, + WIFI_CONNECTED, + WIFI_WAIT_TRANS_START, + WIFI_TRANS_FILE, + WIFI_CONFIG_DHCPD, + WIFI_COFIG_DHCPD_IP, + WIFI_COFIG_DHCPD_DNS, + WIFI_EXCEPTION, +} WIFI_STATE; + +typedef enum { + TRANSFER_IDLE, + TRANSFERING, + TRANSFER_STORE, +} TRANSFER_STATE; +extern volatile TRANSFER_STATE esp_state; + +typedef struct { + char buf[20][80]; + int rd_index; + int wt_index; +} QUEUE; + +typedef enum { + WIFI_PARA_SET, // 0x0:net parameter + WIFI_PRINT_INF, // 0x1:print message + WIFI_TRANS_INF, // 0x2:Pass through information + WIFI_EXCEP_INF, // 0x3:Exception information + WIFI_CLOUD_CFG, // 0x4:cloud config + WIFI_CLOUD_UNBIND, // 0x5:Unbind ID +} WIFI_RET_TYPE; + +typedef struct { + uint32_t uart_read_point; + uint32_t uart_write_point; + uint8_t uartTxBuffer[UART_FIFO_BUFFER_SIZE]; +} SZ_USART_FIFO; + +#define WIFI_GCODE_BUFFER_LEAST_SIZE 96 +#define WIFI_GCODE_BUFFER_SIZE (WIFI_GCODE_BUFFER_LEAST_SIZE * 3) +typedef struct { + uint8_t wait_tick; + uint8_t Buffer[WIFI_GCODE_BUFFER_SIZE]; + uint32_t r; + uint32_t w; +} WIFI_GCODE_BUFFER; + +extern volatile WIFI_STATE wifi_link_state; +extern WIFI_PARA wifiPara; +extern IP_PARA ipPara; +extern CLOUD_PARA cloud_para; + +extern WIFI_GCODE_BUFFER espGcodeFifo; + +extern uint32_t getWifiTick(); +extern uint32_t getWifiTickDiff(int32_t lastTick, int32_t curTick); + +extern void mks_esp_wifi_init(); +extern int cfg_cloud_flag; +extern int send_to_wifi(char *buf, int len); +extern void wifi_looping(); +extern int raw_send_to_wifi(char *buf, int len); +extern int package_to_wifi(WIFI_RET_TYPE type,char *buf, int len); +extern void get_wifi_list_command_send(); +extern void get_wifi_commands(); +extern int readWifiBuf(int8_t *buf, int32_t len); +extern int storeRcvData(int32_t len); + +#ifdef __cplusplus + } /* C-declarations for C++ */ +#endif diff --git a/Marlin/src/lcd/extui/lib/mks_ui/wifi_upload.cpp b/Marlin/src/lcd/extui/lib/mks_ui/wifi_upload.cpp new file mode 100644 index 0000000000..132838c8a9 --- /dev/null +++ b/Marlin/src/lcd/extui/lib/mks_ui/wifi_upload.cpp @@ -0,0 +1,847 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#include "../../../../inc/MarlinConfigPre.h" + +#if HAS_TFT_LVGL_UI + +#include "draw_ui.h" +#include "wifi_module.h" +#include "wifi_upload.h" + +#include "../../../../MarlinCore.h" + +#define WIFI_SET() WRITE(WIFI_RESET_PIN, HIGH); +#define WIFI_RESET() WRITE(WIFI_RESET_PIN, LOW); +#define WIFI_IO1_SET() WRITE(WIFI_IO1_PIN, HIGH); +#define WIFI_IO1_RESET() WRITE(WIFI_IO1_PIN, LOW); + +extern SZ_USART_FIFO WifiRxFifo; + +extern int readUsartFifo(SZ_USART_FIFO *fifo, int8_t *buf, int32_t len); +extern int writeUsartFifo(SZ_USART_FIFO * fifo, int8_t * buf, int32_t len); +extern void esp_port_begin(uint8_t interrupt); +extern int usartFifoAvailable(SZ_USART_FIFO *fifo); +extern void wifi_delay(int n); + +#define ARRAY_SIZE(a) sizeof(a) / sizeof((a)[0]) + +//typedef signed char bool; + +// ESP8266 command codes +const uint8_t ESP_FLASH_BEGIN = 0x02; +const uint8_t ESP_FLASH_DATA = 0x03; +const uint8_t ESP_FLASH_END = 0x04; +const uint8_t ESP_MEM_BEGIN = 0x05; +const uint8_t ESP_MEM_END = 0x06; +const uint8_t ESP_MEM_DATA = 0x07; +const uint8_t ESP_SYNC = 0x08; +const uint8_t ESP_WRITE_REG = 0x09; +const uint8_t ESP_READ_REG = 0x0a; + +// MAC address storage locations +const uint32_t ESP_OTP_MAC0 = 0x3ff00050; +const uint32_t ESP_OTP_MAC1 = 0x3ff00054; +const uint32_t ESP_OTP_MAC2 = 0x3ff00058; +const uint32_t ESP_OTP_MAC3 = 0x3ff0005c; + +const size_t EspFlashBlockSize = 0x0400; // 1K byte blocks + +const uint8_t ESP_IMAGE_MAGIC = 0xe9; +const uint8_t ESP_CHECKSUM_MAGIC = 0xef; + +const uint32_t ESP_ERASE_CHIP_ADDR = 0x40004984; // &SPIEraseChip +const uint32_t ESP_SEND_PACKET_ADDR = 0x40003c80; // &send_packet +const uint32_t ESP_SPI_READ_ADDR = 0x40004b1c; // &SPIRead +const uint32_t ESP_UNKNOWN_ADDR = 0x40001121; // not used +const uint32_t ESP_USER_DATA_RAM_ADDR = 0x3ffe8000; // &user data ram +const uint32_t ESP_IRAM_ADDR = 0x40100000; // instruction RAM +const uint32_t ESP_FLASH_ADDR = 0x40200000; // address of start of Flash +//const uint32_t ESP_FLASH_READ_STUB_BEGIN = IRAM_ADDR + 0x18; + +UPLOAD_STRUCT esp_upload; + +static const unsigned int retriesPerReset = 3; +static const uint32_t connectAttemptInterval = 50; +static const unsigned int percentToReportIncrement = 5; // how often we report % complete +static const uint32_t defaultTimeout = 500; +static const uint32_t eraseTimeout = 15000; +static const uint32_t blockWriteTimeout = 200; +static const uint32_t blockWriteInterval = 15; // 15ms is long enough, 10ms is mostly too short + +// Messages corresponding to result codes, should make sense when followed by " error" +const char *resultMessages[] = { + "no", + "timeout", + "comm write", + "connect", + "bad reply", + "file read", + "empty file", + "response header", + "slip frame", + "slip state", + "slip data" +}; + +// A note on baud rates. +// The ESP8266 supports 921600, 460800, 230400, 115200, 74880 and some lower baud rates. +// 921600b is not reliable because even though it sometimes succeeds in connecting, we get a bad response during uploading after a few blocks. +// Probably our UART ISR cannot receive bytes fast enough, perhaps because of the latency of the system tick ISR. +// 460800b doesn't always manage to connect, but if it does then uploading appears to be reliable. +// 230400b always manages to connect. +static const uint32_t uploadBaudRates[] = { 460800, 230400, 115200, 74880 }; + + + +signed char IsReady() { + return esp_upload.state == upload_idle; +} + + + + + +void uploadPort_write(const uint8_t *buf, size_t len) { + #if 0 + int i; + + for(i = 0; i < len; i++) { + while (USART_GetFlagStatus(USART1, USART_FLAG_TC) == RESET); + + USART_SendData(USART1, *(buf + i)); + } + #endif +} + +char uploadPort_read() { + uint8_t retChar; + if (readUsartFifo(&WifiRxFifo, (int8_t *)&retChar, 1) == 1) + return retChar; + else + return 0; + +} + +int uploadPort_available() { + return usartFifoAvailable(&WifiRxFifo); +} + + +void uploadPort_begin() { + esp_port_begin(1); +} + +void uploadPort_close() { + + //WIFI_COM.end(); + //WIFI_COM.begin(115200, true); + + esp_port_begin(0); + +} + + +void flushInput() { + while (uploadPort_available() != 0) { + (void)uploadPort_read(); + //IWDG_ReloadCounter(); + } +} + +// Extract 1-4 bytes of a value in little-endian order from a buffer beginning at a specified offset +uint32_t getData(unsigned byteCnt, const uint8_t *buf, int ofst) { + uint32_t val = 0; + + if (buf && byteCnt) { + unsigned int shiftCnt = 0; + if (byteCnt > 4) + byteCnt = 4; + do{ + val |= (uint32_t)buf[ofst++] << shiftCnt; + shiftCnt += 8; + } while (--byteCnt); + } + return(val); +} + +// Put 1-4 bytes of a value in little-endian order into a buffer beginning at a specified offset. +void putData(uint32_t val, unsigned byteCnt, uint8_t *buf, int ofst) { + if (buf && byteCnt) { + if (byteCnt > 4) { + byteCnt = 4; + } + do { + buf[ofst++] = (uint8_t)(val & 0xff); + val >>= 8; + } while (--byteCnt); + } +} + +// Read a byte optionally performing SLIP decoding. The return values are: +// +// 2 - an escaped byte was read successfully +// 1 - a non-escaped byte was read successfully +// 0 - no data was available +// -1 - the value 0xc0 was encountered (shouldn't happen) +// -2 - a SLIP escape byte was found but the following byte wasn't available +// -3 - a SLIP escape byte was followed by an invalid byte +int ReadByte(uint8_t *data, signed char slipDecode) { + if (uploadPort_available() == 0) { + return(0); + } + + // at least one byte is available + *data = uploadPort_read(); + if (!slipDecode) { + return(1); + } + + if (*data == 0xc0) { + // this shouldn't happen + return(-1); + } + + // if not the SLIP escape, we're done + if (*data != 0xdb) { + return(1); + } + + // SLIP escape, check availability of subsequent byte + if (uploadPort_available() == 0) { + return(-2); + } + + // process the escaped byte + *data = uploadPort_read(); + if (*data == 0xdc) { + *data = 0xc0; + return(2); + } + + if (*data == 0xdd) { + *data = 0xdb; + return(2); + } + // invalid + return(-3); +} +// When we write a sync packet, there must be no gaps between most of the characters. +// So use this function, which does a block write to the UART buffer in the latest CoreNG. +void _writePacketRaw(const uint8_t *buf, size_t len) { + uploadPort_write(buf, len); +} + +// Write a byte to the serial port optionally SLIP encoding. Return the number of bytes actually written. +void WriteByteRaw(uint8_t b) { + uploadPort_write((const uint8_t *)&b, 1); +} + +// Write a byte to the serial port optionally SLIP encoding. Return the number of bytes actually written. +void WriteByteSlip(uint8_t b) { + if (b == 0xC0) { + WriteByteRaw(0xDB); + WriteByteRaw(0xDC); + } + else if (b == 0xDB) { + WriteByteRaw(0xDB); + WriteByteRaw(0xDD); + } + else { + uploadPort_write((const uint8_t *)&b, 1); + } +} + +// Wait for a data packet to be returned. If the body of the packet is +// non-zero length, return an allocated buffer indirectly containing the +// data and return the data length. Note that if the pointer for returning +// the data buffer is NULL, the response is expected to be two bytes of zero. +// +// If an error occurs, return a negative value. Otherwise, return the number +// of bytes in the response (or zero if the response was not the standard "two bytes of zero"). +EspUploadResult readPacket(uint8_t op, uint32_t *valp, size_t *bodyLen, uint32_t msTimeout) { + typedef enum { + begin = 0, + header, + body, + end, + done + } PacketState; + + uint8_t resp, opRet; + + const size_t headerLength = 8; + + uint32_t startTime = getWifiTick(); + uint8_t hdr[headerLength]; + uint16_t hdrIdx = 0; + + uint16_t bodyIdx = 0; + uint8_t respBuf[2]; + + // wait for the response + uint16_t needBytes = 1; + + PacketState state = begin; + + *bodyLen = 0; + + + while (state != done) { + uint8_t c; + EspUploadResult stat; + + //IWDG_ReloadCounter(); + + if (getWifiTickDiff(startTime, getWifiTick()) > msTimeout) { + return(timeout); + } + + if (uploadPort_available() < needBytes) { + // insufficient data available + // preferably, return to Spin() here + continue; + } + + // sufficient bytes have been received for the current state, process them + switch(state) { + case begin: // expecting frame start + c = uploadPort_read(); + if (c != (uint8_t)0xc0) { + break; + } + state = header; + needBytes = 2; + + break; + case end: // expecting frame end + c = uploadPort_read(); + if (c != (uint8_t)0xc0) { + return slipFrame; + } + state = done; + + break; + + case header: // reading an 8-byte header + case body: // reading the response body + { + int rslt; + // retrieve a byte with SLIP decoding + rslt = ReadByte(&c, 1); + if (rslt != 1 && rslt != 2) { + // some error occurred + stat = (rslt == 0 || rslt == -2) ? slipData : slipFrame; + return stat; + } + else if (state == header) { + //store the header byte + hdr[hdrIdx++] = c; + if (hdrIdx >= headerLength) { + // get the body length, prepare a buffer for it + *bodyLen = (uint16_t)getData(2, hdr, 2); + + // extract the value, if requested + if (valp != 0) { + *valp = getData(4, hdr, 4); + } + + if (*bodyLen != 0) { + state = body; + } + else { + needBytes = 1; + state = end; + } + } + } + else { + // Store the response body byte, check for completion + if (bodyIdx < ARRAY_SIZE(respBuf)) { + respBuf[bodyIdx] = c; + } + ++bodyIdx; + if (bodyIdx >= *bodyLen) { + needBytes = 1; + state = end; + } + } + } + break; + + default: // this shouldn't happen + return slipState; + } + } + + // Extract elements from the header + resp = (uint8_t)getData(1, hdr, 0); + opRet = (uint8_t)getData(1, hdr, 1); + // Sync packets often provoke a response with a zero opcode instead of ESP_SYNC + if (resp != 0x01 || opRet != op) { +//debug//printf("resp %02x %02x\n", resp, opRet); + return respHeader; + } + + return success; +} + +// Send a block of data performing SLIP encoding of the content. +void _writePacket(const uint8_t *data, size_t len) { + unsigned char outBuf[2048] = {0}; + unsigned int outIndex = 0; + while (len != 0) { + if (*data == 0xC0) { + outBuf[outIndex++] = 0xDB; + outBuf[outIndex++] = 0xDC; + } + else if (*data == 0xDB) { + outBuf[outIndex++] = 0xDB; + outBuf[outIndex++] = 0xDD; + } + else { + outBuf[outIndex++] = *data; + + } + data++; + --len; + } + uploadPort_write((const uint8_t *)outBuf, outIndex); +} + +// Send a packet to the serial port while performing SLIP framing. The packet data comprises a header and an optional data block. +// A SLIP packet begins and ends with 0xc0. The data encapsulated has the bytes +// 0xc0 and 0xdb replaced by the two-byte sequences {0xdb, 0xdc} and {0xdb, 0xdd} respectively. + +void writePacket(const uint8_t *hdr, size_t hdrLen, const uint8_t *data, size_t dataLen) { + + WriteByteRaw(0xc0); // send the packet start character + _writePacket(hdr, hdrLen); // send the header + _writePacket(data, dataLen); // send the data block + WriteByteRaw(0xc0); // send the packet end character +} + +// Send a packet to the serial port while performing SLIP framing. The packet data comprises a header and an optional data block. +// This is like writePacket except that it does a fast block write for both the header and the main data with no SLIP encoding. Used to send sync commands. +void writePacketRaw(const uint8_t *hdr, size_t hdrLen, const uint8_t *data, size_t dataLen) { + WriteByteRaw(0xc0); // send the packet start character + _writePacketRaw(hdr, hdrLen); // send the header + _writePacketRaw(data, dataLen); // send the data block in raw mode + WriteByteRaw(0xc0); // send the packet end character +} + +// Send a command to the attached device together with the supplied data, if any. +// The data is supplied via a list of one or more segments. +void sendCommand(uint8_t op, uint32_t checkVal, const uint8_t *data, size_t dataLen) { + // populate the header + uint8_t hdr[8]; + putData(0, 1, hdr, 0); + putData(op, 1, hdr, 1); + putData(dataLen, 2, hdr, 2); + putData(checkVal, 4, hdr, 4); + + // send the packet + //flushInput(); + if (op == ESP_SYNC) { + writePacketRaw(hdr, sizeof(hdr), data, dataLen); + } + else { + writePacket(hdr, sizeof(hdr), data, dataLen); + } +} + +// Send a command to the attached device together with the supplied data, if any, and get the response +EspUploadResult doCommand(uint8_t op, const uint8_t *data, size_t dataLen, uint32_t checkVal, uint32_t *valp, uint32_t msTimeout) { + size_t bodyLen; + EspUploadResult stat; + + sendCommand(op, checkVal, data, dataLen); + + stat = readPacket(op, valp, &bodyLen, msTimeout); + if (stat == success && bodyLen != 2) { + stat = badReply; + } + + return stat; +} + +// Send a synchronising packet to the serial port in an attempt to induce +// the ESP8266 to auto-baud lock on the baud rate. +EspUploadResult Sync(uint16_t timeout) { + uint8_t buf[36]; + EspUploadResult stat; + int i ; + + // compose the data for the sync attempt + memset(buf, 0x55, sizeof(buf)); + buf[0] = 0x07; + buf[1] = 0x07; + buf[2] = 0x12; + buf[3] = 0x20; + + stat = doCommand(ESP_SYNC, buf, sizeof(buf), 0, 0, timeout); + + // If we got a response other than sync, discard it and wait for a sync response. This happens at higher baud rates. + for (i = 0; i < 10 && stat == respHeader; ++i) { + size_t bodyLen; + stat = readPacket(ESP_SYNC, 0, &bodyLen, timeout); + } + + if (stat == success) { + // Read and discard additional replies + for (;;) { + size_t bodyLen; + EspUploadResult rc = readPacket(ESP_SYNC, 0, &bodyLen, defaultTimeout); + if (rc != success || bodyLen != 2) { + break; + } + } + } + //DEBUG + //else debug//printf("stat=%d\n", (int)stat); + return stat; +} + +// Send a command to the device to begin the Flash process. +EspUploadResult flashBegin(uint32_t addr, uint32_t size) { + // determine the number of blocks represented by the size + uint32_t blkCnt; + uint8_t buf[16]; + uint32_t timeout; + + blkCnt = (size + EspFlashBlockSize - 1) / EspFlashBlockSize; + + // ensure that the address is on a block boundary + addr &= ~(EspFlashBlockSize - 1); + + // begin the Flash process + putData(size, 4, buf, 0); + putData(blkCnt, 4, buf, 4); + putData(EspFlashBlockSize, 4, buf, 8); + putData(addr, 4, buf, 12); + + timeout = (size != 0) ? eraseTimeout : defaultTimeout; + return doCommand(ESP_FLASH_BEGIN, buf, sizeof(buf), 0, 0, timeout); +} + +// Send a command to the device to terminate the Flash process +EspUploadResult flashFinish(signed char reboot) { + uint8_t buf[4]; + putData(reboot ? 0 : 1, 4, buf, 0); + return doCommand(ESP_FLASH_END, buf, sizeof(buf), 0, 0, defaultTimeout); +} + +// Compute the checksum of a block of data +uint16_t checksum(const uint8_t *data, uint16_t dataLen, uint16_t cksum) { + if (data != NULL) { + while (dataLen--) { + cksum ^= (uint16_t)*data++; + } + } + return(cksum); +} + +EspUploadResult flashWriteBlock(uint16_t flashParmVal, uint16_t flashParmMask) { + #if 0 + const uint32_t blkSize = EspFlashBlockSize; + int i; + + // Allocate a data buffer for the combined header and block data + const uint16_t hdrOfst = 0; + const uint16_t dataOfst = 16; + const uint16_t blkBufSize = dataOfst + blkSize; + uint32_t blkBuf32[blkBufSize/4]; + uint8_t * const blkBuf = (uint8_t*)(blkBuf32); + uint32_t cnt; + uint16_t cksum; + EspUploadResult stat; + + // Prepare the header for the block + putData(blkSize, 4, blkBuf, hdrOfst + 0); + putData(esp_upload.uploadBlockNumber, 4, blkBuf, hdrOfst + 4); + putData(0, 4, blkBuf, hdrOfst + 8); + putData(0, 4, blkBuf, hdrOfst + 12); + + // Get the data for the block + f_read(&esp_upload.uploadFile, blkBuf + dataOfst, blkSize, &cnt );//->Read(reinterpret_cast(blkBuf + dataOfst), blkSize); + if (cnt != blkSize) { + if (f_tell(&esp_upload.uploadFile) == esp_upload.fileSize) { + // partial last block, fill the remainder + memset(blkBuf + dataOfst + cnt, 0xff, blkSize - cnt); + } + else { + return fileRead; + } + } + + // Patch the flash parameters into the first block if it is loaded at address 0 + if (esp_upload.uploadBlockNumber == 0 && esp_upload.uploadAddress == 0 && blkBuf[dataOfst] == ESP_IMAGE_MAGIC && flashParmMask != 0) { + // update the Flash parameters + uint32_t flashParm = getData(2, blkBuf + dataOfst + 2, 0) & ~(uint32_t)flashParmMask; + putData(flashParm | flashParmVal, 2, blkBuf + dataOfst + 2, 0); + } + + // Calculate the block checksum + cksum = checksum(blkBuf + dataOfst, blkSize, ESP_CHECKSUM_MAGIC); + + for (i = 0; i < 3; i++) { + if ((stat = doCommand(ESP_FLASH_DATA, blkBuf, blkBufSize, cksum, 0, blockWriteTimeout)) == success) { + break; + } + } + + //printf("Upload %d\%\n", ftell(&esp_upload.uploadFile) * 100 / esp_upload.fileSize); + + return stat; + #endif +} + +void upload_spin() { + #if 0 + switch (esp_upload.state) { + case resetting: + + if (esp_upload.connectAttemptNumber == 9) { + // Time to give up + //Network::ResetWiFi(); + esp_upload.uploadResult = connected; + esp_upload.state = done; + } + else{ + + // Reset the serial port at the new baud rate. Also reset the ESP8266. + // const uint32_t baud = uploadBaudRates[esp_upload.connectAttemptNumber/esp_upload.retriesPerBaudRate]; + if (esp_upload.connectAttemptNumber % esp_upload.retriesPerBaudRate == 0) { + } + // uploadPort.begin(baud); + // uploadPort_close(); + + + uploadPort_begin(); + + wifi_delay(2000); + + flushInput(); + + esp_upload.lastAttemptTime = esp_upload.lastResetTime = getWifiTick(); + esp_upload.state = connecting; + } + + break; + + case connecting: + if ((getWifiTickDiff(esp_upload.lastAttemptTime, getWifiTick()) >= connectAttemptInterval) && (getWifiTickDiff(esp_upload.lastResetTime, getWifiTick()) >= 500)) { + // Attempt to establish a connection to the ESP8266. + EspUploadResult res = Sync(5000); + esp_upload.lastAttemptTime = getWifiTick(); + if (res == success) { + // Successful connection +// //MessageF(" success on attempt %d\n", (connectAttemptNumber % retriesPerBaudRate) + 1); + //printf("connect success\n"); + esp_upload.state = erasing; + } + else { + // This attempt failed + esp_upload.connectAttemptNumber++; + if (esp_upload.connectAttemptNumber % retriesPerReset == 0) { + esp_upload.state = resetting; // try a reset and a lower baud rate + } + } + } + break; + + case erasing: + if (getWifiTickDiff(esp_upload.lastAttemptTime, getWifiTick()) >= blockWriteInterval) { + uint32_t eraseSize; + const uint32_t sectorsPerBlock = 16; + const uint32_t sectorSize = 4096; + const uint32_t numSectors = (esp_upload.fileSize + sectorSize - 1)/sectorSize; + const uint32_t startSector = esp_upload.uploadAddress/sectorSize; + uint32_t headSectors = sectorsPerBlock - (startSector % sectorsPerBlock); + + if (numSectors < headSectors) { + headSectors = numSectors; + } + eraseSize = (numSectors < 2 * headSectors) + ? (numSectors + 1) / 2 * sectorSize + : (numSectors - headSectors) * sectorSize; + + //MessageF("Erasing %u bytes...\n", fileSize); + esp_upload.uploadResult = flashBegin(esp_upload.uploadAddress, eraseSize); + if (esp_upload.uploadResult == success) { + //MessageF("Uploading file...\n"); + esp_upload.uploadBlockNumber = 0; + esp_upload.uploadNextPercentToReport = percentToReportIncrement; + esp_upload.lastAttemptTime = getWifiTick(); + esp_upload.state = uploading; + } + else { + //MessageF("Erase failed\n"); + esp_upload.state = done; + } + } + break; + + case uploading: + // The ESP needs several milliseconds to recover from one packet before it will accept another + if (getWifiTickDiff(esp_upload.lastAttemptTime, getWifiTick()) >= 15) { + unsigned int percentComplete; + const uint32_t blkCnt = (esp_upload.fileSize + EspFlashBlockSize - 1) / EspFlashBlockSize; + if (esp_upload.uploadBlockNumber < blkCnt) { + esp_upload.uploadResult = flashWriteBlock(0, 0); + esp_upload.lastAttemptTime = getWifiTick(); + if (esp_upload.uploadResult != success) { + //MessageF("Flash block upload failed\n"); + esp_upload.state = done; + } + percentComplete = (100 * esp_upload.uploadBlockNumber)/blkCnt; + ++esp_upload.uploadBlockNumber; + if (percentComplete >= esp_upload.uploadNextPercentToReport) { + //MessageF("%u%% complete\n", percentComplete); + esp_upload.uploadNextPercentToReport += percentToReportIncrement; + } + } + else { + esp_upload.state = done; + } + } + break; + + case done: + f_close(&esp_upload.uploadFile); + //uploadPort.end(); + //uploadPort_close(); + + //WIFI_COM.begin(115200, true); + //wifi_init(); + + if (esp_upload.uploadResult == success) { + //printf("upload successfully\n"); + } + else { + //printf("upload failed\n"); + } + esp_upload.state = upload_idle;//idle; + break; + + default: + break; + } + #endif +} + +// Try to upload the given file at the given address +void SendUpdateFile(const char *file, uint32_t address) { + #if 0 + FRESULT res = f_open(&esp_upload.uploadFile, file, FA_OPEN_EXISTING | FA_READ); + + if (res != FR_OK) return; + + esp_upload.fileSize = f_size(&esp_upload.uploadFile); + if (esp_upload.fileSize == 0) { + f_close(&esp_upload.uploadFile); + return; + } + f_lseek(&esp_upload.uploadFile, 0); + + esp_upload.uploadAddress = address; + esp_upload.connectAttemptNumber = 0; + esp_upload.state = resetting; + #endif +} + +static const uint32_t FirmwareAddress = 0x00000000, WebFilesAddress = 0x00100000; + +void ResetWiFiForUpload(int begin_or_end) { + #if 0 + uint32_t start, now; + + GPIO_InitTypeDef GPIO_InitStructure; + + #if V1_0_V1_1 + GPIO_InitStructure.Speed = GPIO_SPEED_FREQ_HIGH; + GPIO_InitStructure.Pin = GPIO_Pin_8; + GPIO_InitStructure.Mode = GPIO_MODE_OUTPUT_PP; + HAL_GPIO_Init(GPIOA, &GPIO_InitStructure); + #else + GPIO_InitStructure.Speed = GPIO_SPEED_FREQ_LOW; + GPIO_InitStructure.Pin = GPIO_Pin_13; + GPIO_InitStructure.Mode = GPIO_MODE_OUTPUT_PP; + HAL_GPIO_Init(GPIOC, &GPIO_InitStructure); + #endif + start = getWifiTick(); + now = start; + + if (begin_or_end == 0) { + #if V1_0_V1_1 + HAL_GPIO_WritePin(GPIOA,GPIO_Pin_8,GPIO_PIN_RESET); //update mode + #else + HAL_GPIO_WritePin(GPIOC,GPIO_Pin_13,GPIO_PIN_RESET); //update mode + #endif + } + else { + #if V1_0_V1_1 + #if V1_0_V1_1 + HAL_GPIO_WritePin(GPIOA,GPIO_Pin_8,GPIO_PIN_SET); //boot mode + GPIO_InitStructure.Speed = GPIO_SPEED_FREQ_HIGH; + GPIO_InitStructure.Pin = GPIO_Pin_8; + GPIO_InitStructure.Mode = GPIO_MODE_INPUT; + HAL_GPIO_Init(GPIOA, &GPIO_InitStructure); + #endif + #else + HAL_GPIO_WritePin(GPIOC,GPIO_Pin_13,GPIO_PIN_SET); //boot mode + GPIO_InitStructure.Speed = GPIO_SPEED_FREQ_LOW; + GPIO_InitStructure.Pin = GPIO_Pin_13; + GPIO_InitStructure.Mode = GPIO_MODE_INPUT; + HAL_GPIO_Init(GPIOC, &GPIO_InitStructure); + #endif + } + WIFI_RESET(); + while (getWifiTickDiff(start, now) < 500) now = getWifiTick(); + WIFI_SET(); + #endif +} + +int32_t wifi_upload(int type) { + esp_upload.retriesPerBaudRate = 9; + + ResetWiFiForUpload(0); + + if (type == 0) + SendUpdateFile(ESP_FIRMWARE_FILE, FirmwareAddress); + else if (type == 1) + SendUpdateFile(ESP_WEB_FIRMWARE_FILE, FirmwareAddress); + else if (type == 2) + SendUpdateFile(ESP_WEB_FILE, WebFilesAddress); + else + return -1; + + while (esp_upload.state != upload_idle) { + upload_spin(); + //IWDG_ReloadCounter(); + } + + ResetWiFiForUpload(1); + + return esp_upload.uploadResult == success ? 0 : -1; +} + +#endif // HAS_TFT_LVGL_UI diff --git a/Marlin/src/lcd/extui/lib/mks_ui/wifi_upload.h b/Marlin/src/lcd/extui/lib/mks_ui/wifi_upload.h new file mode 100644 index 0000000000..d942a2c84f --- /dev/null +++ b/Marlin/src/lcd/extui/lib/mks_ui/wifi_upload.h @@ -0,0 +1,74 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#ifdef __cplusplus + extern "C" { /* C-declarations for C++ */ +#endif + +#define ESP_FIRMWARE_FILE "1:/MksWifi.bin" +#define ESP_WEB_FIRMWARE_FILE "1:/MksWifi_Web.bin" +#define ESP_WEB_FILE "1:/MksWifi_WebView.bin" + +typedef enum { + upload_idle, + resetting, + connecting, + erasing, + uploading, + done +} UploadState; + +typedef enum { + success = 0, + timeout, + connected, + badReply, + fileRead, + emptyFile, + respHeader, + slipFrame, + slipState, + slipData, +} EspUploadResult; + +typedef struct { + //FIL uploadFile; + uint32_t fileSize; + + uint32_t uploadAddress; + UploadState state; + uint32_t retriesPerBaudRate; + uint32_t connectAttemptNumber; + uint32_t lastAttemptTime; + uint32_t lastResetTime; + uint32_t uploadBlockNumber; + uint32_t uploadNextPercentToReport; + EspUploadResult uploadResult; +} UPLOAD_STRUCT; + +extern UPLOAD_STRUCT esp_upload; +int32_t wifi_upload(int type); + +#ifdef __cplusplus + } /* C-declarations for C++ */ +#endif diff --git a/Marlin/src/lcd/extui/malyan_lcd.cpp b/Marlin/src/lcd/extui/malyan_lcd.cpp index b5148065c7..79a5fb961a 100644 --- a/Marlin/src/lcd/extui/malyan_lcd.cpp +++ b/Marlin/src/lcd/extui/malyan_lcd.cpp @@ -45,7 +45,7 @@ #if ENABLED(MALYAN_LCD) -#define DEBUG_MALYAN_LCD +//#define DEBUG_MALYAN_LCD #include "ui_api.h" @@ -61,10 +61,6 @@ #define DEBUG_OUT ENABLED(DEBUG_MALYAN_LCD) #include "../../core/debug_out.h" -// On the Malyan M200, this will be Serial1. On a RAMPS board, -// it might not be. -#define LCD_SERIAL Serial1 - // This is based on longest sys command + a filename, plus some buffer // in case we encounter some data we don't recognize // There is no evidence a line will ever be this long, but better safe than sorry @@ -432,7 +428,11 @@ namespace ExtUI { * it and translate into ExtUI operations where possible. */ inbound_count = 0; - LCD_SERIAL.begin(500000); + + #ifndef LCD_BAUDRATE + #define LCD_BAUDRATE 500000 + #endif + LCD_SERIAL.begin(LCD_BAUDRATE); // Signal init write_to_lcd_P(PSTR("{SYS:STARTED}\r\n")); diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index 31449fcef4..1270e3d649 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -61,7 +61,7 @@ #include "../../libs/numtostr.h" #endif -#if EXTRUDERS > 1 +#if HAS_MULTI_EXTRUDER #include "../../module/tool_change.h" #endif @@ -223,7 +223,7 @@ namespace ExtUI { bool isHeaterIdle(const extruder_t extruder) { #if HAS_HOTEND && HEATER_IDLE_HANDLER - return thermalManager.hotend_idle[extruder - E0].timed_out; + return thermalManager.heater_idle[extruder - E0].timed_out; #else UNUSED(extruder); return false; @@ -233,10 +233,10 @@ namespace ExtUI { bool isHeaterIdle(const heater_t heater) { #if HEATER_IDLE_HANDLER switch (heater) { - TERN_(HAS_HEATED_BED, case BED: return thermalManager.bed_idle.timed_out); + TERN_(HAS_HEATED_BED, case BED: return thermalManager.heater_idle[thermalManager.IDLE_INDEX_BED].timed_out); TERN_(HAS_HEATED_CHAMBER, case CHAMBER: return false); // Chamber has no idle timer default: - return TERN0(HAS_HOTEND, thermalManager.hotend_idle[heater - H0].timed_out); + return TERN0(HAS_HOTEND, thermalManager.heater_idle[heater - H0].timed_out); } #else UNUSED(heater); @@ -348,7 +348,7 @@ namespace ExtUI { } void setActiveTool(const extruder_t extruder, bool no_move) { - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER const uint8_t e = extruder - E0; if (e != active_extruder) tool_change(e, no_move); active_extruder = e; @@ -544,11 +544,13 @@ namespace ExtUI { void setAxisSteps_per_mm(const float value, const axis_t axis) { planner.settings.axis_steps_per_mm[axis] = value; + planner.refresh_positioning(); } void setAxisSteps_per_mm(const float value, const extruder_t extruder) { UNUSED_E(extruder); planner.settings.axis_steps_per_mm[E_AXIS_N(extruder - E0)] = value; + planner.refresh_positioning(); } feedRate_t getAxisMaxFeedrate_mm_s(const axis_t axis) { @@ -580,11 +582,13 @@ namespace ExtUI { void setAxisMaxAcceleration_mm_s2(const float value, const axis_t axis) { planner.set_max_acceleration(axis, value); + planner.reset_acceleration_rates(); } void setAxisMaxAcceleration_mm_s2(const float value, const extruder_t extruder) { UNUSED_E(extruder); planner.set_max_acceleration(E_AXIS_N(extruder - E0), value); + planner.reset_acceleration_rates(); } #if HAS_FILAMENT_SENSOR @@ -695,21 +699,17 @@ namespace ExtUI { */ void smartAdjustAxis_steps(const int16_t steps, const axis_t axis, bool linked_nozzles) { const float mm = steps * planner.steps_to_mm[axis]; + UNUSED(mm); if (!babystepAxis_steps(steps, axis)) return; #if ENABLED(BABYSTEP_ZPROBE_OFFSET) // Make it so babystepping in Z adjusts the Z probe offset. - if (axis == Z - #if EXTRUDERS > 1 - && (linked_nozzles || active_extruder == 0) - #endif - ) probe.offset.z += mm; - #else - UNUSED(mm); + if (axis == Z && TERN1(HAS_MULTI_EXTRUDER, (linked_nozzles || active_extruder == 0))) + probe.offset.z += mm; #endif - #if EXTRUDERS > 1 && HAS_HOTEND_OFFSET + #if HAS_MULTI_EXTRUDER && HAS_HOTEND_OFFSET /** * When linked_nozzles is false, as an axis is babystepped * adjust the hotend offsets so that the other nozzles are @@ -726,7 +726,6 @@ namespace ExtUI { } #else UNUSED(linked_nozzles); - UNUSED(mm); #endif } @@ -755,7 +754,7 @@ namespace ExtUI { if (WITHIN(value, Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX)) probe.offset.z = value; #elif ENABLED(BABYSTEP_DISPLAY_TOTAL) - babystep.add_mm(Z_AXIS, (value - getZOffset_mm())); + babystep.add_mm(Z_AXIS, value - getZOffset_mm()); #else UNUSED(value); #endif @@ -864,7 +863,7 @@ namespace ExtUI { } void startPIDTune(const float temp, extruder_t tool) { - thermalManager.PID_autotune(temp, (heater_ind_t)tool, 8, true); + thermalManager.PID_autotune(temp, (heater_id_t)tool, 8, true); } #endif @@ -1003,7 +1002,7 @@ namespace ExtUI { bool FileList::seek(const uint16_t pos, const bool skip_range_check) { #if ENABLED(SDSUPPORT) if (!skip_range_check && (pos + 1) > count()) return false; - card.getfilename_sorted(pos); + card.getfilename_sorted(SD_ORDER(pos, count())); return card.filename[0] != '\0'; #else UNUSED(pos); diff --git a/Marlin/src/lcd/extui/ui_api.h b/Marlin/src/lcd/extui/ui_api.h index ca12d79a8b..15122ec69e 100644 --- a/Marlin/src/lcd/extui/ui_api.h +++ b/Marlin/src/lcd/extui/ui_api.h @@ -143,7 +143,12 @@ namespace ExtUI { void onMeshUpdate(const int8_t xpos, const int8_t ypos, const float zval); inline void onMeshUpdate(const xy_int8_t &pos, const float zval) { onMeshUpdate(pos.x, pos.y, zval); } - typedef enum : unsigned char { PROBE_START, PROBE_FINISH } probe_state_t; + typedef enum : unsigned char { + MESH_START, // Prior to start of probe + MESH_FINISH, // Following probe of all points + PROBE_START, // Beginning probe of grid location + PROBE_FINISH // Finished probe of grid location + } probe_state_t; void onMeshUpdate(const int8_t xpos, const int8_t ypos, probe_state_t state); inline void onMeshUpdate(const xy_int8_t &pos, probe_state_t state) { onMeshUpdate(pos.x, pos.y, state); } #endif @@ -370,7 +375,6 @@ namespace ExtUI { * constexpr float increment = 10; * * UI_INCREMENT(TargetTemp_celsius, E0) - * */ #define UI_INCREMENT_BY(method, inc, ...) ExtUI::set ## method(ExtUI::get ## method (__VA_ARGS__) + inc, ##__VA_ARGS__) #define UI_DECREMENT_BY(method, inc, ...) ExtUI::set ## method(ExtUI::get ## method (__VA_ARGS__) - inc, ##__VA_ARGS__) diff --git a/Marlin/src/lcd/fontutils.cpp b/Marlin/src/lcd/fontutils.cpp index 8b046af9a7..5bf07e1bd4 100644 --- a/Marlin/src/lcd/fontutils.cpp +++ b/Marlin/src/lcd/fontutils.cpp @@ -9,7 +9,7 @@ #include "../inc/MarlinConfig.h" -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #include "ultralcd.h" #include "../MarlinCore.h" #endif diff --git a/Marlin/src/lcd/language/language_an.h b/Marlin/src/lcd/language/language_an.h index 1cb64f985b..a5030fcd56 100644 --- a/Marlin/src/lcd/language/language_an.h +++ b/Marlin/src/lcd/language/language_an.h @@ -26,7 +26,6 @@ * * LCD Menu Messages * See also https://marlinfw.org/docs/development/lcd_language.html - * */ #define DISPLAY_CHARSET_ISO10646_1 diff --git a/Marlin/src/lcd/language/language_bg.h b/Marlin/src/lcd/language/language_bg.h index 8917d98e68..dcb06e31e7 100644 --- a/Marlin/src/lcd/language/language_bg.h +++ b/Marlin/src/lcd/language/language_bg.h @@ -26,7 +26,6 @@ * * LCD Menu Messages * See also https://marlinfw.org/docs/development/lcd_language.html - * */ #define DISPLAY_CHARSET_ISO10646_5 diff --git a/Marlin/src/lcd/language/language_ca.h b/Marlin/src/lcd/language/language_ca.h index 1c4a029ff7..0657c4a759 100644 --- a/Marlin/src/lcd/language/language_ca.h +++ b/Marlin/src/lcd/language/language_ca.h @@ -26,7 +26,6 @@ * * LCD Menu Messages * See also https://marlinfw.org/docs/development/lcd_language.html - * */ namespace Language_ca { using namespace Language_en; // Inherit undefined strings from English diff --git a/Marlin/src/lcd/language/language_cz.h b/Marlin/src/lcd/language/language_cz.h index c21cacddc8..716c0a0929 100644 --- a/Marlin/src/lcd/language/language_cz.h +++ b/Marlin/src/lcd/language/language_cz.h @@ -31,7 +31,6 @@ * Translated by Petr Zahradnik, Computer Laboratory * Blog and video blog Zahradnik se bavi * https://www.zahradniksebavi.cz - * */ #define DISPLAY_CHARSET_ISO10646_CZ @@ -404,18 +403,12 @@ namespace Language_cz { PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Celkem"); PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Endstop abort"); PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Chyba zahřívání"); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD_BED = _UxGT("Chyba zahř.podl."); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD_CHAMBER = _UxGT("Chyba zahř.komory"); PROGMEM Language_Str MSG_ERR_REDUNDANT_TEMP = _UxGT("REDUND. TEPLOTA"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("TEPLOTNÍ ÚNIK"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("TEPL. ÚNIK PODL."); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("TEPL. ÚNIK KOMORA"); PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("VYSOKÁ TEPLOTA"); PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("NÍZKA TEPLOTA"); - PROGMEM Language_Str MSG_ERR_MAXTEMP_BED = _UxGT("VYS. TEPL. PODL."); - PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("NÍZ. TEPL. PODL."); - PROGMEM Language_Str MSG_ERR_MAXTEMP_CHAMBER = _UxGT("Err: MAXTEMP KOMORA"); - PROGMEM Language_Str MSG_ERR_MINTEMP_CHAMBER = _UxGT("Err: MINTEMP KOMORA"); PROGMEM Language_Str MSG_HALTED = _UxGT("TISK. ZASTAVENA"); PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Proveďte reset"); PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("d"); @@ -503,7 +496,6 @@ namespace Language_cz { PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("Délka mm senz.fil."); PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Parkování selhalo"); PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Kalibrace selhala"); - PROGMEM Language_Str MSG_M600_TOO_COLD = _UxGT("M600: Moc studený"); PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("VYBERTE FILAMENT"); PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); @@ -527,7 +519,7 @@ namespace Language_cz { PROGMEM Language_Str MSG_MMU2_EJECT_RECOVER = _UxGT("Vytáhněte, klikněte"); PROGMEM Language_Str MSG_MIX = _UxGT("Mix"); - PROGMEM Language_Str MSG_MIX_COMPONENT_N = _UxGT("Komponenta ~"); + PROGMEM Language_Str MSG_MIX_COMPONENT_N = _UxGT("Komponenta ="); PROGMEM Language_Str MSG_MIXER = _UxGT("Mixér"); PROGMEM Language_Str MSG_GRADIENT = _UxGT("Přechod"); PROGMEM Language_Str MSG_FULL_GRADIENT = _UxGT("Celý přechod"); diff --git a/Marlin/src/lcd/language/language_da.h b/Marlin/src/lcd/language/language_da.h index 7a9321d001..0e4fa75aa6 100644 --- a/Marlin/src/lcd/language/language_da.h +++ b/Marlin/src/lcd/language/language_da.h @@ -26,7 +26,6 @@ * * LCD Menu Messages * See also https://marlinfw.org/docs/development/lcd_language.html - * */ #define DISPLAY_CHARSET_ISO10646_1 @@ -52,7 +51,7 @@ namespace Language_da { #if PREHEAT_COUNT PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Forvarm ") PREHEAT_1_LABEL; PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Forvarm ") PREHEAT_1_LABEL " ~"; - PROGMEM Language_Str MSG_PREHEAT_1_END = _UxGT("Forvarm ") PREHEAT_1_LABEL _UxGT(" end") + PROGMEM Language_Str MSG_PREHEAT_1_END = _UxGT("Forvarm ") PREHEAT_1_LABEL _UxGT(" end"); PROGMEM Language_Str MSG_PREHEAT_1_END_E = _UxGT("Forvarm ") PREHEAT_1_LABEL _UxGT(" end ~"); PROGMEM Language_Str MSG_PREHEAT_1_ALL = _UxGT("Forvarm ") PREHEAT_1_LABEL _UxGT(" Alle"); PROGMEM Language_Str MSG_PREHEAT_1_BEDONLY = _UxGT("Forvarm ") PREHEAT_1_LABEL _UxGT(" Bed"); @@ -60,7 +59,7 @@ namespace Language_da { PROGMEM Language_Str MSG_PREHEAT_M = _UxGT("Forvarm $"); PROGMEM Language_Str MSG_PREHEAT_M_H = _UxGT("Forvarm $ ~"); - PROGMEM Language_Str MSG_PREHEAT_M_END = _UxGT("Forvarm $ end") + PROGMEM Language_Str MSG_PREHEAT_M_END = _UxGT("Forvarm $ end"); PROGMEM Language_Str MSG_PREHEAT_M_END_E = _UxGT("Forvarm $ end ~"); PROGMEM Language_Str MSG_PREHEAT_M_ALL = _UxGT("Forvarm $ Alle"); PROGMEM Language_Str MSG_PREHEAT_M_BEDONLY = _UxGT("Forvarm $ Bed"); @@ -142,8 +141,6 @@ namespace Language_da { PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("Temp løber løbsk"); PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Fejl: Maks temp"); PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Fejl: Min temp"); - PROGMEM Language_Str MSG_ERR_MAXTEMP_BED = _UxGT("Fejl: Maks Plade temp"); - PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("Fejl: Min Plade temp"); PROGMEM Language_Str MSG_HALTED = _UxGT("PRINTER STOPPET"); PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Reset Venligst"); PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("d"); // Kun et bogstav diff --git a/Marlin/src/lcd/language/language_de.h b/Marlin/src/lcd/language/language_de.h index ebd0805037..5492cd5d59 100644 --- a/Marlin/src/lcd/language/language_de.h +++ b/Marlin/src/lcd/language/language_de.h @@ -26,17 +26,16 @@ * * LCD Menu Messages * See also https://marlinfw.org/docs/development/lcd_language.html - * */ namespace Language_de { using namespace Language_en; // Inherit undefined strings from English constexpr uint8_t CHARSIZE = 2; - PROGMEM Language_Str LANGUAGE = _UxGT("Deutsche"); + PROGMEM Language_Str LANGUAGE = _UxGT("Deutsch"); PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT(" bereit"); - + PROGMEM Language_Str MSG_MARLIN = _UxGT("Marlin"); PROGMEM Language_Str MSG_YES = _UxGT("JA"); PROGMEM Language_Str MSG_NO = _UxGT("NEIN"); PROGMEM Language_Str MSG_BACK = _UxGT("Zurück"); @@ -44,9 +43,11 @@ namespace Language_de { PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("Medium erkannt"); PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Medium entfernt"); PROGMEM Language_Str MSG_MEDIA_WAITING = _UxGT("Warten auf Medium"); + PROGMEM Language_Str MSG_SD_INIT_FAIL = _UxGT("SD Init fehlgesch."); PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("Medium Lesefehler"); PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("USB Gerät entfernt"); PROGMEM Language_Str MSG_MEDIA_USB_FAILED = _UxGT("USB Start fehlge."); + PROGMEM Language_Str MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Subcall überschritten"); PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("Endstopp"); // Max length 8 characters PROGMEM Language_Str MSG_LCD_SOFT_ENDSTOPS = _UxGT("Software-Endstopp"); PROGMEM Language_Str MSG_MAIN = _UxGT("Hauptmenü"); @@ -56,7 +57,13 @@ namespace Language_de { PROGMEM Language_Str MSG_DISABLE_STEPPERS = _UxGT("Motoren deaktivieren"); // M84 :: Max length 19 characters PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Debug-Menü"); PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Statusbalken-Test"); + PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("Auto Home"); + PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Home X"); + PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Home Y"); + PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Home Z"); PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Z-Achsen ausgleichen"); + PROGMEM Language_Str MSG_ASSISTED_TRAMMING = _UxGT("Bett ausrichten"); // Bettausrichtung + PROGMEM Language_Str MSG_LEVEL_BED_HOMING = _UxGT("XYZ homen"); PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("Klick zum Starten"); PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("Nächste Koordinate"); PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("Nivellieren fertig!"); @@ -110,9 +117,9 @@ namespace Language_de { PROGMEM Language_Str MSG_MESH_Y = _UxGT("Index Y"); PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Z-Wert"); PROGMEM Language_Str MSG_USER_MENU = _UxGT("Benutzer-Menü"); - PROGMEM Language_Str MSG_LCD_TILTING_MESH = _UxGT("Berührungspunkt"); PROGMEM Language_Str MSG_M48_TEST = _UxGT("M48 Sondentest"); PROGMEM Language_Str MSG_M48_POINT = _UxGT("M48 Punkt"); + PROGMEM Language_Str MSG_M48_OUT_OF_BOUNDS = _UxGT("Zu weit draußen"); PROGMEM Language_Str MSG_M48_DEVIATION = _UxGT("Abweichung"); PROGMEM Language_Str MSG_IDEX_MENU = _UxGT("IDEX-Modus"); PROGMEM Language_Str MSG_OFFSETS_MENU = _UxGT("Werkzeugversätze"); @@ -126,6 +133,7 @@ namespace Language_de { PROGMEM Language_Str MSG_UBL_DOING_G29 = _UxGT("G29 ausführen"); PROGMEM Language_Str MSG_UBL_TOOLS = _UxGT("UBL-Werkzeuge"); PROGMEM Language_Str MSG_UBL_LEVEL_BED = _UxGT("Unified Bed Leveling"); + PROGMEM Language_Str MSG_LCD_TILTING_MESH = _UxGT("Berührungspunkt"); PROGMEM Language_Str MSG_UBL_MANUAL_MESH = _UxGT("Netz manuell erst."); PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Unterlegen & messen"); PROGMEM Language_Str MSG_UBL_BC_INSERT2 = _UxGT("Messen"); @@ -154,6 +162,7 @@ namespace Language_de { PROGMEM Language_Str MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Eig. Netz validieren"); PROGMEM Language_Str MSG_G26_HEATING_BED = _UxGT("G26 heizt Bett"); PROGMEM Language_Str MSG_G26_HEATING_NOZZLE = _UxGT("G26 Düse aufheizen"); + PROGMEM Language_Str MSG_G26_MANUAL_PRIME = _UxGT("Manuell Prime..."); PROGMEM Language_Str MSG_G26_FIXED_LENGTH = _UxGT("Feste Länge Prime"); PROGMEM Language_Str MSG_G26_PRIME_DONE = _UxGT("Priming fertig"); PROGMEM Language_Str MSG_G26_CANCELED = _UxGT("G26 abgebrochen"); @@ -234,6 +243,7 @@ namespace Language_de { PROGMEM Language_Str MSG_NOZZLE = _UxGT("Düse"); PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Düse ~"); PROGMEM Language_Str MSG_NOZZLE_PARKED = _UxGT("Düse geparkt"); + PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Düse bereit"); PROGMEM Language_Str MSG_BED = _UxGT("Bett"); PROGMEM Language_Str MSG_CHAMBER = _UxGT("Gehäuse"); PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Lüfter"); @@ -255,6 +265,22 @@ namespace Language_de { PROGMEM Language_Str MSG_AUTOTEMP = _UxGT("Auto Temperatur"); PROGMEM Language_Str MSG_LCD_ON = _UxGT("an"); PROGMEM Language_Str MSG_LCD_OFF = _UxGT("aus"); + PROGMEM Language_Str MSG_PID_AUTOTUNE = _UxGT("PID Autotune"); + PROGMEM Language_Str MSG_PID_AUTOTUNE_E = _UxGT("PID Autotune *"); + PROGMEM Language_Str MSG_PID_AUTOTUNE_DONE = _UxGT("PID Tuning fertig"); + PROGMEM Language_Str MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Autotune fehlge. Falscher Extruder"); + PROGMEM Language_Str MSG_PID_TEMP_TOO_HIGH = _UxGT("Autotune fehlge. Temperatur zu hoch."); + PROGMEM Language_Str MSG_PID_TIMEOUT = _UxGT("Autotune fehlge.! Timeout."); + PROGMEM Language_Str MSG_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("Auswählen"); PROGMEM Language_Str MSG_SELECT_E = _UxGT("Auswählen *"); PROGMEM Language_Str MSG_ACC = _UxGT("Beschleunigung"); @@ -281,6 +307,8 @@ namespace Language_de { PROGMEM Language_Str MSG_AMAX_EN = _UxGT("A max *"); PROGMEM Language_Str MSG_A_RETRACT = _UxGT("A Einzug"); PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("A Leerfahrt"); + PROGMEM Language_Str MSG_XY_FREQUENCY_LIMIT = _UxGT("max. Frequenz"); + PROGMEM Language_Str MSG_XY_FREQUENCY_FEEDRATE = _UxGT("min. Vorschub"); PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("Steps/mm"); PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" Steps/mm"); PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" Steps/mm"); @@ -291,6 +319,8 @@ namespace Language_de { PROGMEM Language_Str MSG_MOTION = _UxGT("Bewegung"); PROGMEM Language_Str MSG_FILAMENT = _UxGT("Filament"); PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E in mm³"); + PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT = _UxGT("E Limit in mm³"); + PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT_E = _UxGT("E Limit *"); PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Filamentdurchmesser"); PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Filamentdurchmesser *"); PROGMEM Language_Str MSG_FILAMENT_UNLOAD = _UxGT("Entladen mm"); @@ -302,6 +332,9 @@ namespace Language_de { PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Konfig. laden"); PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("Standardwerte laden"); PROGMEM Language_Str MSG_INIT_EEPROM = _UxGT("Werkseinstellungen"); + PROGMEM Language_Str MSG_ERR_EEPROM_CRC = _UxGT("EEPROM CRC Fehler"); + PROGMEM Language_Str MSG_ERR_EEPROM_INDEX = _UxGT("EEPROM Index Fehler"); + PROGMEM Language_Str MSG_ERR_EEPROM_VERSION = _UxGT("EEPROM Version Fehler"); PROGMEM Language_Str MSG_SETTINGS_STORED = _UxGT("Einstell. gespei."); PROGMEM Language_Str MSG_MEDIA_UPDATE = _UxGT("FW Update vom Medium"); PROGMEM Language_Str MSG_RESET_PRINTER = _UxGT("Drucker neustarten"); @@ -309,19 +342,26 @@ namespace Language_de { PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("Info"); PROGMEM Language_Str MSG_PREPARE = _UxGT("Vorbereitung"); PROGMEM Language_Str MSG_TUNE = _UxGT("Justierung"); + PROGMEM Language_Str MSG_POWER_MONITOR = _UxGT("Power Monitor"); + PROGMEM Language_Str MSG_CURRENT = _UxGT("Strom"); + PROGMEM Language_Str MSG_VOLTAGE = _UxGT("Spannung"); + PROGMEM Language_Str MSG_POWER = _UxGT("Power"); PROGMEM Language_Str MSG_START_PRINT = _UxGT("Starte Druck"); PROGMEM Language_Str MSG_BUTTON_NEXT = _UxGT("Weiter"); PROGMEM Language_Str MSG_BUTTON_INIT = _UxGT("Bestätigen"); PROGMEM Language_Str MSG_BUTTON_STOP = _UxGT("Stop"); PROGMEM Language_Str MSG_BUTTON_PRINT = _UxGT("Drucken"); PROGMEM Language_Str MSG_BUTTON_RESET = _UxGT("Reseten"); + PROGMEM Language_Str MSG_BUTTON_IGNORE = _UxGT("Ignorieren"); PROGMEM Language_Str MSG_BUTTON_CANCEL = _UxGT("Abbrechen"); PROGMEM Language_Str MSG_BUTTON_DONE = _UxGT("Fertig"); PROGMEM Language_Str MSG_BUTTON_BACK = _UxGT("Zurück"); + PROGMEM Language_Str MSG_BUTTON_PROCEED = _UxGT("Weiter"); PROGMEM Language_Str MSG_PAUSING = _UxGT("Pause..."); PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("SD-Druck pausieren"); PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("SD-Druck fortsetzen"); PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("SD-Druck abbrechen"); + PROGMEM Language_Str MSG_PRINTING_OBJECT = _UxGT("Objekt drucken"); PROGMEM Language_Str MSG_CANCEL_OBJECT = _UxGT("Objekt abbrechen"); PROGMEM Language_Str MSG_CANCEL_OBJECT_N = _UxGT("Objekt abbrechen ="); PROGMEM Language_Str MSG_OUTAGE_RECOVERY = _UxGT("Wiederh. n. Stroma."); @@ -346,12 +386,22 @@ namespace Language_de { PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("S UnRet V"); PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("Autom. Einzug"); PROGMEM Language_Str MSG_FILAMENT_SWAP_LENGTH = _UxGT("Einzugslänge"); + PROGMEM Language_Str MSG_FILAMENT_SWAP_EXTRA = _UxGT("Extra Einzug"); PROGMEM Language_Str MSG_FILAMENT_PURGE_LENGTH = _UxGT("Entladelänge"); PROGMEM Language_Str MSG_TOOL_CHANGE = _UxGT("Werkzeugwechsel"); PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Z anheben"); PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Prime-Geschwin."); PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Einzug-Geschwin."); - PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Düsen-Standby"); + PROGMEM Language_Str MSG_FILAMENT_PARK_ENABLED = _UxGT("Kopf parken"); + PROGMEM Language_Str MSG_SINGLENOZZLE_UNRETRACT_SPEED = _UxGT("Rückzugsgeschwindigkeit"); + PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_SPEED = _UxGT("Lüfter Geschwindigkeit"); + PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_TIME = _UxGT("Lüfter Zeit"); + PROGMEM Language_Str MSG_TOOL_MIGRATION_ON = _UxGT("Auto AN"); + PROGMEM Language_Str MSG_TOOL_MIGRATION_OFF = _UxGT("Auto AUS"); + PROGMEM Language_Str MSG_TOOL_MIGRATION = _UxGT("Werkzeugmigration"); + PROGMEM Language_Str MSG_TOOL_MIGRATION_AUTO = _UxGT("Auto-Migration"); + PROGMEM Language_Str MSG_TOOL_MIGRATION_END = _UxGT("Letzter Extruder"); + PROGMEM Language_Str MSG_TOOL_MIGRATION_SWAP = _UxGT("Migrieren zu *"); PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Filament wechseln"); PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Filament wechseln *"); PROGMEM Language_Str MSG_FILAMENTLOAD = _UxGT("Filament laden"); @@ -367,6 +417,7 @@ namespace Language_de { PROGMEM Language_Str MSG_BLTOUCH = _UxGT("BLTouch"); PROGMEM Language_Str MSG_BLTOUCH_SELFTEST = _UxGT("Selbsttest"); PROGMEM Language_Str MSG_BLTOUCH_RESET = _UxGT("Zurücksetzen"); + PROGMEM Language_Str MSG_BLTOUCH_STOW = _UxGT("Einfahren"); PROGMEM Language_Str MSG_BLTOUCH_DEPLOY = _UxGT("Ausfahren"); PROGMEM Language_Str MSG_BLTOUCH_SW_MODE = _UxGT("SW-Modus"); PROGMEM Language_Str MSG_BLTOUCH_5V_MODE = _UxGT("5V-Modus"); @@ -374,7 +425,6 @@ namespace Language_de { PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE = _UxGT("Mode-Store"); PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_5V = _UxGT("Setze auf 5V"); PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_OD = _UxGT("Setze auf OD"); - PROGMEM Language_Str MSG_BLTOUCH_STOW = _UxGT("Einfahren"); PROGMEM Language_Str MSG_BLTOUCH_MODE_ECHO = _UxGT("Modus: "); PROGMEM Language_Str MSG_BLTOUCH_MODE_CHANGE = _UxGT("ACHTUNG: Falsche Einstellung - kann zu Beschädigung führen! Fortfahren?"); PROGMEM Language_Str MSG_TOUCHMI_PROBE = _UxGT("TouchMI"); @@ -395,18 +445,12 @@ namespace Language_de { PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Total"); PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Abbr. mit Endstopp"); PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("HEIZEN ERFOLGLOS"); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD_BED = _UxGT("Bett heizen fehlge."); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD_CHAMBER = _UxGT("Geh. heizen fehlge."); PROGMEM Language_Str MSG_ERR_REDUNDANT_TEMP = _UxGT("REDUND. TEMP-ABWEI."); PROGMEM Language_Str MSG_THERMAL_RUNAWAY = " " LCD_STR_THERMOMETER _UxGT(" NICHT ERREICHT"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("BETT") " " LCD_STR_THERMOMETER _UxGT(" NICHT ERREICHT"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("GEH.") " " LCD_STR_THERMOMETER _UxGT(" NICHT ERREICHT"); PROGMEM Language_Str MSG_ERR_MAXTEMP = " " LCD_STR_THERMOMETER _UxGT(" ÜBERSCHRITTEN"); PROGMEM Language_Str MSG_ERR_MINTEMP = " " LCD_STR_THERMOMETER _UxGT(" UNTERSCHRITTEN"); - PROGMEM Language_Str MSG_ERR_MAXTEMP_BED = _UxGT("BETT ") LCD_STR_THERMOMETER _UxGT(" ÜBERSCHRITTEN"); - PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("BETT ") LCD_STR_THERMOMETER _UxGT(" UNTERSCHRITTEN"); - PROGMEM Language_Str MSG_ERR_MAXTEMP_CHAMBER = _UxGT("Err:Gehäuse max Temp"); - PROGMEM Language_Str MSG_ERR_MINTEMP_CHAMBER = _UxGT("Err:Gehäuse min Temp"); PROGMEM Language_Str MSG_HALTED = _UxGT("DRUCKER GESTOPPT"); PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Bitte neustarten"); PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("t"); // One character only @@ -443,6 +487,9 @@ namespace Language_de { PROGMEM Language_Str MSG_INFO_EXTRUDERS = _UxGT("Extruder"); PROGMEM Language_Str MSG_INFO_BAUDRATE = _UxGT("Baudrate"); PROGMEM Language_Str MSG_INFO_PROTOCOL = _UxGT("Protokoll"); + PROGMEM Language_Str MSG_INFO_RUNAWAY_OFF = _UxGT("Runaway Watch: AUS"); + PROGMEM Language_Str MSG_INFO_RUNAWAY_ON = _UxGT("Runaway Watch: AN"); + PROGMEM Language_Str MSG_HOTEND_IDLE_TIMEOUT = _UxGT("Hotend Idle Timeout"); PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Beleuchtung"); PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Helligkeit"); @@ -484,7 +531,6 @@ namespace Language_de { PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("Runout-Weg mm"); PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Homing gescheitert"); PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Probing gescheitert"); - PROGMEM Language_Str MSG_M600_TOO_COLD = _UxGT("M600: zu kalt"); PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("FILAMENT WÄHLEN"); PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); @@ -508,7 +554,7 @@ namespace Language_de { PROGMEM Language_Str MSG_MMU2_EJECT_RECOVER = _UxGT("Entfernen, klicken"); PROGMEM Language_Str MSG_MIX = _UxGT("Mix"); - PROGMEM Language_Str MSG_MIX_COMPONENT_N = _UxGT("Komponente ~"); + PROGMEM Language_Str MSG_MIX_COMPONENT_N = _UxGT("Komponente ="); PROGMEM Language_Str MSG_MIXER = _UxGT("Mixer"); PROGMEM Language_Str MSG_GRADIENT = _UxGT("Gradient"); // equal Farbverlauf PROGMEM Language_Str MSG_FULL_GRADIENT = _UxGT("Volle Gradient"); @@ -531,6 +577,20 @@ namespace Language_de { PROGMEM Language_Str MSG_SNAKE = _UxGT("Sn4k3"); PROGMEM Language_Str MSG_MAZE = _UxGT("Maze"); + PROGMEM Language_Str MSG_BAD_PAGE = _UxGT("ungült. Seitenzahl"); + PROGMEM Language_Str MSG_BAD_PAGE_SPEED = _UxGT("ungült. Seitengeschw."); + + PROGMEM Language_Str MSG_EDIT_PASSWORD = _UxGT("Passwort bearbeiten"); + PROGMEM Language_Str MSG_LOGIN_REQUIRED = _UxGT("Login erforderlich"); + PROGMEM Language_Str MSG_PASSWORD_SETTINGS = _UxGT("Passwort Einstellungen"); + PROGMEM Language_Str MSG_ENTER_DIGIT = _UxGT("PIN eingeben"); + PROGMEM Language_Str MSG_CHANGE_PASSWORD = _UxGT("Passwort ändern"); + PROGMEM Language_Str MSG_REMOVE_PASSWORD = _UxGT("Passwort löschen"); + PROGMEM Language_Str MSG_PASSWORD_SET = _UxGT("Passwort ist "); + PROGMEM Language_Str MSG_START_OVER = _UxGT("von vorn beginnen"); + PROGMEM Language_Str MSG_REMINDER_SAVE_SETTINGS = _UxGT("Bald speichern!"); + PROGMEM Language_Str MSG_PASSWORD_REMOVED = _UxGT("Passwort gelöscht"); + // // Die Filament-Change-Bildschirme können bis zu 3 Zeilen auf einem 4-Zeilen-Display anzeigen // ...oder 2 Zeilen auf einem 3-Zeilen-Display. @@ -576,7 +636,11 @@ namespace Language_de { PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Glätten"); PROGMEM Language_Str MSG_LEVEL_X_AXIS = _UxGT("X Achse leveln"); PROGMEM Language_Str MSG_AUTO_CALIBRATE = _UxGT("Auto. Kalibiren"); - PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Heizung Timeout"); + #if ENABLED(TOUCH_UI_FTDI_EVE) + PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Idle Timeout, Temperatur fällt. Drücke Okay, um erneut aufzuheizen und fortzufahren."); + #else + PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Heizungs Timeout"); + #endif PROGMEM Language_Str MSG_REHEAT = _UxGT("Erneut aufheizen"); PROGMEM Language_Str MSG_REHEATING = _UxGT("Erneut aufhei. ..."); } diff --git a/Marlin/src/lcd/language/language_el.h b/Marlin/src/lcd/language/language_el.h index cee8dd0e55..fea2bf5818 100644 --- a/Marlin/src/lcd/language/language_el.h +++ b/Marlin/src/lcd/language/language_el.h @@ -26,7 +26,6 @@ * * LCD Menu Messages * See also https://marlinfw.org/docs/development/lcd_language.html - * */ #define DISPLAY_CHARSET_ISO10646_GREEK @@ -180,8 +179,6 @@ namespace Language_el { PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("ΔΙΑΦΥΓΗ ΘΕΡΜΟΚΡΑΣΙΑΣ"); PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("ΠΕΡΙΤΗ ΘΕΡΜΟΚΡΑΣΙΑ"); PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("ΜΗ ΕΠΑΡΚΗΣ ΘΕΡΜΟΚΡΑΣΙΑΣ"); //SHORTEN - PROGMEM Language_Str MSG_ERR_MAXTEMP_BED = _UxGT("ΜΕΓΙΣΤΗ ΘΕΡΜΟΚΡΑΣΙΑΣ ΕΠ. ΕΚΤΥΠΩΣΗΣ"); //SHORTEN - PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("ΕΛΑΧΙΣΤΗ ΘΕΡΜΟΚΡΑΣΙΑΣ ΕΠ. ΕΚΤΥΠΩΣΗΣ"); //SHORTEN PROGMEM Language_Str MSG_HALTED = _UxGT("H εκτύπωση διακόπηκε"); PROGMEM Language_Str MSG_HEATING = _UxGT("Θερμαίνεται…"); PROGMEM Language_Str MSG_BED_HEATING = _UxGT("Θέρμανση ΕΠ. Εκτύπωσης"); //SHORTEN diff --git a/Marlin/src/lcd/language/language_el_gr.h b/Marlin/src/lcd/language/language_el_gr.h index d7bead9ea6..344618b137 100644 --- a/Marlin/src/lcd/language/language_el_gr.h +++ b/Marlin/src/lcd/language/language_el_gr.h @@ -26,7 +26,6 @@ * * LCD Menu Messages * See also https://marlinfw.org/docs/development/lcd_language.html - * */ #define DISPLAY_CHARSET_ISO10646_GREEK @@ -182,8 +181,6 @@ namespace Language_el_gr { PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("ΔΙΑΦΥΓΗ ΘΕΡΜΟΤΗΤΑΣ"); PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Λάθος: ΜΕΓΙΣΤΗ ΘΕΡΜΟΤΗΤΑ"); PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Λάθος: ΕΛΑΧΙΣΤΗ ΘΕΡΜΟΤΗΤΑ"); - PROGMEM Language_Str MSG_ERR_MAXTEMP_BED = _UxGT("Λάθος: ΜΕΓΙΣΤΗ ΘΕΡΜΟΤΗΤΑ ΚΛΙΝΗΣ"); - PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("Λάθος: ΕΛΑΧΙΣΤΗ ΘΕΡΜΟΤΗΤΑ ΚΛΙΝΗΣ"); PROGMEM Language_Str MSG_HEATING = _UxGT("Θερμαίνεται…"); PROGMEM Language_Str MSG_BED_HEATING = _UxGT("Θέρμανση κλίνης…"); PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Βαθμονόμηση Delta"); diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index fde21f2bba..f377a5184c 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -26,7 +26,6 @@ * * LCD Menu Messages * See also https://marlinfw.org/docs/development/lcd_language.html - * */ #define en 1234 @@ -222,6 +221,10 @@ namespace Language_en { PROGMEM Language_Str MSG_SET_LEDS_VIOLET = _UxGT("Violet"); PROGMEM Language_Str MSG_SET_LEDS_WHITE = _UxGT("White"); PROGMEM Language_Str MSG_SET_LEDS_DEFAULT = _UxGT("Default"); + PROGMEM Language_Str MSG_LED_CHANNEL_N = _UxGT("Channel ="); + PROGMEM Language_Str MSG_LEDS2 = _UxGT("Lights #2"); + PROGMEM Language_Str MSG_NEO2_PRESETS = _UxGT("Light #2 Presets"); + PROGMEM Language_Str MSG_NEO2_BRIGHTNESS = _UxGT("Brightness"); PROGMEM Language_Str MSG_CUSTOM_LEDS = _UxGT("Custom Lights"); PROGMEM Language_Str MSG_INTENSITY_R = _UxGT("Red Intensity"); PROGMEM Language_Str MSG_INTENSITY_G = _UxGT("Green Intensity"); @@ -362,6 +365,7 @@ namespace Language_en { PROGMEM Language_Str MSG_PAUSING = _UxGT("Pausing..."); PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Pause Print"); PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Resume Print"); + PROGMEM Language_Str MSG_HOST_START_PRINT = _UxGT("Host Start"); PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("Stop Print"); PROGMEM Language_Str MSG_PRINTING_OBJECT = _UxGT("Printing Object"); PROGMEM Language_Str MSG_CANCEL_OBJECT = _UxGT("Cancel Object"); @@ -447,18 +451,12 @@ namespace Language_en { PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Total"); PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Endstop Abort"); PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Heating Failed"); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD_BED = _UxGT("Bed Heating Failed"); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD_CHAMBER = _UxGT("Chamber Heating Fail"); PROGMEM Language_Str MSG_ERR_REDUNDANT_TEMP = _UxGT("Err: REDUNDANT TEMP"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("THERMAL RUNAWAY"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("BED THERMAL RUNAWAY"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("CHAMBER T. RUNAWAY"); PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Err: MAXTEMP"); PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Err: MINTEMP"); - PROGMEM Language_Str MSG_ERR_MAXTEMP_BED = _UxGT("Err: MAXTEMP BED"); - PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("Err: MINTEMP BED"); - PROGMEM Language_Str MSG_ERR_MAXTEMP_CHAMBER = _UxGT("Err: MAXTEMP CHAMBER"); - PROGMEM Language_Str MSG_ERR_MINTEMP_CHAMBER = _UxGT("Err: MINTEMP CHAMBER"); PROGMEM Language_Str MSG_HALTED = _UxGT("PRINTER HALTED"); PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Please Reset"); PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("d"); // One character only @@ -468,6 +466,8 @@ namespace Language_en { PROGMEM Language_Str MSG_COOLING = _UxGT("Cooling..."); PROGMEM Language_Str MSG_BED_HEATING = _UxGT("Bed Heating..."); PROGMEM Language_Str MSG_BED_COOLING = _UxGT("Bed Cooling..."); + PROGMEM Language_Str MSG_PROBE_HEATING = _UxGT("Probe Heating..."); + PROGMEM Language_Str MSG_PROBE_COOLING = _UxGT("Probe Cooling..."); PROGMEM Language_Str MSG_CHAMBER_HEATING = _UxGT("Chamber Heating..."); PROGMEM Language_Str MSG_CHAMBER_COOLING = _UxGT("Chamber Cooling..."); PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Delta Calibration"); @@ -539,7 +539,6 @@ namespace Language_en { PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("Runout Dist mm"); PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Homing Failed"); PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Probing Failed"); - PROGMEM Language_Str MSG_M600_TOO_COLD = _UxGT("M600: Too Cold"); PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("CHOOSE FILAMENT"); PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); diff --git a/Marlin/src/lcd/language/language_es.h b/Marlin/src/lcd/language/language_es.h index 2b10bfe313..c77b12ee77 100644 --- a/Marlin/src/lcd/language/language_es.h +++ b/Marlin/src/lcd/language/language_es.h @@ -26,7 +26,6 @@ * * LCD Menu Messages * See also https://marlinfw.org/docs/development/lcd_language.html - * */ namespace Language_es { @@ -415,18 +414,12 @@ namespace Language_es { PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Total"); PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Cancelado - Endstop"); PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Calent. fallido"); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD_BED = _UxGT("Calent. cama fallido"); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD_CHAMBER = _UxGT("Calent. Cám. fallido"); PROGMEM Language_Str MSG_ERR_REDUNDANT_TEMP = _UxGT("Err: TEMP. REDUN."); PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("FUGA TÉRMICA"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("FUGA TÉRMICA CAMA"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("FUGA TÉRMICA CAMARA"); PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Err:TEMP. MÁX"); PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Err:TEMP. MIN"); - PROGMEM Language_Str MSG_ERR_MAXTEMP_BED = _UxGT("Err:TEMP. MÁX CAMA"); - PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("Err:TEMP. MIN CAMA"); - PROGMEM Language_Str MSG_ERR_MAXTEMP_CHAMBER = _UxGT("Err:TEMP. MÁX CÁMARA"); - PROGMEM Language_Str MSG_ERR_MINTEMP_CHAMBER = _UxGT("Err:TEMP. MIN CÁMARA"); PROGMEM Language_Str MSG_HALTED = _UxGT("IMPRESORA DETENIDA"); PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Por favor, reinicie"); PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("d"); // One character only @@ -506,7 +499,6 @@ namespace Language_es { PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("Dist. filamento mm"); PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Ir a origen Fallado"); PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Sondeo Fallado"); - PROGMEM Language_Str MSG_M600_TOO_COLD = _UxGT("M600: Muy Frio"); PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("ELIJE FILAMENTO"); PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); diff --git a/Marlin/src/lcd/language/language_eu.h b/Marlin/src/lcd/language/language_eu.h index 5b38299e76..7e35c6ee41 100644 --- a/Marlin/src/lcd/language/language_eu.h +++ b/Marlin/src/lcd/language/language_eu.h @@ -26,7 +26,6 @@ * * LCD Menu Messages * See also https://marlinfw.org/docs/development/lcd_language.html - * */ #define DISPLAY_CHARSET_ISO10646_1 @@ -244,8 +243,6 @@ namespace Language_eu { PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("TENP. KONTROL EZA"); PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Err: Tenp Maximoa"); PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Err: Tenp Minimoa"); - PROGMEM Language_Str MSG_ERR_MAXTEMP_BED = _UxGT("Err: Ohe Tenp Max"); - PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("Err: Ohe Tenp Min"); PROGMEM Language_Str MSG_HALTED = _UxGT("INPRIMA. GELDIRIK"); PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Berrabia. Mesedez"); PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("d"); // One character only @@ -278,8 +275,7 @@ namespace Language_eu { PROGMEM Language_Str MSG_INFO_BAUDRATE = _UxGT("Baudioak"); PROGMEM Language_Str MSG_INFO_PROTOCOL = _UxGT("Protokoloa"); PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Kabina Argia"); - PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS - = ; + PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Argiaren Distira"); #if LCD_WIDTH >= 20 PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Inprim. Zenbaketa"); PROGMEM Language_Str MSG_INFO_COMPLETED_PRINTS = _UxGT("Burututa"); @@ -310,7 +306,6 @@ namespace Language_eu { PROGMEM Language_Str MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Pita: "); PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Hasi. huts egin du"); PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Neurketak huts egin du"); - PROGMEM Language_Str MSG_M600_TOO_COLD = _UxGT("M600: hotzegi"); PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("Inprimagailu okerra"); diff --git a/Marlin/src/lcd/language/language_fi.h b/Marlin/src/lcd/language/language_fi.h index 77424df353..af7dd22af9 100644 --- a/Marlin/src/lcd/language/language_fi.h +++ b/Marlin/src/lcd/language/language_fi.h @@ -26,7 +26,6 @@ * * LCD Menu Messages * See also https://marlinfw.org/docs/development/lcd_language.html - * */ #define DISPLAY_CHARSET_ISO10646_1 diff --git a/Marlin/src/lcd/language/language_fr.h b/Marlin/src/lcd/language/language_fr.h index d403477eb0..714feeee99 100644 --- a/Marlin/src/lcd/language/language_fr.h +++ b/Marlin/src/lcd/language/language_fr.h @@ -26,7 +26,6 @@ * * LCD Menu Messages * See also https://marlinfw.org/docs/development/lcd_language.html - * */ #define DISPLAY_CHARSET_ISO10646_1 @@ -413,6 +412,8 @@ namespace Language_fr { PROGMEM Language_Str MSG_COOLING = _UxGT("Refroidissement"); PROGMEM Language_Str MSG_BED_HEATING = _UxGT("Lit en chauffe..."); PROGMEM Language_Str MSG_BED_COOLING = _UxGT("Refroid. du lit..."); + PROGMEM Language_Str MSG_PROBE_HEATING = _UxGT("Probe en chauffe..."); + PROGMEM Language_Str MSG_PROBE_COOLING = _UxGT("Refroid. Probe..."); PROGMEM Language_Str MSG_CHAMBER_HEATING = _UxGT("Chauffe caisson..."); PROGMEM Language_Str MSG_CHAMBER_COOLING = _UxGT("Refroid. caisson..."); PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Calibration Delta"); @@ -485,7 +486,6 @@ namespace Language_fr { PROGMEM Language_Str MSG_RUNOUT_SENSOR = _UxGT("Capteur fil."); PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Echec origine"); PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Echec sonde"); - PROGMEM Language_Str MSG_M600_TOO_COLD = _UxGT("M600: Trop froid"); PROGMEM Language_Str MSG_KILL_MMU2_FIRMWARE = _UxGT("MAJ firmware MMU!!"); PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("CHOISIR FILAMENT"); @@ -508,7 +508,7 @@ namespace Language_fr { PROGMEM Language_Str MSG_MMU2_RESETTING = _UxGT("Réinit. MMU..."); PROGMEM Language_Str MSG_MMU2_EJECT_RECOVER = _UxGT("Retrait, click"); - PROGMEM Language_Str MSG_MIX_COMPONENT_N = _UxGT("Composante ~"); + PROGMEM Language_Str MSG_MIX_COMPONENT_N = _UxGT("Composante ="); PROGMEM Language_Str MSG_MIXER = _UxGT("Mixeur"); PROGMEM Language_Str MSG_GRADIENT = _UxGT("Dégradé"); PROGMEM Language_Str MSG_FULL_GRADIENT = _UxGT("Dégradé complet"); diff --git a/Marlin/src/lcd/language/language_gl.h b/Marlin/src/lcd/language/language_gl.h index 4415fc5e1c..2fd4bf6975 100644 --- a/Marlin/src/lcd/language/language_gl.h +++ b/Marlin/src/lcd/language/language_gl.h @@ -26,7 +26,6 @@ * * LCD Menu Messages * See also https://marlinfw.org/docs/development/lcd_language.html - * */ #define DISPLAY_CHARSET_ISO10646_1 @@ -437,18 +436,12 @@ namespace Language_gl { 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_HALTED = _UxGT("IMPRESORA DETIDA"); PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Debe reiniciar!"); PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("d"); // One character only @@ -528,7 +521,6 @@ namespace Language_gl { PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("Dist mm Sensor Fil"); PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Fallo ao ir á Orixe"); PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Fallo ao Sondar"); - PROGMEM Language_Str MSG_M600_TOO_COLD = _UxGT("M600: Moi Frío"); PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("ESCOLLE FILAMENTO"); PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); diff --git a/Marlin/src/lcd/language/language_hr.h b/Marlin/src/lcd/language/language_hr.h index 4873f5c254..1b2ae41fce 100644 --- a/Marlin/src/lcd/language/language_hr.h +++ b/Marlin/src/lcd/language/language_hr.h @@ -26,7 +26,6 @@ * * LCD Menu Messages * See also https://marlinfw.org/docs/development/lcd_language.html - * */ #define DISPLAY_CHARSET_ISO10646_1 // use the better font on full graphic displays. diff --git a/Marlin/src/lcd/language/language_hu.h b/Marlin/src/lcd/language/language_hu.h index 182ed27072..f93e5ee4e2 100644 --- a/Marlin/src/lcd/language/language_hu.h +++ b/Marlin/src/lcd/language/language_hu.h @@ -29,7 +29,6 @@ * A Magyar fordítást készítette: AntoszHUN * * - * */ namespace Language_hu { @@ -439,18 +438,12 @@ namespace Language_hu { PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Teljes"); PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Végállás megszakítva!"); PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Fütés hiba!"); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD_BED = _UxGT("Ágy fütés hiba!"); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD_CHAMBER = _UxGT("Kamra fütés hiba!"); PROGMEM Language_Str MSG_ERR_REDUNDANT_TEMP = _UxGT("Hiba: SZÜKSÉGTELEN HÖFOK"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("FÜTÉS KIMARADÁS"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("ÁGY FÜTÉS KIMARADÁS"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("KAMRA FÜTÉS KIMARADÁS"); PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Hiba: MAX Höfok"); PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Hiba: MIN Höfok"); - PROGMEM Language_Str MSG_ERR_MAXTEMP_BED = _UxGT("Hiba: MAX ÁGY HÖFOK"); - PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("Hiba: MIN ÁGY HÖFOK"); - PROGMEM Language_Str MSG_ERR_MAXTEMP_CHAMBER = _UxGT("Hiba: MAX KAMRA HÖFOK"); - PROGMEM Language_Str MSG_ERR_MINTEMP_CHAMBER = _UxGT("Hiba: MIN KAMRA HÖFOK"); PROGMEM Language_Str MSG_HALTED = _UxGT("A NYOMTATÓ LEFAGYOTT"); PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Indítsd újra!"); PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("n"); // Csak egy karakter @@ -530,7 +523,6 @@ namespace Language_hu { PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("Túlfutás Táv. mm"); PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Tájolási hiba"); PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Szondázás hiba"); - PROGMEM Language_Str MSG_M600_TOO_COLD = _UxGT("M600: Túl hideg"); PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("SZÁLVÁLASZTÁS"); PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); diff --git a/Marlin/src/lcd/language/language_it.h b/Marlin/src/lcd/language/language_it.h index 43765d7c3a..a70463956a 100644 --- a/Marlin/src/lcd/language/language_it.h +++ b/Marlin/src/lcd/language/language_it.h @@ -26,7 +26,6 @@ * * LCD Menu Messages * See also https://marlinfw.org/docs/development/lcd_language.html - * */ #define DISPLAY_CHARSET_ISO10646_1 @@ -46,6 +45,7 @@ namespace Language_it { PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("Media inserito"); PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Media rimosso"); PROGMEM Language_Str MSG_MEDIA_WAITING = _UxGT("Aspettando media"); + PROGMEM Language_Str MSG_SD_INIT_FAIL = _UxGT("Inizial.SD fallita"); PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("Err.leggendo media"); PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("Dispos.USB rimosso"); PROGMEM Language_Str MSG_MEDIA_USB_FAILED = _UxGT("Avvio USB fallito"); @@ -221,6 +221,10 @@ namespace Language_it { PROGMEM Language_Str MSG_SET_LEDS_VIOLET = _UxGT("Viola"); PROGMEM Language_Str MSG_SET_LEDS_WHITE = _UxGT("Bianco"); PROGMEM Language_Str MSG_SET_LEDS_DEFAULT = _UxGT("Predefinito"); + PROGMEM Language_Str MSG_LED_CHANNEL_N = _UxGT("Canale ="); + PROGMEM Language_Str MSG_LEDS2 = _UxGT("Luci #2"); + PROGMEM Language_Str MSG_NEO2_PRESETS = _UxGT("Luce #2 Presets"); + PROGMEM Language_Str MSG_NEO2_BRIGHTNESS = _UxGT("Luminosità"); PROGMEM Language_Str MSG_CUSTOM_LEDS = _UxGT("Luci personalizzate"); PROGMEM Language_Str MSG_INTENSITY_R = _UxGT("Intensità rosso"); PROGMEM Language_Str MSG_INTENSITY_G = _UxGT("Intensità verde"); @@ -445,19 +449,13 @@ namespace Language_it { PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Babystep Z"); PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Totali"); PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Finecorsa annullati"); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Riscald. Fallito"); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD_BED = _UxGT("Risc. piatto fallito"); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD_CHAMBER = _UxGT("Risc. camera fallito"); + PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Risc.Fallito"); // Max 12 caratteri PROGMEM Language_Str MSG_ERR_REDUNDANT_TEMP = _UxGT("Err: TEMP RIDONDANTE"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("TEMP FUORI CONTROLLO"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("TEMP PIAT.FUORI CTRL"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("T.CAMERA FUORI CTRL"); PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Err: TEMP MASSIMA"); PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Err: TEMP MINIMA"); - PROGMEM Language_Str MSG_ERR_MAXTEMP_BED = _UxGT("Err: TEMP MAX PIATTO"); - PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("Err: TEMP MIN PIATTO"); - PROGMEM Language_Str MSG_ERR_MAXTEMP_CHAMBER = _UxGT("Err: TEMP MAX CAMERA"); - PROGMEM Language_Str MSG_ERR_MINTEMP_CHAMBER = _UxGT("Err: TEMP MIN CAMERA"); PROGMEM Language_Str MSG_HALTED = _UxGT("STAMPANTE FERMATA"); PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Riavviare prego"); PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("g"); // Un solo carattere @@ -467,6 +465,8 @@ namespace Language_it { PROGMEM Language_Str MSG_COOLING = _UxGT("Raffreddamento.."); PROGMEM Language_Str MSG_BED_HEATING = _UxGT("Risc. piatto..."); PROGMEM Language_Str MSG_BED_COOLING = _UxGT("Raffr. piatto..."); + PROGMEM Language_Str MSG_PROBE_HEATING = _UxGT("Risc. sonda..."); + PROGMEM Language_Str MSG_PROBE_COOLING = _UxGT("Raffr. sonda..."); PROGMEM Language_Str MSG_CHAMBER_HEATING = _UxGT("Risc. camera..."); PROGMEM Language_Str MSG_CHAMBER_COOLING = _UxGT("Raffr. camera..."); PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Calibraz. Delta"); @@ -537,7 +537,6 @@ namespace Language_it { PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("Dist mm filo term."); PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Home fallito"); PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Sondaggio fallito"); - PROGMEM Language_Str MSG_M600_TOO_COLD = _UxGT("M600:Troppo freddo"); PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("SCELTA FILAMENTO"); PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); @@ -561,7 +560,7 @@ namespace Language_it { PROGMEM Language_Str MSG_MMU2_EJECT_RECOVER = _UxGT("Rimuovi, click"); PROGMEM Language_Str MSG_MIX = _UxGT("Miscela"); - PROGMEM Language_Str MSG_MIX_COMPONENT_N = _UxGT("Componente ~"); + PROGMEM Language_Str MSG_MIX_COMPONENT_N = _UxGT("Componente ="); PROGMEM Language_Str MSG_MIXER = _UxGT("Miscelatore"); PROGMEM Language_Str MSG_GRADIENT = _UxGT("Gradiente"); PROGMEM Language_Str MSG_FULL_GRADIENT = _UxGT("Gradiente pieno"); @@ -588,6 +587,17 @@ namespace Language_it { PROGMEM Language_Str MSG_BAD_PAGE = _UxGT("Indice pag. errato"); PROGMEM Language_Str MSG_BAD_PAGE_SPEED = _UxGT("Vel. pag. errata"); + PROGMEM Language_Str MSG_EDIT_PASSWORD = _UxGT("Modif.password"); + PROGMEM Language_Str MSG_LOGIN_REQUIRED = _UxGT("Login richiesto"); + PROGMEM Language_Str MSG_PASSWORD_SETTINGS = _UxGT("Impostaz.password"); + PROGMEM Language_Str MSG_ENTER_DIGIT = _UxGT("Inserisci cifra"); + PROGMEM Language_Str MSG_CHANGE_PASSWORD = _UxGT("Imp./Modif.password"); + PROGMEM Language_Str MSG_REMOVE_PASSWORD = _UxGT("Elimina password"); + PROGMEM Language_Str MSG_PASSWORD_SET = _UxGT("La password è "); + PROGMEM Language_Str MSG_START_OVER = _UxGT("Ricominciare"); + PROGMEM Language_Str MSG_REMINDER_SAVE_SETTINGS = _UxGT("Ricordati di mem.!"); + PROGMEM Language_Str MSG_PASSWORD_REMOVED = _UxGT("Password eliminata"); + // // Le schermate di Cambio Filamento possono visualizzare fino a 3 linee su un display a 4 righe // ...o fino a 2 linee su un display a 3 righe. diff --git a/Marlin/src/lcd/language/language_jp_kana.h b/Marlin/src/lcd/language/language_jp_kana.h index 5f679dd49d..f1289123a4 100644 --- a/Marlin/src/lcd/language/language_jp_kana.h +++ b/Marlin/src/lcd/language/language_jp_kana.h @@ -27,7 +27,6 @@ * * LCD Menu Messages * See also https://marlinfw.org/docs/development/lcd_language.html - * */ //#define DISPLAY_CHARSET_ISO10646_KANA @@ -184,8 +183,6 @@ namespace Language_jp_kana { PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("ネツボウソウ"); // "THERMAL RUNAWAY" PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("エラー:サイコウオンチョウカ"); // "Err: MAXTEMP" PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("エラー:サイテイオンミマン"); // "Err: MINTEMP" - PROGMEM Language_Str MSG_ERR_MAXTEMP_BED = _UxGT("エラー:ベッド サイコウオンチョウカ"); // "Err: MAXTEMP BED" - PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("エラー:ベッド サイテイオンミマン"); // "Err: MINTEMP BED" PROGMEM Language_Str MSG_HALTED = _UxGT("プリンターハテイシシマシタ"); // "PRINTER HALTED" PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("リセットシテクダサイ"); // "Please reset" PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("d"); // One character only diff --git a/Marlin/src/lcd/language/language_ko_KR.h b/Marlin/src/lcd/language/language_ko_KR.h index 2ffcdf7b41..1ab03dcf57 100644 --- a/Marlin/src/lcd/language/language_ko_KR.h +++ b/Marlin/src/lcd/language/language_ko_KR.h @@ -26,7 +26,6 @@ * * LCD Menu Messages * See also https://marlinfw.org/docs/development/lcd_language.html - * */ namespace Language_ko_KR { using namespace Language_en; // Inherit undefined strings from English diff --git a/Marlin/src/lcd/language/language_nl.h b/Marlin/src/lcd/language/language_nl.h index c8c79e472a..7b6c16b3b3 100644 --- a/Marlin/src/lcd/language/language_nl.h +++ b/Marlin/src/lcd/language/language_nl.h @@ -26,7 +26,6 @@ * * LCD Menu Messages * See also https://marlinfw.org/docs/development/lcd_language.html - * */ #define DISPLAY_CHARSET_ISO10646_1 @@ -164,8 +163,6 @@ namespace Language_nl { PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("Therm. wegloop"); PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Err: Max. temp"); PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Err: Min. temp"); - PROGMEM Language_Str MSG_ERR_MAXTEMP_BED = _UxGT("Err: Max.tmp bed"); - PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("Err: Min.tmp bed"); PROGMEM Language_Str MSG_HALTED = _UxGT("PRINTER GESTOPT"); PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Reset A.U.B."); PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("d"); // One character only. Keep English standard diff --git a/Marlin/src/lcd/language/language_pl.h b/Marlin/src/lcd/language/language_pl.h index 79190ddfcb..770c872a40 100644 --- a/Marlin/src/lcd/language/language_pl.h +++ b/Marlin/src/lcd/language/language_pl.h @@ -26,7 +26,6 @@ * * LCD Menu Messages * See also https://marlinfw.org/docs/development/lcd_language.html - * */ #define DISPLAY_CHARSET_ISO10646_PL @@ -385,18 +384,12 @@ namespace Language_pl { PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Łącznie"); PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Błąd krańcówki"); PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Rozgrz. nieudane"); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD_BED = _UxGT("Rozgrz. stołu nieudane"); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD_CHAMBER = _UxGT("Rozgrz. komory nieudane"); PROGMEM Language_Str MSG_ERR_REDUNDANT_TEMP = _UxGT("Błąd temperatury"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("ZANIK TEMPERATURY"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("ZANIK TEMP. STOŁU"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("ZANIK TEMP.KOMORY"); PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Błąd: MAXTEMP"); PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Błąd: MINTEMP"); - PROGMEM Language_Str MSG_ERR_MAXTEMP_BED = _UxGT("Błąd: MAXTEMP STÓŁ"); - PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("Błąd: MINTEMP STÓŁ"); - PROGMEM Language_Str MSG_ERR_MAXTEMP_CHAMBER = _UxGT("Błąd: MAXTEMP KOMORA"); - PROGMEM Language_Str MSG_ERR_MINTEMP_CHAMBER = _UxGT("Błąd: MINTEMP KOMORA"); PROGMEM Language_Str MSG_HALTED = _UxGT("Drukarka zatrzym."); PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Proszę zresetować"); PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("d"); // One character only @@ -476,7 +469,6 @@ namespace Language_pl { PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("Dystans do czujnika mm"); PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Zerowanie nieudane"); PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Sondowanie nieudane"); - PROGMEM Language_Str MSG_M600_TOO_COLD = _UxGT("M600: za zimne"); PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("WYBIERZ FILAMENT"); PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); @@ -500,7 +492,7 @@ namespace Language_pl { PROGMEM Language_Str MSG_MMU2_EJECT_RECOVER = _UxGT("Usuń, kliknij"); PROGMEM Language_Str MSG_MIX = _UxGT("Miks"); - PROGMEM Language_Str MSG_MIX_COMPONENT_N = _UxGT("Komponent ~"); + PROGMEM Language_Str MSG_MIX_COMPONENT_N = _UxGT("Komponent ="); PROGMEM Language_Str MSG_MIXER = _UxGT("Mikser"); PROGMEM Language_Str MSG_GRADIENT = _UxGT("Gradient"); PROGMEM Language_Str MSG_FULL_GRADIENT = _UxGT("Pełny gradient"); diff --git a/Marlin/src/lcd/language/language_pt.h b/Marlin/src/lcd/language/language_pt.h index 1180649c98..56426c0321 100644 --- a/Marlin/src/lcd/language/language_pt.h +++ b/Marlin/src/lcd/language/language_pt.h @@ -27,7 +27,6 @@ * * LCD Menu Messages * See also https://marlinfw.org/docs/development/lcd_language.html - * */ #define DISPLAY_CHARSET_ISO10646_1 @@ -150,8 +149,6 @@ namespace Language_pt { PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Aquecimento falhou"); PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Err: T Máxima"); PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Err: T Mínima"); - PROGMEM Language_Str MSG_ERR_MAXTEMP_BED = _UxGT("Err: T Base Máxima"); - PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("Err: T Base Mínima"); PROGMEM Language_Str MSG_HEATING = _UxGT("Aquecendo..."); PROGMEM Language_Str MSG_BED_HEATING = _UxGT("Aquecendo base..."); PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Calibração Delta"); diff --git a/Marlin/src/lcd/language/language_pt_br.h b/Marlin/src/lcd/language/language_pt_br.h index e0a52fc390..cf2f7a0cce 100644 --- a/Marlin/src/lcd/language/language_pt_br.h +++ b/Marlin/src/lcd/language/language_pt_br.h @@ -27,7 +27,6 @@ * * LCD Menu Messages * See also https://marlinfw.org/docs/development/lcd_language.html - * */ namespace Language_pt_br { using namespace Language_en; // Inherit undefined strings from English @@ -351,18 +350,12 @@ namespace Language_pt_br { PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Total"); PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Abortar Fim de Curso"); PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Aquecimento falhou"); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD_BED = _UxGT("Aquecer mesa falhou"); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD_CHAMBER = _UxGT("Aquecer câmara falhou"); PROGMEM Language_Str MSG_ERR_REDUNDANT_TEMP = _UxGT("Erro:Temp Redundante"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("ESCAPE TÉRMICO"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("ESCAPE TÉRMICO MESA"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("ESCAPE TÉRMICO CAMARA"); PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Erro:Temp Máxima"); PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Erro:Temp Mínima"); - PROGMEM Language_Str MSG_ERR_MAXTEMP_BED = _UxGT("Erro:Temp Mesa Máx"); - PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("Erro:Temp Mesa Mín"); - PROGMEM Language_Str MSG_ERR_MAXTEMP_CHAMBER = _UxGT("Erro:Temp Câmara Máx"); - PROGMEM Language_Str MSG_ERR_MINTEMP_CHAMBER = _UxGT("Erro:Temp Câmara Min"); PROGMEM Language_Str MSG_HALTED = _UxGT("IMPRESSORA PAROU"); PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Favor resetar"); PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("d"); @@ -434,7 +427,6 @@ namespace Language_pt_br { PROGMEM Language_Str MSG_RUNOUT_SENSOR = _UxGT("Sensor filamento"); PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Falha ao ir à origem"); PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Falha ao sondar"); - PROGMEM Language_Str MSG_M600_TOO_COLD = _UxGT("M600: Muito frio"); PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("ESCOLHER FILAMENTO"); PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); diff --git a/Marlin/src/lcd/language/language_ro.h b/Marlin/src/lcd/language/language_ro.h index 39e5cb9e2c..d71471a09d 100644 --- a/Marlin/src/lcd/language/language_ro.h +++ b/Marlin/src/lcd/language/language_ro.h @@ -442,18 +442,12 @@ namespace Language_ro { PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Total"); PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Endstop Abort"); PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Heating Failed"); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD_BED = _UxGT("Bed Heating Failed"); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD_CHAMBER = _UxGT("Chamber Heating Fail"); PROGMEM Language_Str MSG_ERR_REDUNDANT_TEMP = _UxGT("Err: REDUNDANT TEMP"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("THERMAL RUNAWAY"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("BED THERMAL RUNAWAY"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("CHAMBER T. RUNAWAY"); PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Err: MAXTEMP"); PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Err: MINTEMP"); - PROGMEM Language_Str MSG_ERR_MAXTEMP_BED = _UxGT("Err: MAXTEMP BED"); - PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("Err: MINTEMP BED"); - PROGMEM Language_Str MSG_ERR_MAXTEMP_CHAMBER = _UxGT("Err: MAXTEMP CHAMBER"); - PROGMEM Language_Str MSG_ERR_MINTEMP_CHAMBER = _UxGT("Err: MINTEMP CHAMBER"); PROGMEM Language_Str MSG_HALTED = _UxGT("PRINTER HALTED"); PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Please Reset"); PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("d"); // One character only @@ -534,7 +528,6 @@ namespace Language_ro { PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("Runout Dist mm"); PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Homing Failed"); PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Probing Failed"); - PROGMEM Language_Str MSG_M600_TOO_COLD = _UxGT("M600: Too Cold"); PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("CHOOSE FILAMENT"); PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); diff --git a/Marlin/src/lcd/language/language_ru.h b/Marlin/src/lcd/language/language_ru.h index 6228e92346..0953bb8a71 100644 --- a/Marlin/src/lcd/language/language_ru.h +++ b/Marlin/src/lcd/language/language_ru.h @@ -26,7 +26,6 @@ * * LCD Menu Messages * See also https://marlinfw.org/docs/development/lcd_language.html - * */ #define DISPLAY_CHARSET_ISO10646_5 @@ -530,18 +529,12 @@ namespace Language_ru { PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Сумарно"); PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Сработал концевик"); PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Разогрев не удался"); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD_BED = _UxGT("Сбой нагрева стола"); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD_CHAMBER = _UxGT("Сбой нагрева камеры"); PROGMEM Language_Str MSG_ERR_REDUNDANT_TEMP = _UxGT("Ошибка:Избыточная Т"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("УТЕЧКА ТЕПЛА"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("УТЕЧКА ТЕПЛА СТОЛА"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("УТЕЧКА ТЕПЛА КАМЕРЫ"); PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Ошибка: Т макс."); PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Ошибка: Т мин."); - PROGMEM Language_Str MSG_ERR_MAXTEMP_BED = _UxGT("Ошибка: Т стола макс"); - PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("Ошибка: Т стола мин."); - PROGMEM Language_Str MSG_ERR_MAXTEMP_CHAMBER = _UxGT("Ошибка:Т камеры макс"); - PROGMEM Language_Str MSG_ERR_MINTEMP_CHAMBER = _UxGT("Ошибка:Т камеры мин."); PROGMEM Language_Str MSG_HALTED = _UxGT("ПРИНТЕР ОСТАНОВЛЕН"); PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Сделайте сброс"); PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("д"); // One character only @@ -642,7 +635,6 @@ namespace Language_ru { PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("До конца, мм"); PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Ошибка парковки"); PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Ошибка зондирования"); - PROGMEM Language_Str MSG_M600_TOO_COLD = _UxGT("M600: Низкая Т") LCD_STR_DEGREE; PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("ВЫБИРЕТЕ ФИЛАМЕНТ"); PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("Настройки MMU"); diff --git a/Marlin/src/lcd/language/language_sk.h b/Marlin/src/lcd/language/language_sk.h index 736e2069d9..8a59bfc673 100644 --- a/Marlin/src/lcd/language/language_sk.h +++ b/Marlin/src/lcd/language/language_sk.h @@ -30,7 +30,6 @@ * * Translated by Michal Holeš, Farma MaM * https://www.facebook.com/farmamam - * */ #define DISPLAY_CHARSET_ISO10646_SK @@ -435,18 +434,12 @@ namespace Language_sk { PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Celkom"); PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Zastavenie Endstop"); PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Chyba ohrevu"); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD_BED = _UxGT("Chyba ohrevu podl."); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD_CHAMBER = _UxGT("Chyba ohrevu komory"); PROGMEM Language_Str MSG_ERR_REDUNDANT_TEMP = _UxGT("Chyba: REDUND. TEP."); PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("TEPLOTNÝ SKOK"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("TEPLOTNÝ SKOK PODL."); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("TEPLOTNÝ SKOK KOMO."); PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Chyba: MAXTEMP"); PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Chyba: MINTEMP"); - PROGMEM Language_Str MSG_ERR_MAXTEMP_BED = _UxGT("Chyba: MAXTEMP PODL."); - PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("Chyba: MINTEMP PODL."); - PROGMEM Language_Str MSG_ERR_MAXTEMP_CHAMBER = _UxGT("Chyba: MAXTEMP KOMO."); - PROGMEM Language_Str MSG_ERR_MINTEMP_CHAMBER = _UxGT("Chyba: MINTEMP KOMO."); PROGMEM Language_Str MSG_HALTED = _UxGT("TLAČIAREŇ ZASTAVENÁ"); PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Reštartuje ju"); PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("d"); @@ -527,7 +520,6 @@ namespace Language_sk { PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("Vzd. mm fil. senz."); PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Parkovanie zlyhalo"); PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Kalibrácia zlyhala"); - PROGMEM Language_Str MSG_M600_TOO_COLD = _UxGT("M600: Príliš studený"); PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("VYBERTE FILAMENT"); PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU2"); @@ -551,7 +543,7 @@ namespace Language_sk { PROGMEM Language_Str MSG_MMU2_EJECT_RECOVER = _UxGT("Odstráňte, kliknite"); PROGMEM Language_Str MSG_MIX = _UxGT("Mix"); - PROGMEM Language_Str MSG_MIX_COMPONENT_N = _UxGT("Zložka ~"); + PROGMEM Language_Str MSG_MIX_COMPONENT_N = _UxGT("Zložka ="); PROGMEM Language_Str MSG_MIXER = _UxGT("Mixér"); PROGMEM Language_Str MSG_GRADIENT = _UxGT("Gradient"); PROGMEM Language_Str MSG_FULL_GRADIENT = _UxGT("Plný gradient"); diff --git a/Marlin/src/lcd/language/language_test.h b/Marlin/src/lcd/language/language_test.h index b15f20619e..16cafbebbe 100644 --- a/Marlin/src/lcd/language/language_test.h +++ b/Marlin/src/lcd/language/language_test.h @@ -26,7 +26,6 @@ * * LCD Menu Messages * See also https://marlinfw.org/docs/development/lcd_language.html - * */ // Select ONE of the following Mappers. diff --git a/Marlin/src/lcd/language/language_tr.h b/Marlin/src/lcd/language/language_tr.h index bb68a61717..90208befe7 100644 --- a/Marlin/src/lcd/language/language_tr.h +++ b/Marlin/src/lcd/language/language_tr.h @@ -30,7 +30,6 @@ * Bu çeviri dosyasındaki sorunlar ve düzeltmeler için iletişim; * Contact for issues and corrections in this translation file; * Yücel Temel - (info@elektromanyetix.com) - https://elektromanyetix.com/ - * */ #define DISPLAY_CHARSET_ISO10646_TR @@ -414,18 +413,12 @@ namespace Language_tr { PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Toplam"); PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Endstop iptal"); PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Isınma başarısız"); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD_BED = _UxGT("Yatak Isınma Başrsız"); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD_CHAMBER = _UxGT("Oda Isıtma Hatası"); PROGMEM Language_Str MSG_ERR_REDUNDANT_TEMP = _UxGT("Hata: Sıcaklık Aşımı"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("TERMAL PROBLEM"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("TABLA TERMAL PROBLEM"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("ODA TERMAL PROBLEM"); PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Hata: MAX.SICAKLIK"); PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Hata: MIN.SICAKLIK"); - PROGMEM Language_Str MSG_ERR_MAXTEMP_BED = _UxGT("Hata: MAX.SIC. TABLA"); - PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("Hata: MIN.SIC. TABLA"); - PROGMEM Language_Str MSG_ERR_MAXTEMP_CHAMBER = _UxGT("Hata: MAX.SIC ODA"); - PROGMEM Language_Str MSG_ERR_MINTEMP_CHAMBER = _UxGT("Hata: MIN.SIC ODA"); PROGMEM Language_Str MSG_HALTED = _UxGT("YAZICI DURDURULDU"); PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Lütfen Resetleyin"); PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("G"); // One character only @@ -502,7 +495,6 @@ namespace Language_tr { PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("Aşınma Farkı mm"); PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Sıfırlama Başarısız"); PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Probing Başarısız"); - PROGMEM Language_Str MSG_M600_TOO_COLD = _UxGT("M600: Çok Soğuk"); PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("FILAMAN SEÇ"); PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); diff --git a/Marlin/src/lcd/language/language_uk.h b/Marlin/src/lcd/language/language_uk.h index 686657246f..54171e1ebc 100644 --- a/Marlin/src/lcd/language/language_uk.h +++ b/Marlin/src/lcd/language/language_uk.h @@ -26,7 +26,6 @@ * * LCD Menu Messages * See also https://marlinfw.org/docs/development/lcd_language.html - * */ #define DISPLAY_CHARSET_ISO10646_5 @@ -524,18 +523,12 @@ namespace Language_uk { PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Сумарно"); PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Кінцевик спрацював"); PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Збій нагріву"); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD_BED = _UxGT("Збій нагріву столу"); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD_CHAMBER = _UxGT("Збій нагріву камери"); PROGMEM Language_Str MSG_ERR_REDUNDANT_TEMP = _UxGT("ЗАВИЩЕНА Т") LCD_STR_DEGREE; PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("ВИТІК ТЕПЛА"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("ВИТІК ТЕПЛА СТОЛУ"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("ВИТІК ТЕПЛА КАМЕРИ"); PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("ПЕРЕГРІВ"); PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("МІНІМАЛЬНА Т") LCD_STR_DEGREE; - PROGMEM Language_Str MSG_ERR_MAXTEMP_BED = _UxGT("ПЕРЕГРІВ СТОЛУ"); - PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("МІНІМАЛЬНА Т") LCD_STR_DEGREE _UxGT(" СТОЛУ"); - PROGMEM Language_Str MSG_ERR_MAXTEMP_CHAMBER = _UxGT("ПЕРЕГРІВ КАМЕРИ"); - PROGMEM Language_Str MSG_ERR_MINTEMP_CHAMBER = _UxGT("МІНІМАЛЬНА Т") LCD_STR_DEGREE _UxGT(" КАМЕРИ"); PROGMEM Language_Str MSG_HALTED = _UxGT("ПРИНТЕР ЗУПИНЕНО"); PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Перезавантажте"); PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("д"); // One character only @@ -652,7 +645,6 @@ namespace Language_uk { #endif PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Помилка паркування"); PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Помилка зондування"); - PROGMEM Language_Str MSG_M600_TOO_COLD = _UxGT("M600: низька Т") LCD_STR_DEGREE; PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("ОБЕРІТЬ ПРУТОК"); PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("Налаштування MMU"); diff --git a/Marlin/src/lcd/language/language_vi.h b/Marlin/src/lcd/language/language_vi.h index 227a4950f3..fb60a5d821 100644 --- a/Marlin/src/lcd/language/language_vi.h +++ b/Marlin/src/lcd/language/language_vi.h @@ -26,7 +26,6 @@ * * LCD Menu Messages * See also https://marlinfw.org/docs/development/lcd_language.html - * */ namespace Language_vi { using namespace Language_en; // Inherit undefined strings from English @@ -330,14 +329,11 @@ namespace Language_vi { PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Nhít Z"); PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Hủy bỏ công tắc"); // Endstop abort PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Sưởi đầu phun không thành công"); // Heating failed - PROGMEM Language_Str MSG_HEATING_FAILED_LCD_BED = _UxGT("Sưởi bàn không thành công"); // Bed heating failed PROGMEM Language_Str MSG_ERR_REDUNDANT_TEMP = _UxGT("Điều sai: nhiệt độ dư"); // Err: REDUNDANT TEMP PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("Vấn đề nhiệt"); // THERMAL RUNAWAY | problem PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("Vấn đề nhiệt bàn"); // BED THERMAL RUNAWAY PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Điều sai: nhiệt độ tối đa"); // Err: MAXTEMP PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Điều sai: nhiệt độ tối thiểu"); // Err: MINTEMP - PROGMEM Language_Str MSG_ERR_MAXTEMP_BED = _UxGT("Điều sai: nhiệt độ bàn tối đa"); // Err: MAXTEMP BED - PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("Điều sai: nhiệt độ bàn tối thiểu"); // Err: MINTEMP BED PROGMEM Language_Str MSG_HALTED = _UxGT("MÁY IN Đà DỪNG LẠI"); // PRINTER HALTED PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Xin bặt lại"); // Please reset PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("n"); // d - ngày - One character only @@ -406,7 +402,6 @@ namespace Language_vi { PROGMEM Language_Str MSG_RUNOUT_SENSOR_ENABLE = _UxGT("Cảm Biến Hết"); // Runout Sensor PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("Sự nhà không thành công"); // Homing failed PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT(" không thành công"); // Probing failed - PROGMEM Language_Str MSG_M600_TOO_COLD = _UxGT("M600: Quá lạnh"); // // Filament Change screens show up to 3 lines on a 4-line display diff --git a/Marlin/src/lcd/language/language_zh_CN.h b/Marlin/src/lcd/language/language_zh_CN.h index cf772caaef..53dac64c0b 100644 --- a/Marlin/src/lcd/language/language_zh_CN.h +++ b/Marlin/src/lcd/language/language_zh_CN.h @@ -26,7 +26,6 @@ * * LCD Menu Messages * See also https://marlinfw.org/docs/development/lcd_language.html - * */ namespace Language_zh_CN { using namespace Language_en; // Inherit undefined strings from English @@ -441,18 +440,12 @@ namespace Language_zh_CN { PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("总计"); PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("挡块终止"); //"Endstop abort" PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("加热失败"); //"Heating failed" - PROGMEM Language_Str MSG_HEATING_FAILED_LCD_BED = _UxGT("热床加热失败"); - PROGMEM Language_Str MSG_HEATING_FAILED_LCD_CHAMBER = _UxGT("机箱加热失败"); PROGMEM Language_Str MSG_ERR_REDUNDANT_TEMP = _UxGT("错误:冗余温度"); //"Err: REDUNDANT TEMP" PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("温控失控"); //"THERMAL RUNAWAY" PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("热床热量失控"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("机箱热量失控"); PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("错误:最高温度"); //"Err: MAXTEMP" PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("错误:最低温度"); //"Err: MINTEMP" - PROGMEM Language_Str MSG_ERR_MAXTEMP_BED = _UxGT("错误:最高热床温度"); //"Err: MAXTEMP BED" - PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("错误:最低热床温度"); //"Err: MINTEMP BED" - PROGMEM Language_Str MSG_ERR_MAXTEMP_CHAMBER = _UxGT("错误:最高机箱温度"); - PROGMEM Language_Str MSG_ERR_MINTEMP_CHAMBER = _UxGT("错误:最低机箱温度"); PROGMEM Language_Str MSG_HALTED = _UxGT("打印停机"); //"PRINTER HALTED" PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("请重置"); //"Please reset" PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("天"); //"d" // One character only @@ -534,7 +527,6 @@ namespace Language_zh_CN { PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("断料距离mm"); PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("归原位失败"); // "Homing failed" PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("探针探测失败"); // "Probing failed" - PROGMEM Language_Str MSG_M600_TOO_COLD = _UxGT("M600: 太凉"); // "M600: Too cold" PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("选择料"); PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); diff --git a/Marlin/src/lcd/language/language_zh_TW.h b/Marlin/src/lcd/language/language_zh_TW.h index 94a7944b35..7f1fce649e 100644 --- a/Marlin/src/lcd/language/language_zh_TW.h +++ b/Marlin/src/lcd/language/language_zh_TW.h @@ -26,7 +26,6 @@ * * LCD Menu Messages * See also https://marlinfw.org/docs/development/lcd_language.html - * */ namespace Language_zh_TW { using namespace Language_en; // Inherit undefined strings from English @@ -382,18 +381,12 @@ namespace Language_zh_TW { PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("總計"); //"Total" PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("擋塊終止"); //"Endstop abort" PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("加熱失敗"); //"Heating failed" - PROGMEM Language_Str MSG_HEATING_FAILED_LCD_BED = _UxGT("熱床加熱失敗"); //"Bed Heating Failed" - PROGMEM Language_Str MSG_HEATING_FAILED_LCD_CHAMBER = _UxGT("機箱加熱失敗"); //"Chamber Heating Fail" PROGMEM Language_Str MSG_ERR_REDUNDANT_TEMP = _UxGT("錯誤:冗餘溫度"); //"Err: REDUNDANT TEMP" PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("溫度失控"); //"THERMAL RUNAWAY" PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("熱床溫度失控"); //"BED THERMAL RUNAWAY" PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("機箱溫度失控"); //"CHAMBER T. RUNAWAY" PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("錯誤:最高溫度"); //"Err: MAXTEMP" PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("錯誤:最低溫度"); //"Err: MINTEMP" - PROGMEM Language_Str MSG_ERR_MAXTEMP_BED = _UxGT("錯誤:最高熱床溫度"); //"Err: MAXTEMP BED" - PROGMEM Language_Str MSG_ERR_MINTEMP_BED = _UxGT("錯誤:最低熱床溫度"); //"Err: MINTEMP BED" - PROGMEM Language_Str MSG_ERR_MAXTEMP_CHAMBER = _UxGT("錯誤:最高機箱溫度"); //"Err: MAXTEMP CHAMBER" - PROGMEM Language_Str MSG_ERR_MINTEMP_CHAMBER = _UxGT("錯誤:最低機箱溫度"); //"Err: MINTEMP CHAMBER" PROGMEM Language_Str MSG_HALTED = _UxGT("印表機停機"); //"PRINTER HALTED" PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("請重置"); //"Please reset" PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("天"); //"d" // One character only @@ -474,7 +467,6 @@ namespace Language_zh_TW { PROGMEM Language_Str MSG_RUNOUT_DISTANCE_MM = _UxGT("絲距離mm"); //"Runout Dist mm" PROGMEM Language_Str MSG_KILL_HOMING_FAILED = _UxGT("歸原位失敗"); // "Homing failed" PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("探針探測失敗"); // "Probing failed" - PROGMEM Language_Str MSG_M600_TOO_COLD = _UxGT("M600: 太冷"); // "M600: Too cold" // // Filament Change screens show up to 3 lines on a 4-line display diff --git a/Marlin/src/lcd/lcdprint.cpp b/Marlin/src/lcd/lcdprint.cpp index 0f7f945a99..e381c590f5 100644 --- a/Marlin/src/lcd/lcdprint.cpp +++ b/Marlin/src/lcd/lcdprint.cpp @@ -26,7 +26,7 @@ #include "../inc/MarlinConfigPre.h" -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #include "lcdprint.h" @@ -57,7 +57,10 @@ lcd_uint_t lcd_put_u8str_ind_P(PGM_P const pstr, const int8_t ind, PGM_P const i PGM_P const b = ind == -2 ? GET_TEXT(MSG_CHAMBER) : GET_TEXT(MSG_BED); n -= lcd_put_u8str_max_P(b, n * (MENU_FONT_WIDTH)) / (MENU_FONT_WIDTH); } - if (n) n -= lcd_put_u8str_max_P((PGM_P)p, n * (MENU_FONT_WIDTH)) / (MENU_FONT_WIDTH); + if (n) { + n -= lcd_put_u8str_max_P((PGM_P)p, n * (MENU_FONT_WIDTH)) / (MENU_FONT_WIDTH); + break; + } } else if (ch == '$' && inStr) { n -= lcd_put_u8str_max_P(inStr, n * (MENU_FONT_WIDTH)) / (MENU_FONT_WIDTH); @@ -70,4 +73,4 @@ lcd_uint_t lcd_put_u8str_ind_P(PGM_P const pstr, const int8_t ind, PGM_P const i return n; } -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD diff --git a/Marlin/src/lcd/lcdprint.h b/Marlin/src/lcd/lcdprint.h index 031d467bf9..14df5309d7 100644 --- a/Marlin/src/lcd/lcdprint.h +++ b/Marlin/src/lcd/lcdprint.h @@ -34,7 +34,7 @@ #include "../inc/MarlinConfig.h" -#if HAS_GRAPHICAL_LCD +#if HAS_MARLINUI_U8GLIB #include "dogm/u8g_fontutf8.h" typedef u8g_uint_t lcd_uint_t; diff --git a/Marlin/src/lcd/menu/menu.cpp b/Marlin/src/lcd/menu/menu.cpp index e6739a135c..5d67410351 100644 --- a/Marlin/src/lcd/menu/menu.cpp +++ b/Marlin/src/lcd/menu/menu.cpp @@ -34,10 +34,6 @@ #include "../../libs/buzzer.h" #endif -#if WATCH_HOTENDS || WATCH_BED - #include "../../module/temperature.h" -#endif - #if ENABLED(BABYSTEP_ZPROBE_OFFSET) #include "../../module/probe.h" #endif @@ -217,14 +213,14 @@ void MarlinUI::goto_screen(screenFunc_t screen, const uint16_t encoder/*=0*/, co clear_lcd(); // Re-initialize custom characters that may be re-used - #if HAS_CHARACTER_LCD + #if HAS_MARLINUI_HD44780 if (TERN1(AUTO_BED_LEVELING_UBL, !ubl.lcd_map_control)) set_custom_characters(on_status_screen() ? CHARSET_INFO : CHARSET_MENU); #endif refresh(LCDVIEW_CALL_REDRAW_NEXT); screen_changed = true; - TERN_(HAS_GRAPHICAL_LCD, drawing_screen = false); + TERN_(HAS_MARLINUI_U8GLIB, drawing_screen = false); TERN_(HAS_LCD_MENU, encoder_direction_normal()); @@ -347,8 +343,10 @@ void scroll_screen(const uint8_t limit, const bool is_menu) { #endif // BABYSTEP_ZPROBE_OFFSET void _lcd_draw_homing() { - constexpr uint8_t line = (LCD_HEIGHT - 1) / 2; - if (ui.should_draw()) MenuItem_static::draw(line, GET_TEXT(MSG_LEVEL_BED_HOMING)); + if (ui.should_draw()) { + constexpr uint8_t line = (LCD_HEIGHT - 1) / 2; + MenuItem_static::draw(line, GET_TEXT(MSG_LEVEL_BED_HOMING)); + } } #if ENABLED(LCD_BED_LEVELING) || (HAS_LEVELING && DISABLED(SLIM_LCD_MENUS)) diff --git a/Marlin/src/lcd/menu/menu.h b/Marlin/src/lcd/menu/menu.h index d692144464..5248662823 100644 --- a/Marlin/src/lcd/menu/menu.h +++ b/Marlin/src/lcd/menu/menu.h @@ -39,7 +39,7 @@ typedef void (*selectFunc_t)(); #define SS_INVERT 0x02 #define SS_DEFAULT SS_CENTER -#if HAS_GRAPHICAL_LCD && EITHER(BABYSTEP_ZPROBE_GFX_OVERLAY, MESH_EDIT_GFX_OVERLAY) +#if HAS_MARLINUI_U8GLIB && EITHER(BABYSTEP_ZPROBE_GFX_OVERLAY, MESH_EDIT_GFX_OVERLAY) void _lcd_zoffset_overlay_gfx(const float zvalue); #endif @@ -215,7 +215,7 @@ void _lcd_draw_homing(); void line_to_z(const float &z); #endif -#if HAS_GRAPHICAL_LCD && EITHER(BABYSTEP_ZPROBE_GFX_OVERLAY, MESH_EDIT_GFX_OVERLAY) +#if HAS_MARLINUI_U8GLIB && EITHER(BABYSTEP_ZPROBE_GFX_OVERLAY, MESH_EDIT_GFX_OVERLAY) void _lcd_zoffset_overlay_gfx(const float zvalue); #endif diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index 9978bc7eab..5bca89141f 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -111,7 +111,7 @@ void menu_backlash(); #if ENABLED(LIN_ADVANCE) #if EXTRUDERS == 1 EDIT_ITEM(float42_52, MSG_ADVANCE_K, &planner.extruder_advance_K[0], 0, 999); - #elif EXTRUDERS > 1 + #elif HAS_MULTI_EXTRUDER LOOP_L_N(n, EXTRUDERS) EDIT_ITEM_N(float42_52, n, MSG_ADVANCE_K_E, &planner.extruder_advance_K[n], 0, 999); #endif @@ -122,7 +122,7 @@ void menu_backlash(); #if ENABLED(VOLUMETRIC_EXTRUDER_LIMIT) EDIT_ITEM_FAST(float42_52, MSG_VOLUMETRIC_LIMIT, &planner.volumetric_extruder_limit[active_extruder], 0.0f, 20.0f, planner.calculate_volumetric_extruder_limits); - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER LOOP_L_N(n, EXTRUDERS) EDIT_ITEM_FAST_N(float42_52, n, MSG_VOLUMETRIC_LIMIT_E, &planner.volumetric_extruder_limit[n], 0.0f, 20.00f, planner.calculate_volumetric_extruder_limits); #endif @@ -130,7 +130,7 @@ void menu_backlash(); if (parser.volumetric_enabled) { EDIT_ITEM_FAST(float43, MSG_FILAMENT_DIAM, &planner.filament_size[active_extruder], 1.5f, 3.25f, planner.calculate_volumetric_multipliers); - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER LOOP_L_N(n, EXTRUDERS) EDIT_ITEM_FAST_N(float43, n, MSG_FILAMENT_DIAM_E, &planner.filament_size[n], 1.5f, 3.25f, planner.calculate_volumetric_multipliers); #endif @@ -141,13 +141,13 @@ void menu_backlash(); constexpr float extrude_maxlength = TERN(PREVENT_LENGTHY_EXTRUDE, EXTRUDE_MAXLENGTH, 999); EDIT_ITEM_FAST(float3, MSG_FILAMENT_UNLOAD, &fc_settings[active_extruder].unload_length, 0, extrude_maxlength); - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER LOOP_L_N(n, EXTRUDERS) EDIT_ITEM_FAST_N(float3, n, MSG_FILAMENTUNLOAD_E, &fc_settings[n].unload_length, 0, extrude_maxlength); #endif EDIT_ITEM_FAST(float3, MSG_FILAMENT_LOAD, &fc_settings[active_extruder].load_length, 0, extrude_maxlength); - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER LOOP_L_N(n, EXTRUDERS) EDIT_ITEM_FAST_N(float3, n, MSG_FILAMENTLOAD_E, &fc_settings[n].load_length, 0, extrude_maxlength); #endif @@ -583,7 +583,7 @@ void menu_advanced_settings() { #elif ENABLED(LIN_ADVANCE) #if EXTRUDERS == 1 EDIT_ITEM(float42_52, MSG_ADVANCE_K, &planner.extruder_advance_K[0], 0, 999); - #elif EXTRUDERS > 1 + #elif HAS_MULTI_EXTRUDER LOOP_L_N(n, E_STEPPERS) EDIT_ITEM_N(float42_52, n, MSG_ADVANCE_K_E, &planner.extruder_advance_K[n], 0, 999); #endif diff --git a/Marlin/src/lcd/menu/menu_backlash.cpp b/Marlin/src/lcd/menu/menu_backlash.cpp index 0e1bfb5910..9d0b970ae1 100644 --- a/Marlin/src/lcd/menu/menu_backlash.cpp +++ b/Marlin/src/lcd/menu/menu_backlash.cpp @@ -50,4 +50,4 @@ void menu_backlash() { END_MENU(); } -#endif // HAS_LCD_MENU && BACKLASH_COMPENSATION +#endif // HAS_LCD_MENU && BACKLASH_GCODE diff --git a/Marlin/src/lcd/menu/menu_bed_leveling.cpp b/Marlin/src/lcd/menu/menu_bed_leveling.cpp index 6841561c1b..e19b04ccb5 100644 --- a/Marlin/src/lcd/menu/menu_bed_leveling.cpp +++ b/Marlin/src/lcd/menu/menu_bed_leveling.cpp @@ -36,6 +36,11 @@ #include "../../module/probe.h" #endif +#if HAS_GRAPHICAL_TFT + #include "../tft/touch.h" + #include "../tft/tft.h" +#endif + #if EITHER(PROBE_MANUALLY, MESH_BED_LEVELING) #include "../../module/motion.h" @@ -159,7 +164,11 @@ // Move to the first probe position // void _lcd_level_bed_homing_done() { - if (ui.should_draw()) MenuItem_static::draw(1, GET_TEXT(MSG_LEVEL_BED_WAITING)); + if (ui.should_draw()) { + MenuItem_static::draw(1, GET_TEXT(MSG_LEVEL_BED_WAITING)); + // Color UI needs a control to detect a touch + TERN_(HAS_GRAPHICAL_TFT, touch.add_control(CLICK, 0, 0, TFT_WIDTH, TFT_HEIGHT)); + } if (ui.use_click()) { manual_probe_index = 0; _lcd_level_goto_next_point(); diff --git a/Marlin/src/lcd/menu/menu_configuration.cpp b/Marlin/src/lcd/menu/menu_configuration.cpp index a77e9a7354..22947ee514 100644 --- a/Marlin/src/lcd/menu/menu_configuration.cpp +++ b/Marlin/src/lcd/menu/menu_configuration.cpp @@ -60,7 +60,9 @@ void menu_advanced_settings(); static int8_t bar_percent = 0; if (ui.use_click()) { ui.goto_previous_screen(); - ui.set_custom_characters(CHARSET_MENU); + #if HAS_MARLINUI_HD44780 + ui.set_custom_characters(CHARSET_MENU); + #endif return; } bar_percent += (int8_t)ui.encoderPosition; @@ -73,7 +75,9 @@ void menu_advanced_settings(); void _progress_bar_test() { ui.goto_screen(progress_bar_test); - ui.set_custom_characters(CHARSET_INFO); + #if HAS_MARLINUI_HD44780 + ui.set_custom_characters(CHARSET_INFO); + #endif } #endif // LCD_PROGRESS_BAR_TEST @@ -94,7 +98,7 @@ void menu_advanced_settings(); #endif -#if EXTRUDERS > 1 +#if HAS_MULTI_EXTRUDER #include "../../module/tool_change.h" @@ -280,17 +284,17 @@ void menu_advanced_settings(); EDIT_ITEM(bool, MSG_AUTORETRACT, &fwretract.autoretract_enabled, fwretract.refresh_autoretract); #endif EDIT_ITEM(float52sign, MSG_CONTROL_RETRACT, &fwretract.settings.retract_length, 0, 100); - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER EDIT_ITEM(float52sign, MSG_CONTROL_RETRACT_SWAP, &fwretract.settings.swap_retract_length, 0, 100); #endif EDIT_ITEM(float3, MSG_CONTROL_RETRACTF, &fwretract.settings.retract_feedrate_mm_s, 1, 999); EDIT_ITEM(float52sign, MSG_CONTROL_RETRACT_ZHOP, &fwretract.settings.retract_zraise, 0, 999); EDIT_ITEM(float52sign, MSG_CONTROL_RETRACT_RECOVER, &fwretract.settings.retract_recover_extra, -100, 100); - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER EDIT_ITEM(float52sign, MSG_CONTROL_RETRACT_RECOVER_SWAP, &fwretract.settings.swap_retract_recover_extra, -100, 100); #endif EDIT_ITEM(float3, MSG_CONTROL_RETRACT_RECOVERF, &fwretract.settings.retract_recover_feedrate_mm_s, 1, 999); - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER EDIT_ITEM(float3, MSG_CONTROL_RETRACT_RECOVER_SWAPF, &fwretract.settings.swap_retract_recover_feedrate_mm_s, 1, 999); #endif END_MENU(); @@ -380,7 +384,7 @@ void menu_configuration() { // // Set single nozzle filament retract and prime length // - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER SUBMENU(MSG_TOOL_CHANGE, menu_tool_change); #if ENABLED(TOOLCHANGE_MIGRATION_FEATURE) SUBMENU(MSG_TOOL_MIGRATION, menu_toolchange_migration); diff --git a/Marlin/src/lcd/menu/menu_filament.cpp b/Marlin/src/lcd/menu/menu_filament.cpp index 316b2bc782..d116a6a398 100644 --- a/Marlin/src/lcd/menu/menu_filament.cpp +++ b/Marlin/src/lcd/menu/menu_filament.cpp @@ -101,9 +101,7 @@ void _menu_temp_filament_op(const PauseMode mode, const int8_t extruder) { } /** - * * "Change Filament" submenu - * */ #if E_STEPPERS > 1 || ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) @@ -138,8 +136,9 @@ void _menu_temp_filament_op(const PauseMode mode, const int8_t extruder) { SUBMENU_N_P(s, msg, []{ _menu_temp_filament_op(PAUSE_MODE_CHANGE_FILAMENT, MenuItemBase::itemIndex); }); else { ACTION_ITEM_N_P(s, msg, []{ - char cmd[13]; - sprintf_P(cmd, PSTR("M600 B0 T%i"), int(MenuItemBase::itemIndex)); + PGM_P const cmdpstr = PSTR("M600 B0 T%i"); + char cmd[strlen_P(cmdpstr) + 3 + 1]; + sprintf_P(cmd, cmdpstr, int(MenuItemBase::itemIndex)); queue.inject(cmd); }); } diff --git a/Marlin/src/lcd/menu/menu_info.cpp b/Marlin/src/lcd/menu/menu_info.cpp index 00ab9ad195..a4cbc31d8b 100644 --- a/Marlin/src/lcd/menu/menu_info.cpp +++ b/Marlin/src/lcd/menu/menu_info.cpp @@ -34,6 +34,9 @@ #include "game/game.h" #endif +#define VALUE_ITEM(MSG, VALUE, STYL) do{ char msg[21]; strcpy_P(msg, PSTR(": ")); strcpy(msg + 2, VALUE); STATIC_ITEM(MSG, STYL, msg); }while(0) +#define VALUE_ITEM_P(MSG, PVALUE, STYL) do{ char msg[21]; strcpy_P(msg, PSTR(": ")); strcpy_P(msg + 2, PSTR(PVALUE)); STATIC_ITEM(MSG, STYL, msg); }while(0) + #if ENABLED(PRINTCOUNTER) #include "../../module/printcounter.h" @@ -49,8 +52,8 @@ char buffer[21]; START_SCREEN(); // 12345678901234567890 - STATIC_ITEM(MSG_INFO_PRINT_COUNT, SS_LEFT, i16tostr3left(stats.totalPrints)); // Print Count: 999 - STATIC_ITEM(MSG_INFO_COMPLETED_PRINTS, SS_LEFT, i16tostr3left(stats.finishedPrints)); // Completed : 666 + VALUE_ITEM(MSG_INFO_PRINT_COUNT, i16tostr3left(stats.totalPrints), SS_LEFT); // Print Count: 999 + VALUE_ITEM(MSG_INFO_COMPLETED_PRINTS, i16tostr3left(stats.finishedPrints), SS_LEFT); // Completed : 666 STATIC_ITEM(MSG_INFO_PRINT_TIME, SS_LEFT); // Total print Time: STATIC_ITEM_P(PSTR("> "), SS_LEFT, duration_t(stats.printTime).toString(buffer)); // > 99y 364d 23h 59m 59s @@ -176,7 +179,7 @@ void menu_info_thermistors() { #undef THERMISTOR_ID #define THERMISTOR_ID TEMP_SENSOR_BED #include "../thermistornames.h" - STATIC_ITEM_P(PSTR("BED:" THERMISTOR_NAME), SS_INVERT); + STATIC_ITEM_P(PSTR("BED: " THERMISTOR_NAME), SS_INVERT); PSTRING_ITEM(MSG_INFO_MIN_TEMP, STRINGIFY(BED_MINTEMP), SS_LEFT); PSTRING_ITEM(MSG_INFO_MAX_TEMP, STRINGIFY(BED_MAXTEMP), SS_LEFT); STATIC_ITEM(TERN(WATCH_BED, MSG_INFO_RUNAWAY_ON, MSG_INFO_RUNAWAY_OFF), SS_LEFT); @@ -186,7 +189,7 @@ void menu_info_thermistors() { #undef THERMISTOR_ID #define THERMISTOR_ID TEMP_SENSOR_CHAMBER #include "../thermistornames.h" - STATIC_ITEM_P(PSTR("CHAM:" THERMISTOR_NAME), SS_INVERT); + STATIC_ITEM_P(PSTR("CHAM: " THERMISTOR_NAME), SS_INVERT); PSTRING_ITEM(MSG_INFO_MIN_TEMP, STRINGIFY(CHAMBER_MINTEMP), SS_LEFT); PSTRING_ITEM(MSG_INFO_MAX_TEMP, STRINGIFY(CHAMBER_MAXTEMP), SS_LEFT); STATIC_ITEM(TERN(WATCH_CHAMBER, MSG_INFO_RUNAWAY_ON, MSG_INFO_RUNAWAY_OFF), SS_LEFT); diff --git a/Marlin/src/lcd/menu/menu_item.h b/Marlin/src/lcd/menu/menu_item.h index bee05141bb..755135d14d 100644 --- a/Marlin/src/lcd/menu/menu_item.h +++ b/Marlin/src/lcd/menu/menu_item.h @@ -342,8 +342,8 @@ class MenuItem_bool : public MenuEditItemBase { #define PSTRING_ITEM(LABEL, V...) PSTRING_ITEM_P(GET_TEXT(LABEL), ##V) -#define STATIC_ITEM(LABEL, V...) STATIC_ITEM_P(GET_TEXT(LABEL), ##V) -#define STATIC_ITEM_N(LABEL, N, V...) STATIC_ITEM_N_P(GET_TEXT(LABEL), ##V) +#define STATIC_ITEM(LABEL, V...) STATIC_ITEM_P(GET_TEXT(LABEL), ##V) +#define STATIC_ITEM_N(LABEL, N, V...) STATIC_ITEM_N_P(GET_TEXT(LABEL), N, ##V) #define MENU_ITEM_N_S_P(TYPE, N, S, PLABEL, V...) _MENU_ITEM_N_S_P(TYPE, N, S, false, PLABEL, ##V) #define MENU_ITEM_N_S(TYPE, N, S, LABEL, V...) MENU_ITEM_N_S_P(TYPE, N, S, GET_TEXT(LABEL), ##V) diff --git a/Marlin/src/lcd/menu/menu_led.cpp b/Marlin/src/lcd/menu/menu_led.cpp index 290b0ddf63..386a4d799a 100644 --- a/Marlin/src/lcd/menu/menu_led.cpp +++ b/Marlin/src/lcd/menu/menu_led.cpp @@ -54,9 +54,33 @@ #endif + #if ENABLED(NEO2_COLOR_PRESETS) + + void menu_leds2_presets() { + START_MENU(); + #if LCD_HEIGHT > 2 + STATIC_ITEM(MSG_NEO2_PRESETS, SS_DEFAULT|SS_INVERT); + #endif + BACK_ITEM(MSG_LED_CONTROL); + ACTION_ITEM(MSG_SET_LEDS_WHITE, leds2.set_white); + ACTION_ITEM(MSG_SET_LEDS_RED, leds2.set_red); + ACTION_ITEM(MSG_SET_LEDS_ORANGE, leds2.set_orange); + ACTION_ITEM(MSG_SET_LEDS_YELLOW, leds2.set_yellow); + ACTION_ITEM(MSG_SET_LEDS_GREEN, leds2.set_green); + ACTION_ITEM(MSG_SET_LEDS_BLUE, leds2.set_blue); + ACTION_ITEM(MSG_SET_LEDS_INDIGO, leds2.set_indigo); + ACTION_ITEM(MSG_SET_LEDS_VIOLET, leds2.set_violet); + END_MENU(); + } + + #endif + void menu_led_custom() { START_MENU(); BACK_ITEM(MSG_LED_CONTROL); + #if ENABLED(NEOPIXEL2_SEPARATE) + STATIC_ITEM_N(MSG_LED_CHANNEL_N, 1, SS_DEFAULT|SS_INVERT); + #endif EDIT_ITEM(uint8, MSG_INTENSITY_R, &leds.color.r, 0, 255, leds.update, true); EDIT_ITEM(uint8, MSG_INTENSITY_G, &leds.color.g, 0, 255, leds.update, true); EDIT_ITEM(uint8, MSG_INTENSITY_B, &leds.color.b, 0, 255, leds.update, true); @@ -66,6 +90,14 @@ EDIT_ITEM(uint8, MSG_LED_BRIGHTNESS, &leds.color.i, 0, 255, leds.update, true); #endif #endif + #if ENABLED(NEOPIXEL2_SEPARATE) + STATIC_ITEM_N(MSG_LED_CHANNEL_N, 2, SS_DEFAULT|SS_INVERT); + EDIT_ITEM(uint8, MSG_INTENSITY_R, &leds2.color.r, 0, 255, leds2.update, true); + EDIT_ITEM(uint8, MSG_INTENSITY_G, &leds2.color.g, 0, 255, leds2.update, true); + EDIT_ITEM(uint8, MSG_INTENSITY_B, &leds2.color.b, 0, 255, leds2.update, true); + EDIT_ITEM(uint8, MSG_INTENSITY_W, &leds2.color.w, 0, 255, leds2.update, true); + EDIT_ITEM(uint8, MSG_NEO2_BRIGHTNESS, &leds2.color.i, 0, 255, leds2.update, true); + #endif END_MENU(); } #endif @@ -89,12 +121,20 @@ void menu_led() { BACK_ITEM(MSG_MAIN); #if ENABLED(LED_CONTROL_MENU) - bool led_on = leds.lights_on; - EDIT_ITEM(bool, MSG_LEDS, &led_on, leds.toggle); + editable.state = leds.lights_on; + EDIT_ITEM(bool, MSG_LEDS, &editable.state, leds.toggle); ACTION_ITEM(MSG_SET_LEDS_DEFAULT, leds.set_default); + #if ENABLED(NEOPIXEL2_SEPARATE) + editable.state = leds2.lights_on; + EDIT_ITEM(bool, MSG_LEDS2, &editable.state, leds2.toggle); + ACTION_ITEM(MSG_SET_LEDS_DEFAULT, leds2.set_default); + #endif #if ENABLED(LED_COLOR_PRESETS) SUBMENU(MSG_LED_PRESETS, menu_led_presets); #endif + #if ENABLED(NEO2_COLOR_PRESETS) + SUBMENU(MSG_NEO2_PRESETS, menu_leds2_presets); + #endif SUBMENU(MSG_CUSTOM_LEDS, menu_led_custom); #endif diff --git a/Marlin/src/lcd/menu/menu_main.cpp b/Marlin/src/lcd/menu/menu_main.cpp index 8908f49fb2..5b98382559 100644 --- a/Marlin/src/lcd/menu/menu_main.cpp +++ b/Marlin/src/lcd/menu/menu_main.cpp @@ -54,6 +54,10 @@ #include "../../feature/password/password.h" #endif +#if ENABLED(HOST_START_MENU_ITEM) && defined(ACTION_ON_START) + #include "../../feature/host_actions.h" +#endif + void menu_tune(); void menu_cancelobject(); void menu_motion(); @@ -158,6 +162,10 @@ void menu_main() { if (TERN0(MACHINE_CAN_PAUSE, printingIsPaused())) ACTION_ITEM(MSG_RESUME_PRINT, ui.resume_print); + #if ENABLED(HOST_START_MENU_ITEM) && defined(ACTION_ON_START) + ACTION_ITEM(MSG_HOST_START_PRINT, host_action_start); + #endif + SUBMENU(MSG_MOTION, menu_motion); } diff --git a/Marlin/src/lcd/menu/menu_media.cpp b/Marlin/src/lcd/menu/menu_media.cpp index 3c0c6532f0..93ecc49d98 100644 --- a/Marlin/src/lcd/menu/menu_media.cpp +++ b/Marlin/src/lcd/menu/menu_media.cpp @@ -99,7 +99,7 @@ class MenuItem_sdfolder : public MenuItem_sdbase { encoderTopLine = 0; ui.encoderPosition = 2 * (ENCODER_STEPS_PER_MENU_ITEM); ui.screen_changed = true; - TERN_(HAS_GRAPHICAL_LCD, ui.drawing_screen = false); + TERN_(HAS_MARLINUI_U8GLIB, ui.drawing_screen = false); ui.refresh(); } }; @@ -107,7 +107,7 @@ class MenuItem_sdfolder : public MenuItem_sdbase { void menu_media() { ui.encoder_direction_menus(); - #if HAS_GRAPHICAL_LCD + #if HAS_MARLINUI_U8GLIB static uint16_t fileCnt; if (ui.first_page) fileCnt = card.get_num_Files(); #else diff --git a/Marlin/src/lcd/menu/menu_motion.cpp b/Marlin/src/lcd/menu/menu_motion.cpp index 77ab643cd6..4e356b3e0c 100644 --- a/Marlin/src/lcd/menu/menu_motion.cpp +++ b/Marlin/src/lcd/menu/menu_motion.cpp @@ -205,7 +205,7 @@ void _menu_move_distance(const AxisEnum axis, const screenFunc_t func, const int #if DISABLED(HAS_GRAPHICAL_TFT) extern const char NUL_STR[]; SUBMENU_P(NUL_STR, []{ _goto_manual_move(float(SHORT_MANUAL_Z_MOVE)); }); - MENU_ITEM_ADDON_START(0 + ENABLED(HAS_CHARACTER_LCD)); + MENU_ITEM_ADDON_START(0 + ENABLED(HAS_MARLINUI_HD44780)); lcd_put_u8str(tmp); MENU_ITEM_ADDON_END(); #else @@ -348,7 +348,7 @@ void menu_motion() { // // Assisted Bed Tramming // - #if ENABLED(ASSISTED_TRAMMING) + #if ENABLED(ASSISTED_TRAMMING_MENU_ITEM) GCODES_ITEM(MSG_ASSISTED_TRAMMING, PSTR("G35")); #endif diff --git a/Marlin/src/lcd/menu/menu_tune.cpp b/Marlin/src/lcd/menu/menu_tune.cpp index c02906f7f9..b84cb8cbd7 100644 --- a/Marlin/src/lcd/menu/menu_tune.cpp +++ b/Marlin/src/lcd/menu/menu_tune.cpp @@ -46,7 +46,7 @@ #include "../../feature/babystep.h" #include "../lcdprint.h" - #if HAS_GRAPHICAL_LCD + #if HAS_MARLINUI_U8GLIB #include "../dogm/ultralcd_DOGM.h" #endif @@ -68,10 +68,10 @@ const float spm = planner.steps_to_mm[axis]; MenuEditItemBase::draw_edit_screen(msg, BABYSTEP_TO_STR(spm * babystep.accum)); #if ENABLED(BABYSTEP_DISPLAY_TOTAL) - const bool in_view = TERN1(HAS_GRAPHICAL_LCD, PAGE_CONTAINS(LCD_PIXEL_HEIGHT - MENU_FONT_HEIGHT, LCD_PIXEL_HEIGHT - 1)); + const bool in_view = TERN1(HAS_MARLINUI_U8GLIB, PAGE_CONTAINS(LCD_PIXEL_HEIGHT - MENU_FONT_HEIGHT, LCD_PIXEL_HEIGHT - 1)); if (in_view) { - TERN_(HAS_GRAPHICAL_LCD, ui.set_font(FONT_MENU)); - lcd_moveto(0, TERN(HAS_GRAPHICAL_LCD, LCD_PIXEL_HEIGHT - MENU_FONT_DESCENT, LCD_HEIGHT - 1)); + TERN_(HAS_MARLINUI_U8GLIB, ui.set_font(FONT_MENU)); + lcd_moveto(0, TERN(HAS_MARLINUI_U8GLIB, LCD_PIXEL_HEIGHT - MENU_FONT_DESCENT, LCD_HEIGHT - 1)); lcd_put_u8str_P(GET_TEXT(MSG_BABYSTEP_TOTAL)); lcd_put_wchar(':'); lcd_put_u8str(BABYSTEP_TO_STR(spm * babystep.axis_total[BS_TOTAL_IND(axis)])); @@ -215,7 +215,7 @@ void menu_tune() { #if EXTRUDERS EDIT_ITEM(int3, MSG_FLOW, &planner.flow_percentage[active_extruder], 10, 999, []{ planner.refresh_e_factor(active_extruder); }); // Flow En: - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER LOOP_L_N(n, EXTRUDERS) EDIT_ITEM_N(int3, n, MSG_FLOW_N, &planner.flow_percentage[n], 10, 999, []{ planner.refresh_e_factor(MenuItemBase::itemIndex); }); #endif @@ -227,7 +227,7 @@ void menu_tune() { #if ENABLED(LIN_ADVANCE) && DISABLED(SLIM_LCD_MENUS) #if EXTRUDERS == 1 EDIT_ITEM(float42_52, MSG_ADVANCE_K, &planner.extruder_advance_K[0], 0, 999); - #elif EXTRUDERS > 1 + #elif HAS_MULTI_EXTRUDER LOOP_L_N(n, EXTRUDERS) EDIT_ITEM_N(float42_52, n, MSG_ADVANCE_K_E, &planner.extruder_advance_K[n], 0, 999); #endif diff --git a/Marlin/src/lcd/menu/menu_ubl.cpp b/Marlin/src/lcd/menu/menu_ubl.cpp index d034de0952..2cd300958f 100644 --- a/Marlin/src/lcd/menu/menu_ubl.cpp +++ b/Marlin/src/lcd/menu/menu_ubl.cpp @@ -59,10 +59,14 @@ inline float rounded_mesh_value() { static void _lcd_mesh_fine_tune(PGM_P const msg) { ui.defer_status_screen(); if (ubl.encoder_diff) { - mesh_edit_accumulator += ubl.encoder_diff > 0 ? 0.005f : -0.005f; + mesh_edit_accumulator += TERN(IS_TFTGLCD_PANEL, + ubl.encoder_diff * 0.005f / ENCODER_PULSES_PER_STEP, + ubl.encoder_diff > 0 ? 0.005f : -0.005f + ); ubl.encoder_diff = 0; - ui.refresh(LCDVIEW_CALL_REDRAW_NEXT); + TERN(IS_TFTGLCD_PANEL,,ui.refresh(LCDVIEW_CALL_REDRAW_NEXT)); } + TERN_(IS_TFTGLCD_PANEL, ui.refresh(LCDVIEW_CALL_REDRAW_NEXT)); if (ui.should_draw()) { const float rounded_f = rounded_mesh_value(); diff --git a/Marlin/src/lcd/tft/bitmaps/btn_64x52_rounded.bmp b/Marlin/src/lcd/tft/bitmaps/btn_64x52_rounded.bmp new file mode 100644 index 0000000000..04e879dbb0 Binary files /dev/null and b/Marlin/src/lcd/tft/bitmaps/btn_64x52_rounded.bmp differ diff --git a/Marlin/src/lcd/tft/bitmaps/home.bmp b/Marlin/src/lcd/tft/bitmaps/home.bmp new file mode 100644 index 0000000000..03d3d82a87 Binary files /dev/null and b/Marlin/src/lcd/tft/bitmaps/home.bmp differ diff --git a/Marlin/src/lcd/tft/ili9341.h b/Marlin/src/lcd/tft/ili9341.h index 22709e4cf7..d4a493412f 100644 --- a/Marlin/src/lcd/tft/ili9341.h +++ b/Marlin/src/lcd/tft/ili9341.h @@ -33,10 +33,10 @@ #define ILI9341_MADCTL_RGB 0x00 #define ILI9341_MADCTL_MH 0x04 // Horizontal Refresh Order -#define ILI9341_ORIENTATION_UP ILI9341_MADCTL_MY // 240x320 ; Cable on the upper side +#define ILI9341_ORIENTATION_UP ILI9341_MADCTL_MY // 240x320 ; Cable on the upper side #define ILI9341_ORIENTATION_RIGHT ILI9341_MADCTL_MV // 320x240 ; Cable on the right side #define ILI9341_ORIENTATION_LEFT ILI9341_MADCTL_MY | ILI9341_MADCTL_MX | ILI9341_MADCTL_MV // 320x240 ; Cable on the left side -#define ILI9341_ORIENTATION_DOWN ILI9341_MADCTL_MX // 240x320 ; Cable on the upper side +#define ILI9341_ORIENTATION_DOWN ILI9341_MADCTL_MX // 240x320 ; Cable on the upper side #ifndef ILI9341_COLOR_RGB #define ILI9341_COLOR_BGR diff --git a/Marlin/src/lcd/tft/images/btn_rounded_64x52x4.cpp b/Marlin/src/lcd/tft/images/btn_rounded_64x52x4.cpp new file mode 100644 index 0000000000..69a045d85a --- /dev/null +++ b/Marlin/src/lcd/tft/images/btn_rounded_64x52x4.cpp @@ -0,0 +1,82 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_GRAPHICAL_TFT + +extern const uint8_t btn_rounded_64x52x4[1664] = { + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x88, + 0x88, 0x88, 0x79, 0xce, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xeb, 0x87, 0x77, 0x78, + 0x88, 0x78, 0xcf, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfb, 0x66, 0x78, + 0x88, 0x8d, 0xff, 0xb8, 0x54, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x45, 0x7b, 0xff, 0xc6, 0x67, + 0x87, 0xbf, 0xf7, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x6f, 0xf9, 0x56, + 0x87, 0xef, 0x84, 0x44, 0x45, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x58, 0xfd, 0x46, + 0x87, 0xff, 0x54, 0x44, 0x56, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0xff, 0x45, + 0x87, 0xff, 0x44, 0x45, 0x67, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x76, 0xff, 0x45, + 0x87, 0xff, 0x44, 0x56, 0x77, 0x77, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x77, 0x77, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x77, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x77, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xff, 0x44, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0xff, 0x44, + 0x87, 0xef, 0x84, 0x56, 0x77, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x7a, 0xfe, 0x44, + 0x87, 0xaf, 0xf6, 0x56, 0x77, 0x77, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x77, 0x9f, 0xf9, 0x44, + 0x87, 0x7d, 0xff, 0xb8, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x78, 0x9c, 0xff, 0xd4, 0x45, + 0x87, 0x76, 0xbf, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfb, 0x54, 0x45, + 0x87, 0x76, 0x56, 0xad, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xdb, 0x64, 0x44, 0x46, + 0x87, 0x77, 0x65, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x56, + 0x88, 0x77, 0x76, 0x55, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x44, 0x55, 0x67, + 0x88, 0x77, 0x77, 0x66, 0x65, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x56, 0x66, 0x78, + 0x88, 0x88, 0x77, 0x77, 0x76, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x66, 0x67, 0x77, 0x78, +}; + +#endif // HAS_GRAPHICAL_TFT diff --git a/Marlin/src/lcd/tft/images/home_64x64x4.cpp b/Marlin/src/lcd/tft/images/home_64x64x4.cpp new file mode 100644 index 0000000000..107c76e54e --- /dev/null +++ b/Marlin/src/lcd/tft/images/home_64x64x4.cpp @@ -0,0 +1,94 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "../../../inc/MarlinConfigPre.h" + +#if HAS_GRAPHICAL_TFT + +extern const uint8_t home_64x64x4[2048] = { + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0x77, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x67, 0x88, 0x76, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x86, 0x9d, 0xff, 0xea, 0x67, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x69, 0xff, 0xff, 0xff, 0xc6, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x86, 0x9f, 0xff, 0xff, 0xff, 0xfc, 0x67, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x69, 0xff, 0xff, 0xff, 0xff, 0xff, 0xc6, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x86, 0x9f, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfc, 0x67, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x69, 0xff, 0xff, 0xff, 0xeb, 0xff, 0xff, 0xff, 0xc6, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x86, 0x9f, 0xff, 0xff, 0xff, 0x40, 0xbf, 0xff, 0xff, 0xfc, 0x67, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x69, 0xff, 0xff, 0xff, 0xf6, 0x54, 0xa, 0xff, 0xff, 0xff, 0xc6, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x86, 0x9f, 0xff, 0xff, 0xff, 0x57, 0xff, 0x80, 0xaf, 0xff, 0xff, 0xfc, 0x67, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x69, 0xff, 0xff, 0xff, 0xf5, 0x6f, 0xff, 0xf9, 0xa, 0xff, 0xff, 0xff, 0xc6, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x86, 0x9f, 0xff, 0xff, 0xff, 0x56, 0xff, 0xff, 0xff, 0x90, 0xaf, 0xff, 0xff, 0xfc, 0x67, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x69, 0xff, 0xff, 0xff, 0xf5, 0x6f, 0xff, 0xff, 0xff, 0xf9, 0xa, 0xff, 0xff, 0xff, 0xc6, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x86, 0x9f, 0xff, 0xff, 0xff, 0x56, 0xff, 0xff, 0xff, 0xff, 0xff, 0x90, 0xaf, 0xff, 0xff, 0xfc, 0x67, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x69, 0xff, 0xff, 0xff, 0xf5, 0x6f, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf9, 0xa, 0xff, 0xff, 0xff, 0xc6, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x86, 0x9f, 0xff, 0xff, 0xff, 0x56, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x90, 0xaf, 0xff, 0xff, 0xfc, 0x67, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x69, 0xff, 0xff, 0xff, 0xf5, 0x6f, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf9, 0xa, 0xff, 0xff, 0xff, 0xc6, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x86, 0x9f, 0xff, 0xff, 0xff, 0x56, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x90, 0xaf, 0xff, 0xff, 0xfc, 0x67, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x69, 0xff, 0xff, 0xff, 0xf5, 0x6f, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf9, 0xa, 0xff, 0xff, 0xff, 0xc6, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x86, 0x9f, 0xff, 0xff, 0xff, 0x56, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x90, 0xbf, 0xff, 0xff, 0xfc, 0x67, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x69, 0xff, 0xff, 0xff, 0xf5, 0x6f, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf9, 0xa, 0xff, 0xff, 0xff, 0xc6, 0x78, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x86, 0x9f, 0xff, 0xff, 0xff, 0x56, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x90, 0xaf, 0xff, 0xff, 0xfc, 0x67, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x69, 0xff, 0xff, 0xff, 0xf5, 0x6f, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf9, 0xa, 0xff, 0xff, 0xff, 0xc6, 0x78, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x86, 0x9f, 0xff, 0xff, 0xff, 0x56, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x90, 0xaf, 0xff, 0xff, 0xfc, 0x67, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x69, 0xff, 0xff, 0xff, 0xf5, 0x6f, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf9, 0xa, 0xff, 0xff, 0xff, 0xc6, 0x78, 0x88, 0x88, + 0x88, 0x86, 0x9f, 0xff, 0xff, 0xff, 0x56, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x90, 0xaf, 0xff, 0xff, 0xfc, 0x67, 0x88, 0x88, + 0x88, 0x69, 0xff, 0xff, 0xff, 0xf5, 0x6f, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf9, 0xb, 0xff, 0xff, 0xff, 0xc6, 0x78, 0x88, + 0x87, 0x7f, 0xff, 0xff, 0xff, 0x66, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x90, 0xbf, 0xff, 0xff, 0xfb, 0x68, 0x88, + 0x87, 0x7f, 0xff, 0xff, 0xf7, 0x3c, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf4, 0xb, 0xff, 0xff, 0xfd, 0x67, 0x88, + 0x87, 0x3d, 0xff, 0xff, 0x75, 0x59, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0x30, 0xbf, 0xff, 0xfa, 0x68, 0x88, + 0x88, 0x44, 0xce, 0xd7, 0x58, 0x49, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0x74, 0x19, 0xee, 0xa6, 0x88, 0x88, + 0x88, 0x73, 0x24, 0x56, 0x88, 0x49, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0x78, 0x52, 0x35, 0x68, 0x88, 0x88, + 0x88, 0x87, 0x66, 0x78, 0x88, 0x49, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0x78, 0x87, 0x67, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x49, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x49, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x49, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf9, 0x55, 0x55, 0x55, 0x5d, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x49, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x92, 0x44, 0x44, 0x44, 0x12, 0xef, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x49, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x77, 0x88, 0x88, 0x88, 0x72, 0xbf, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x49, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x97, 0x88, 0x88, 0x88, 0x84, 0xbf, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x49, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x96, 0x88, 0x88, 0x88, 0x84, 0xbf, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x49, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x96, 0x88, 0x88, 0x88, 0x84, 0xbf, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x49, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x96, 0x88, 0x88, 0x88, 0x84, 0xbf, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x49, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x96, 0x88, 0x88, 0x88, 0x84, 0xbf, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x49, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x96, 0x88, 0x88, 0x88, 0x84, 0xbf, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x49, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x96, 0x88, 0x88, 0x88, 0x84, 0xbf, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x49, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x96, 0x88, 0x88, 0x88, 0x84, 0xbf, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x49, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x96, 0x88, 0x88, 0x88, 0x84, 0xbf, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x49, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x96, 0x88, 0x88, 0x88, 0x84, 0xbf, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x49, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x96, 0x88, 0x88, 0x88, 0x84, 0xbf, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x49, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x96, 0x88, 0x88, 0x88, 0x84, 0xbf, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf7, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x64, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x96, 0x88, 0x88, 0x88, 0x84, 0xcf, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xb6, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x83, 0x4c, 0xee, 0xee, 0xee, 0xee, 0xee, 0xff, 0x97, 0x88, 0x88, 0x88, 0x84, 0xae, 0xee, 0xee, 0xee, 0xee, 0xee, 0xea, 0x67, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x87, 0x32, 0x44, 0x44, 0x44, 0x44, 0x33, 0x57, 0x88, 0x88, 0x88, 0x88, 0x86, 0x43, 0x34, 0x44, 0x44, 0x44, 0x34, 0x55, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x76, 0x55, 0x55, 0x55, 0x55, 0x55, 0x67, 0x88, 0x88, 0x88, 0x88, 0x87, 0x65, 0x55, 0x55, 0x55, 0x55, 0x56, 0x78, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, + 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88, 0x88 +}; + +#endif // HAS_GRAPHICAL_TFT diff --git a/Marlin/src/lcd/tft/st7735.h b/Marlin/src/lcd/tft/st7735.h index 30e77fbd91..62f93d5044 100644 --- a/Marlin/src/lcd/tft/st7735.h +++ b/Marlin/src/lcd/tft/st7735.h @@ -33,7 +33,7 @@ #define ST7735_MADCTL_RGB 0x00 #define ST7735_MADCTL_MH 0x04 // Horizontal Refresh Order -#define ST7735_ORIENTATION_UP 0x00 // 128x160 ; Cable on the upper side +#define ST7735_ORIENTATION_UP 0x00 // 128x160 ; Cable on the upper side #define ST7735_ORIENTATION_RIGHT ST7735_MADCTL_MV | ST7735_MADCTL_MY // 160x128 ; Cable on the right side #define ST7735_ORIENTATION_LEFT ST7735_MADCTL_MV | ST7735_MADCTL_MX // 160x128 ; Cable on the left side #define ST7735_ORIENTATION_DOWN ST7735_MADCTL_MX | ST7735_MADCTL_MY // 128x160 ; Cable on the lower side @@ -71,7 +71,7 @@ #define ST7735_IDMOFF 0x38 // Idle Mode Off #define ST7735_IDMON 0x39 // Idle Mode On #define ST7735_COLMOD 0x3A // Interface Pixel Format -#define ST7735_RDID1 0xDA // Read ID1 Value +#define ST7735_RDID1 0xDA // Read ID1 Value #define ST7735_RDID2 0xDB // Read ID2 Value #define ST7735_RDID3 0xDC // Read ID3 Value diff --git a/Marlin/src/lcd/tft/st7789v.h b/Marlin/src/lcd/tft/st7789v.h index f6e937c2c2..67da67966d 100644 --- a/Marlin/src/lcd/tft/st7789v.h +++ b/Marlin/src/lcd/tft/st7789v.h @@ -89,7 +89,7 @@ #define ST7789V_WRCABCMB 0x5E // Write CABC Minimum Brightness #define ST7789V_RDCABCMB 0x5F // Read CABC Minimum Brightness #define ST7789V_RDABCSDR 0x68 // Read Automatic Brightness Control Self-Diagnostic Result -#define ST7789V_RDID1 0xDA // Read ID1 Value +#define ST7789V_RDID1 0xDA // Read ID1 Value #define ST7789V_RDID2 0xDB // Read ID2 Value #define ST7789V_RDID3 0xDC // Read ID3 Value diff --git a/Marlin/src/lcd/tft/st7796s.h b/Marlin/src/lcd/tft/st7796s.h index 7ddbcfae84..10452293de 100644 --- a/Marlin/src/lcd/tft/st7796s.h +++ b/Marlin/src/lcd/tft/st7796s.h @@ -25,92 +25,92 @@ #include "../../inc/MarlinConfig.h" -#define ST7796S_MADCTL_MY 0x80 // Row Address Order -#define ST7796S_MADCTL_MX 0x40 // Column Address Order -#define ST7796S_MADCTL_MV 0x20 // Row/Column Exchange -#define ST7796S_MADCTL_ML 0x10 // Vertical Refresh Order -#define ST7796S_MADCTL_BGR 0x08 // RGB-BGR ORDER -#define ST7796S_MADCTL_RGB 0x00 -#define ST7796S_MADCTL_MH 0x04 // Horizontal Refresh Order +#define ST7796S_MADCTL_MY 0x80 // Row Address Order +#define ST7796S_MADCTL_MX 0x40 // Column Address Order +#define ST7796S_MADCTL_MV 0x20 // Row/Column Exchange +#define ST7796S_MADCTL_ML 0x10 // Vertical Refresh Order +#define ST7796S_MADCTL_BGR 0x08 // RGB-BGR ORDER +#define ST7796S_MADCTL_RGB 0x00 +#define ST7796S_MADCTL_MH 0x04 // Horizontal Refresh Order #define ST7796S_COLOR_BGR -#define ST7796S_ORIENTATION ST7796S_MADCTL_MV -#define ST7796S_MADCTL_DATA (ST7796S_ORIENTATION | TERN(ST7796S_COLOR_BGR, ST7796S_MADCTL_BGR, ST7796S_MADCTL_RGB)) - -#define ST7796S_NOP 0x00 // No Operation -#define ST7796S_SWRESET 0x01 // Software reset -#define ST7796S_RDDID 0x04 // Read Display ID -#define ST7796S_RDNUMED 0x05 // Read Number of the Errors on DSI -#define ST7796S_RDDST 0x09 // Read Display Status -#define ST7796S_RDDPM 0x0A // Read Display Power Mode -#define ST7796S_RDDMADCTL 0x0B // Read Display MADCTL -#define ST7796S_RDDCOLMOD 0x0C // Read Display Pixel Format -#define ST7796S_RDDIM 0x0D // Read Display Image Mode -#define ST7796S_RDDSM 0x0E // Read Display Signal Status -#define ST7796S_RDDSDR 0x0F // Read Display Self-Diagnostic Result -#define ST7796S_SLPIN 0x10 // Sleep In -#define ST7796S_SLPOUT 0x11 // Sleep Out -#define ST7796S_PTLON 0x12 // Partial Display Mode On -#define ST7796S_NORON 0x13 // Normal Display Mode On -#define ST7796S_INVOFF 0x20 // Display Inversion Off -#define ST7796S_INVON 0x21 // Display Inversion On -#define ST7796S_DISPOFF 0x28 // Display Off -#define ST7796S_DISPON 0x29 // Display On -#define ST7796S_CASET 0x2A // Column Address Set -#define ST7796S_RASET 0x2B // Row Address Set -#define ST7796S_RAMWR 0x2C // Memory Write -#define ST7796S_RAMRD 0x2E // Memory Read -#define ST7796S_PTLAR 0x30 // Partial Area -#define ST7796S_VSCRDEF 0x33 // Vertical Scrolling Definition -#define ST7796S_TEOFF 0x34 // Tearing Effect Line OFF -#define ST7796S_TEON 0x35 // Tearing Effect Line On -#define ST7796S_MADCTL 0x36 // Memory Data Access Control -#define ST7796S_VSCSAD 0x37 // Vertical Scroll Start Address of RAM -#define ST7796S_IDMOFF 0x38 // Idle Mode Off -#define ST7796S_IDMON 0x39 // Idle Mode On -#define ST7796S_COLMOD 0x3A // Interface Pixel Format -#define ST7796S_WRMEMC 0x3C // Write Memory Continue -#define ST7796S_RDMEMC 0x3E // Read Memory Continue -#define ST7796S_STE 0x44 // Set Tear ScanLine -#define ST7796S_GSCAN 0x45 // Get ScanLine -#define ST7796S_WRDISBV 0x51 // Write Display Brightness -#define ST7796S_RDDISBV 0x52 // Read Display Brightness Value -#define ST7796S_WRCTRLD 0x53 // Write CTRL Display -#define ST7796S_RDCTRLD 0x54 // Read CTRL value Display -#define ST7796S_WRCABC 0x55 // Write Adaptive Brightness Control -#define ST7796S_RDCABC 0x56 // Read Content Adaptive Brightness Control -#define ST7796S_WRCABCMB 0x5E // Write CABC Minimum Brightness -#define ST7796S_RDCABCMB 0x5F // Read CABC Minimum Brightness -#define ST7796S_RDFCS 0xAA // Read First Checksum -#define ST7796S_RDCFCS 0xAF // Read Continue Checksum -#define ST7796S_RDID1 0xDA // Read ID1 -#define ST7796S_RDID2 0xDB // Read ID2 -#define ST7796S_RDID3 0xDC // Read ID3 - -#define ST7796S_IFMODE 0xB0 // Interface Mode Control -#define ST7796S_FRMCTR1 0xB1 // Frame Rate Control (In Normal Mode/Full Colors) -#define ST7796S_FRMCTR2 0xB2 // Frame Rate Control 2 (In Idle Mode/8 colors) -#define ST7796S_FRMCTR3 0xB3 // Frame Rate Control 3(In Partial Mode/Full Colors) -#define ST7796S_DIC 0xB4 // Display Inversion Control -#define ST7796S_BPC 0xB5 // Blanking Porch Control -#define ST7796S_DFC 0xB6 // Display Function Control -#define ST7796S_EM 0xB7 // Entry Mode Set -#define ST7796S_PWR1 0xC0 // Power Control 1 -#define ST7796S_PWR2 0xC1 // Power Control 2 -#define ST7796S_PWR3 0xC2 // Power Control 3 -#define ST7796S_VCMPCTL 0xC5 // VCOM Control -#define ST7796S_VCMOST 0xC6 // VCOM Offset Register -#define ST7796S_NVMADW 0xD0 // NVM Address/Data Write -#define ST7796S_NVMBPROG 0xD1 // NVM Byte Program -#define ST7796S_NVMSTRD 0xD2 // NVM Status Read -#define ST7796S_RDID4 0xD3 // Read ID4 -#define ST7796S_PGC 0xE0 // Positive Gamma Control -#define ST7796S_NGC 0xE1 // Negative Gamma Control -#define ST7796S_DGC1 0xE2 // Digital Gamma Control 1 -#define ST7796S_DGC2 0xE3 // Digital Gamma Control 2 -#define ST7796S_DOCA 0xE8 // Display Output Ctrl Adjust -#define ST7796S_CSCON 0xF0 // Command Set Control -#define ST7796S_SPIRC 0xFB // SPI Read Control +#define ST7796S_ORIENTATION ST7796S_MADCTL_MV +#define ST7796S_MADCTL_DATA (ST7796S_ORIENTATION | TERN(ST7796S_COLOR_BGR, ST7796S_MADCTL_BGR, ST7796S_MADCTL_RGB)) + +#define ST7796S_NOP 0x00 // No Operation +#define ST7796S_SWRESET 0x01 // Software reset +#define ST7796S_RDDID 0x04 // Read Display ID +#define ST7796S_RDNUMED 0x05 // Read Number of the Errors on DSI +#define ST7796S_RDDST 0x09 // Read Display Status +#define ST7796S_RDDPM 0x0A // Read Display Power Mode +#define ST7796S_RDDMADCTL 0x0B // Read Display MADCTL +#define ST7796S_RDDCOLMOD 0x0C // Read Display Pixel Format +#define ST7796S_RDDIM 0x0D // Read Display Image Mode +#define ST7796S_RDDSM 0x0E // Read Display Signal Status +#define ST7796S_RDDSDR 0x0F // Read Display Self-Diagnostic Result +#define ST7796S_SLPIN 0x10 // Sleep In +#define ST7796S_SLPOUT 0x11 // Sleep Out +#define ST7796S_PTLON 0x12 // Partial Display Mode On +#define ST7796S_NORON 0x13 // Normal Display Mode On +#define ST7796S_INVOFF 0x20 // Display Inversion Off +#define ST7796S_INVON 0x21 // Display Inversion On +#define ST7796S_DISPOFF 0x28 // Display Off +#define ST7796S_DISPON 0x29 // Display On +#define ST7796S_CASET 0x2A // Column Address Set +#define ST7796S_RASET 0x2B // Row Address Set +#define ST7796S_RAMWR 0x2C // Memory Write +#define ST7796S_RAMRD 0x2E // Memory Read +#define ST7796S_PTLAR 0x30 // Partial Area +#define ST7796S_VSCRDEF 0x33 // Vertical Scrolling Definition +#define ST7796S_TEOFF 0x34 // Tearing Effect Line OFF +#define ST7796S_TEON 0x35 // Tearing Effect Line On +#define ST7796S_MADCTL 0x36 // Memory Data Access Control +#define ST7796S_VSCSAD 0x37 // Vertical Scroll Start Address of RAM +#define ST7796S_IDMOFF 0x38 // Idle Mode Off +#define ST7796S_IDMON 0x39 // Idle Mode On +#define ST7796S_COLMOD 0x3A // Interface Pixel Format +#define ST7796S_WRMEMC 0x3C // Write Memory Continue +#define ST7796S_RDMEMC 0x3E // Read Memory Continue +#define ST7796S_STE 0x44 // Set Tear ScanLine +#define ST7796S_GSCAN 0x45 // Get ScanLine +#define ST7796S_WRDISBV 0x51 // Write Display Brightness +#define ST7796S_RDDISBV 0x52 // Read Display Brightness Value +#define ST7796S_WRCTRLD 0x53 // Write CTRL Display +#define ST7796S_RDCTRLD 0x54 // Read CTRL value Display +#define ST7796S_WRCABC 0x55 // Write Adaptive Brightness Control +#define ST7796S_RDCABC 0x56 // Read Content Adaptive Brightness Control +#define ST7796S_WRCABCMB 0x5E // Write CABC Minimum Brightness +#define ST7796S_RDCABCMB 0x5F // Read CABC Minimum Brightness +#define ST7796S_RDFCS 0xAA // Read First Checksum +#define ST7796S_RDCFCS 0xAF // Read Continue Checksum +#define ST7796S_RDID1 0xDA // Read ID1 +#define ST7796S_RDID2 0xDB // Read ID2 +#define ST7796S_RDID3 0xDC // Read ID3 + +#define ST7796S_IFMODE 0xB0 // Interface Mode Control +#define ST7796S_FRMCTR1 0xB1 // Frame Rate Control (In Normal Mode/Full Colors) +#define ST7796S_FRMCTR2 0xB2 // Frame Rate Control 2 (In Idle Mode/8 colors) +#define ST7796S_FRMCTR3 0xB3 // Frame Rate Control 3(In Partial Mode/Full Colors) +#define ST7796S_DIC 0xB4 // Display Inversion Control +#define ST7796S_BPC 0xB5 // Blanking Porch Control +#define ST7796S_DFC 0xB6 // Display Function Control +#define ST7796S_EM 0xB7 // Entry Mode Set +#define ST7796S_PWR1 0xC0 // Power Control 1 +#define ST7796S_PWR2 0xC1 // Power Control 2 +#define ST7796S_PWR3 0xC2 // Power Control 3 +#define ST7796S_VCMPCTL 0xC5 // VCOM Control +#define ST7796S_VCMOST 0xC6 // VCOM Offset Register +#define ST7796S_NVMADW 0xD0 // NVM Address/Data Write +#define ST7796S_NVMBPROG 0xD1 // NVM Byte Program +#define ST7796S_NVMSTRD 0xD2 // NVM Status Read +#define ST7796S_RDID4 0xD3 // Read ID4 +#define ST7796S_PGC 0xE0 // Positive Gamma Control +#define ST7796S_NGC 0xE1 // Negative Gamma Control +#define ST7796S_DGC1 0xE2 // Digital Gamma Control 1 +#define ST7796S_DGC2 0xE3 // Digital Gamma Control 2 +#define ST7796S_DOCA 0xE8 // Display Output Ctrl Adjust +#define ST7796S_CSCON 0xF0 // Command Set Control +#define ST7796S_SPIRC 0xFB // SPI Read Control static const uint16_t st7796s_init[] = { DATASIZE_8BIT, @@ -133,8 +133,8 @@ static const uint16_t st7796s_init[] = { ESC_REG(ST7796S_DOCA), 0x0040, 0x008A, 0x0000, 0x0000, 0x0029, 0x0019, 0x00A5, 0x0033, /* Gamma Correction. */ - ESC_REG(ST7796S_PGC), 0x00F0, 0x0004, 0x0008, 0x0009, 0x0008, 0x0015, 0x002F, 0x0042, 0x0046, 0x0028, 0x0015, 0x0016, 0x0029, 0x002D, - ESC_REG(ST7796S_NGC), 0x00F0, 0x0004, 0x0009, 0x0009, 0x0008, 0x0015, 0x002E, 0x0046, 0x0046, 0x0028, 0x0015, 0x0015, 0x0029, 0x002D, + ESC_REG(ST7796S_PGC), 0x00F0, 0x0004, 0x0008, 0x0009, 0x0008, 0x0015, 0x002F, 0x0042, 0x0046, 0x0028, 0x0015, 0x0016, 0x0029, 0x002D, + ESC_REG(ST7796S_NGC), 0x00F0, 0x0004, 0x0009, 0x0009, 0x0008, 0x0015, 0x002E, 0x0046, 0x0046, 0x0028, 0x0015, 0x0015, 0x0029, 0x002D, ESC_REG(ST7796S_NORON), ESC_REG(ST7796S_WRCTRLD), 0x0024, @@ -146,30 +146,30 @@ static const uint16_t st7796s_init[] = { static const uint16_t lerdge_st7796s_init[] = { DATASIZE_8BIT, - ESC_REG(ST7796S_CSCON), 0x00C3, // enable command 2 part I - ESC_REG(ST7796S_CSCON), 0x0096, // enable command 2 part II + ESC_REG(ST7796S_CSCON), 0x00C3, // enable command 2 part I + ESC_REG(ST7796S_CSCON), 0x0096, // enable command 2 part II - ESC_REG(ST7796S_MADCTL), ST7796S_MADCTL_DATA, + ESC_REG(ST7796S_MADCTL), ST7796S_MADCTL_DATA, ESC_REG(ST7796S_COLMOD), 0x0055, - ESC_REG(ST7796S_DIC), 0x0001, // 1-dot inversion - ESC_REG(ST7796S_EM), 0x00C6, + ESC_REG(ST7796S_DIC), 0x0001, // 1-dot inversion + ESC_REG(ST7796S_EM), 0x00C6, - ESC_REG(ST7796S_PWR2), 0x0015, - ESC_REG(ST7796S_PWR3), 0x00AF, - ESC_REG(0xC3), 0x0009, // Register not documented in datasheet - ESC_REG(ST7796S_VCMPCTL), 0x0022, - ESC_REG(ST7796S_VCMOST), 0x0000, - ESC_REG(ST7796S_DOCA), 0x0040, 0x008A, 0x0000, 0x0000, 0x0029, 0x0019, 0x00A5, 0x0033, + ESC_REG(ST7796S_PWR2), 0x0015, + ESC_REG(ST7796S_PWR3), 0x00AF, + ESC_REG(0xC3), 0x0009, // Register not documented in datasheet + ESC_REG(ST7796S_VCMPCTL), 0x0022, + ESC_REG(ST7796S_VCMOST), 0x0000, + ESC_REG(ST7796S_DOCA), 0x0040, 0x008A, 0x0000, 0x0000, 0x0029, 0x0019, 0x00A5, 0x0033, /* Gamma Correction. */ - ESC_REG(ST7796S_PGC), 0x00F0, 0x0004, 0x0008, 0x0009, 0x0008, 0x0015, 0x002F, 0x0042, 0x0046, 0x0028, 0x0015, 0x0016, 0x0029, 0x002D, - ESC_REG(ST7796S_NGC), 0x00F0, 0x0004, 0x0009, 0x0009, 0x0008, 0x0015, 0x002E, 0x0046, 0x0046, 0x0028, 0x0015, 0x0015, 0x0029, 0x002D, - - ESC_REG(ST7796S_INVON), // Display inversion ON - ESC_REG(ST7796S_WRCTRLD), 0x0024, - ESC_REG(ST7796S_CSCON), 0x003C, // disable command 2 part I - ESC_REG(ST7796S_CSCON), 0x0069, // disable command 2 part II - ESC_REG(ST7796S_DISPON), + ESC_REG(ST7796S_PGC), 0x00F0, 0x0004, 0x0008, 0x0009, 0x0008, 0x0015, 0x002F, 0x0042, 0x0046, 0x0028, 0x0015, 0x0016, 0x0029, 0x002D, + ESC_REG(ST7796S_NGC), 0x00F0, 0x0004, 0x0009, 0x0009, 0x0008, 0x0015, 0x002E, 0x0046, 0x0046, 0x0028, 0x0015, 0x0015, 0x0029, 0x002D, + + ESC_REG(ST7796S_INVON), // Display inversion ON + ESC_REG(ST7796S_WRCTRLD), 0x0024, + ESC_REG(ST7796S_CSCON), 0x003C, // disable command 2 part I + ESC_REG(ST7796S_CSCON), 0x0069, // disable command 2 part II + ESC_REG(ST7796S_DISPON), ESC_END }; diff --git a/Marlin/src/lcd/tft/tft_color.h b/Marlin/src/lcd/tft/tft_color.h index d2c5d8e7db..8e380b366b 100644 --- a/Marlin/src/lcd/tft/tft_color.h +++ b/Marlin/src/lcd/tft/tft_color.h @@ -21,6 +21,8 @@ */ #pragma once +#include "../../inc/MarlinConfigPre.h" + #define RED(color) ((color >> 8) & 0xF8) #define GREEN(color) ((color >> 3) & 0xFC) #define BLUE(color) ((color << 3) & 0xF8) @@ -42,6 +44,7 @@ #define COLOR_SCARLET 0xF904 // #FF2020 #define COLOR_LIME 0x7E00 // #00FF00 #define COLOR_BLUE 0x001F // #0000FF +#define COLOR_LIGHT_BLUE 0x061F // #00C3FF #define COLOR_YELLOW 0xFFE0 // #FFFF00 #define COLOR_MAGENTA 0xF81F // #FF00FF #define COLOR_FUCHSIA 0xF81F // #FF00FF @@ -66,47 +69,108 @@ #define COLOR_DARK_PURPLE 0x9930 // #992380 - -#define COLOR_BACKGROUND 0x20AC // #1E156E -#define COLOR_SELECTION_BG 0x9930 // #992380 -#define COLOR_WEBSITE_URL 0x03B7 - -#define COLOR_INACTIVE COLOR_GREY -#define COLOR_COLD COLOR_AQUA -#define COLOR_HOTEND COLOR_SCARLET -#define COLOR_HEATED_BED COLOR_DARK_ORANGE -#define COLOR_CHAMBER COLOR_DARK_ORANGE -#define COLOR_FAN COLOR_AQUA - -#define COLOR_AXIS_HOMED COLOR_WHITE -#define COLOR_AXIS_NOT_HOMED COLOR_YELLOW - -#define COLOR_RATE_100 COLOR_VIVID_GREEN -#define COLOR_RATE_ALTERED COLOR_YELLOW - -#define COLOR_PRINT_TIME COLOR_AQUA - -#define COLOR_PROGRESS_FRAME COLOR_WHITE -#define COLOR_PROGRESS_BAR COLOR_BLUE -#define COLOR_PROGRESS_BG COLOR_BLACK - -#define COLOR_STATUS_MESSAGE COLOR_YELLOW - -#define COLOR_CONTROL_ENABLED COLOR_WHITE -#define COLOR_CONTROL_DISABLED COLOR_GREY -#define COLOR_CONTROL_CANCEL COLOR_SCARLET -#define COLOR_CONTROL_CONFIRM COLOR_VIVID_GREEN -#define COLOR_BUSY COLOR_SILVER - -#define COLOR_MENU_TEXT COLOR_YELLOW -#define COLOR_MENU_VALUE COLOR_WHITE - -#define COLOR_SLIDER COLOR_WHITE -#define COLOR_SLIDER_INACTIVE COLOR_GREY - -#define COLOR_UBL COLOR_WHITE - -#define COLOR_TOUCH_CALIBRATION COLOR_WHITE - -#define COLOR_KILL_SCREEN_BG COLOR_MAROON -#define COLOR_KILL_SCREEN_TEXT COLOR_WHITE +#ifndef COLOR_BACKGROUND + #define COLOR_BACKGROUND 0x20AC // #1E156E +#endif +#ifndef COLOR_SELECTION_BG + #define COLOR_SELECTION_BG 0x9930 // #992380 +#endif +#ifndef COLOR_WEBSITE_URL + #define COLOR_WEBSITE_URL 0x03B7 +#endif + +#ifndef COLOR_INACTIVE + #define COLOR_INACTIVE COLOR_GREY +#endif +#ifndef COLOR_COLD + #define COLOR_COLD COLOR_AQUA +#endif +#ifndef COLOR_HOTEND + #define COLOR_HOTEND COLOR_SCARLET +#endif +#ifndef COLOR_HEATED_BED + #define COLOR_HEATED_BED COLOR_DARK_ORANGE +#endif +#ifndef COLOR_CHAMBER + #define COLOR_CHAMBER COLOR_DARK_ORANGE +#endif +#ifndef COLOR_FAN + #define COLOR_FAN COLOR_AQUA +#endif + +#ifndef COLOR_AXIS_HOMED + #define COLOR_AXIS_HOMED COLOR_WHITE +#endif +#ifndef COLOR_AXIS_NOT_HOMED + #define COLOR_AXIS_NOT_HOMED COLOR_YELLOW +#endif + +#ifndef COLOR_RATE_100 + #define COLOR_RATE_100 COLOR_VIVID_GREEN +#endif +#ifndef COLOR_RATE_ALTERED + #define COLOR_RATE_ALTERED COLOR_YELLOW +#endif + +#ifndef COLOR_PRINT_TIME + #define COLOR_PRINT_TIME COLOR_AQUA +#endif + +#ifndef COLOR_PROGRESS_FRAME + #define COLOR_PROGRESS_FRAME COLOR_WHITE +#endif +#ifndef COLOR_PROGRESS_BAR + #define COLOR_PROGRESS_BAR COLOR_BLUE +#endif +#ifndef COLOR_PROGRESS_BG + #define COLOR_PROGRESS_BG COLOR_BLACK +#endif + +#ifndef COLOR_STATUS_MESSAGE + #define COLOR_STATUS_MESSAGE COLOR_YELLOW +#endif + +#ifndef COLOR_CONTROL_ENABLED + #define COLOR_CONTROL_ENABLED COLOR_WHITE +#endif +#ifndef COLOR_CONTROL_DISABLED + #define COLOR_CONTROL_DISABLED COLOR_GREY +#endif +#ifndef COLOR_CONTROL_CANCEL + #define COLOR_CONTROL_CANCEL COLOR_SCARLET +#endif +#ifndef COLOR_CONTROL_CONFIRM + #define COLOR_CONTROL_CONFIRM COLOR_VIVID_GREEN +#endif +#ifndef COLOR_BUSY + #define COLOR_BUSY COLOR_SILVER +#endif + +#ifndef COLOR_MENU_TEXT + #define COLOR_MENU_TEXT COLOR_YELLOW +#endif +#ifndef COLOR_MENU_VALUE + #define COLOR_MENU_VALUE COLOR_WHITE +#endif + +#ifndef COLOR_SLIDER + #define COLOR_SLIDER COLOR_WHITE +#endif +#ifndef COLOR_SLIDER_INACTIVE + #define COLOR_SLIDER_INACTIVE COLOR_GREY +#endif + +#ifndef COLOR_UBL + #define COLOR_UBL COLOR_WHITE +#endif + +#ifndef COLOR_TOUCH_CALIBRATION + #define COLOR_TOUCH_CALIBRATION COLOR_WHITE +#endif + +#ifndef COLOR_KILL_SCREEN_BG + #define COLOR_KILL_SCREEN_BG COLOR_MAROON +#endif +#ifndef COLOR_KILL_SCREEN_TEXT + #define COLOR_KILL_SCREEN_TEXT COLOR_WHITE +#endif diff --git a/Marlin/src/lcd/tft/tft_image.cpp b/Marlin/src/lcd/tft/tft_image.cpp index ff60bee9a9..27749cb7f3 100644 --- a/Marlin/src/lcd/tft/tft_image.cpp +++ b/Marlin/src/lcd/tft/tft_image.cpp @@ -45,6 +45,8 @@ const tImage Fan_Slow1_64x64x4 = { (void *)fan_slow1_64x64x4, 64, 64, GREYS const tImage Fan_Fast0_64x64x4 = { (void *)fan_fast0_64x64x4, 64, 64, GREYSCALE4 }; const tImage Fan_Fast1_64x64x4 = { (void *)fan_fast1_64x64x4, 64, 64, GREYSCALE4 }; const tImage SD_64x64x4 = { (void *)sd_64x64x4, 64, 64, GREYSCALE4 }; +const tImage Home_64x64x4 = { (void *)home_64x64x4, 64, 64, GREYSCALE4 }; +const tImage BtnRounded_64x52x4 = { (void *)btn_rounded_64x52x4, 64, 52, GREYSCALE4 }; const tImage Menu_64x64x4 = { (void *)menu_64x64x4, 64, 64, GREYSCALE4 }; const tImage Settings_64x64x4 = { (void *)settings_64x64x4, 64, 64, GREYSCALE4 }; const tImage Confirm_64x64x4 = { (void *)confirm_64x64x4, 64, 64, GREYSCALE4 }; diff --git a/Marlin/src/lcd/tft/tft_image.h b/Marlin/src/lcd/tft/tft_image.h index cf48065968..1f13967ba2 100644 --- a/Marlin/src/lcd/tft/tft_image.h +++ b/Marlin/src/lcd/tft/tft_image.h @@ -39,6 +39,8 @@ extern const uint8_t fan0_64x64x4[], fan1_64x64x4[]; extern const uint8_t fan_slow0_64x64x4[], fan_slow1_64x64x4[]; extern const uint8_t fan_fast0_64x64x4[], fan_fast1_64x64x4[]; extern const uint8_t sd_64x64x4[]; +extern const uint8_t home_64x64x4[]; +extern const uint8_t btn_rounded_64x52x4[]; extern const uint8_t menu_64x64x4[]; extern const uint8_t settings_64x64x4[]; extern const uint8_t confirm_64x64x4[]; @@ -90,6 +92,8 @@ enum MarlinImage : uint8_t { imgRefresh, imgLeveling, imgSlider, + imgHome, + imgBtn52Rounded, imgCount, noImage = imgCount, imgPageUp = imgLeft, @@ -136,6 +140,8 @@ extern const tImage Fan_Slow1_64x64x4; extern const tImage Fan_Fast0_64x64x4; extern const tImage Fan_Fast1_64x64x4; extern const tImage SD_64x64x4; +extern const tImage Home_64x64x4; +extern const tImage BtnRounded_64x52x4; extern const tImage Menu_64x64x4; extern const tImage Settings_64x64x4; extern const tImage Confirm_64x64x4; diff --git a/Marlin/src/lcd/tft/touch.cpp b/Marlin/src/lcd/tft/touch.cpp index d2b860ab15..d19cc4bf1d 100644 --- a/Marlin/src/lcd/tft/touch.cpp +++ b/Marlin/src/lcd/tft/touch.cpp @@ -35,6 +35,7 @@ #include "tft.h" +bool Touch::enabled = true; int16_t Touch::x, Touch::y; touch_control_t Touch::controls[]; touch_control_t *Touch::current_control; @@ -54,6 +55,7 @@ void Touch::init() { calibration_reset(); reset(); io.Init(); + enable(); } void Touch::add_control(TouchControlType type, uint16_t x, uint16_t y, uint16_t width, uint16_t height, int32_t data) { @@ -72,6 +74,8 @@ void Touch::idle() { uint16_t i; int16_t _x, _y; + if (!enabled) return; + if (now == millis()) return; now = millis(); @@ -253,6 +257,13 @@ void Touch::touch(touch_control_t *control) { case UBL: hold(control, UBL_REPEAT_DELAY); ui.encoderPosition += control->data; break; #endif + case MOVE_AXIS: + ui.goto_screen((screenFunc_t)ui.move_axis_screen); + break; + + // TODO: TOUCH could receive data to pass to the callback + case BUTTON: ((screenFunc_t)control->data)(); break; + default: break; } } diff --git a/Marlin/src/lcd/tft/touch.h b/Marlin/src/lcd/tft/touch.h index f3e53ae461..7d8f222918 100644 --- a/Marlin/src/lcd/tft/touch.h +++ b/Marlin/src/lcd/tft/touch.h @@ -79,6 +79,8 @@ enum TouchControlType : uint16_t { FEEDRATE, FLOWRATE, UBL, + MOVE_AXIS, + BUTTON, }; typedef void (*screenFunc_t)(); @@ -132,6 +134,7 @@ class Touch { private: static TOUCH_DRIVER io; static int16_t x, y; + static bool enabled; static touch_control_t controls[MAX_CONTROLS]; static touch_control_t *current_control; @@ -162,6 +165,8 @@ class Touch { static void clear() { controls_count = 0; } static void idle(); static bool is_clicked() { return touch_control_type == CLICK; } + static void disable() { enabled = false; } + static void enable() { enabled = true; } static void add_control(TouchControlType type, uint16_t x, uint16_t y, uint16_t width, uint16_t height, int32_t data = 0); diff --git a/Marlin/src/lcd/tft/ui_320x240.cpp b/Marlin/src/lcd/tft/ui_320x240.cpp index a4ac1465ea..de8498c5ff 100644 --- a/Marlin/src/lcd/tft/ui_320x240.cpp +++ b/Marlin/src/lcd/tft/ui_320x240.cpp @@ -603,7 +603,7 @@ void MenuItem_confirm::draw_select_screen(PGM_P const yes, PGM_P const no, const touch.clear(); if (calibration_stage < CALIBRATION_SUCCESS) { - switch(calibration_stage) { + switch (calibration_stage) { case CALIBRATION_POINT_1: tft_string.set("Top Left"); break; case CALIBRATION_POINT_2: y = TFT_HEIGHT - 21; tft_string.set("Bottom Left"); break; case CALIBRATION_POINT_3: x = TFT_WIDTH - 21; tft_string.set("Top Right"); break; @@ -650,4 +650,7 @@ void menu_item(const uint8_t row, bool sel ) { TERN_(TOUCH_SCREEN, touch.add_control(sel ? CLICK : MENU_ITEM, 0, 2 + 34 * row, 320, 32, encoderTopLine + row)); } +void MarlinUI::move_axis_screen() { +} + #endif // HAS_UI_320x240 diff --git a/Marlin/src/lcd/tft/ui_320x240.h b/Marlin/src/lcd/tft/ui_320x240.h index ed69acbcd2..c9822f11cc 100644 --- a/Marlin/src/lcd/tft/ui_320x240.h +++ b/Marlin/src/lcd/tft/ui_320x240.h @@ -73,6 +73,8 @@ const tImage Images[imgCount] = { Refresh_32x32x4, Leveling_32x32x4, Slider8x16x4, + Home_64x64x4, + BtnRounded_64x52x4, }; #if HAS_TEMP_CHAMBER && HOTENDS > 1 diff --git a/Marlin/src/lcd/tft/ui_480x320.cpp b/Marlin/src/lcd/tft/ui_480x320.cpp index c9f0bfd0e9..ffc619e8dc 100644 --- a/Marlin/src/lcd/tft/ui_480x320.cpp +++ b/Marlin/src/lcd/tft/ui_480x320.cpp @@ -291,6 +291,7 @@ void MarlinUI::draw_status_screen() { offset += 32 - tft_string.width(); } tft.add_text(455 - tft_string.width() - offset, 3, is_homed ? COLOR_AXIS_HOMED : COLOR_AXIS_NOT_HOMED, tft_string); + TERN_(TOUCH_SCREEN, touch.add_control(MOVE_AXIS, 4, 132, TFT_WIDTH - 8, 34)); // feed rate tft.canvas(96, 180, 100, 32); @@ -607,7 +608,7 @@ void MenuItem_confirm::draw_select_screen(PGM_P const yes, PGM_P const no, const touch.clear(); if (calibration_stage < CALIBRATION_SUCCESS) { - switch(calibration_stage) { + switch (calibration_stage) { case CALIBRATION_POINT_1: tft_string.set("Top Left"); break; case CALIBRATION_POINT_2: y = TFT_HEIGHT - 21; tft_string.set("Bottom Left"); break; case CALIBRATION_POINT_3: x = TFT_WIDTH - 21; tft_string.set("Top Right"); break; @@ -654,4 +655,432 @@ void menu_item(const uint8_t row, bool sel ) { TERN_(TOUCH_SCREEN, touch.add_control(sel ? CLICK : MENU_ITEM, 0, 4 + 45 * row, TFT_WIDTH, 43, encoderTopLine + row)); } +#if ENABLED(BABYSTEP_ZPROBE_OFFSET) + #include "../../feature/babystep.h" +#endif + +#if HAS_BED_PROBE + #include "../../module/probe.h" +#endif + +#define Z_SELECTION_Z 1 +#define Z_SELECTION_Z_PROBE -1 + +struct MotionAxisState { + xy_int_t xValuePos, yValuePos, zValuePos, eValuePos, stepValuePos, zTypePos, eNamePos; + float currentStepSize = 10.0; + int z_selection = Z_SELECTION_Z; + uint8_t e_selection = 0; + bool homming = false; + bool blocked = false; + char message[32]; +}; + +MotionAxisState motionAxisState; + +#define E_BTN_COLOR COLOR_YELLOW +#define X_BTN_COLOR COLOR_CORAL_RED +#define Y_BTN_COLOR COLOR_VIVID_GREEN +#define Z_BTN_COLOR COLOR_LIGHT_BLUE + +#define BTN_WIDTH 64 +#define BTN_HEIGHT 52 +#define X_MARGIN 20 +#define Y_MARGIN 15 + +static void quick_feedback() { + #if HAS_CHIRP + ui.chirp(); // Buzz and wait. Is the delay needed for buttons to settle? + #if BOTH(HAS_LCD_MENU, USE_BEEPER) + for (int8_t i = 5; i--;) { buzzer.tick(); delay(2); } + #elif HAS_LCD_MENU + delay(10); + #endif + #endif +} + +#define CUR_STEP_VALUE_WIDTH 104 +static void drawCurStepValue() { + tft_string.set((uint8_t *)ftostr52sp(motionAxisState.currentStepSize)); + tft_string.add("mm"); + tft.canvas(motionAxisState.stepValuePos.x, motionAxisState.stepValuePos.y, CUR_STEP_VALUE_WIDTH, BTN_HEIGHT); + tft.set_background(COLOR_BACKGROUND); + tft.add_text(tft_string.center(CUR_STEP_VALUE_WIDTH), 0, COLOR_AXIS_HOMED, tft_string); +} + +static void drawCurZSelection() { + tft_string.set("Z"); + tft.canvas(motionAxisState.zTypePos.x, motionAxisState.zTypePos.y, tft_string.width(), 34); + tft.set_background(COLOR_BACKGROUND); + tft.add_text(0, 0, Z_BTN_COLOR, tft_string); + tft.queue.sync(); + tft_string.set("Offset"); + tft.canvas(motionAxisState.zTypePos.x, motionAxisState.zTypePos.y + 34, tft_string.width(), 34); + tft.set_background(COLOR_BACKGROUND); + if (motionAxisState.z_selection == Z_SELECTION_Z_PROBE) { + tft.add_text(0, 0, Z_BTN_COLOR, tft_string); + } +} + +static void drawCurESelection() { + tft.canvas(motionAxisState.eNamePos.x, motionAxisState.eNamePos.y, BTN_WIDTH, BTN_HEIGHT); + tft.set_background(COLOR_BACKGROUND); + tft_string.set("E"); + tft.add_text(0, 0, E_BTN_COLOR , tft_string); + tft.add_text(tft_string.width(), 0, E_BTN_COLOR, ui8tostr3rj(motionAxisState.e_selection)); +} + +static void drawMessage(const char *msg) { + tft.canvas(X_MARGIN, TFT_HEIGHT - Y_MARGIN - 34, TFT_HEIGHT / 2, 34); + tft.set_background(COLOR_BACKGROUND); + tft.add_text(0, 0, COLOR_YELLOW, msg); +} + +static void drawAxisValue(AxisEnum axis) { + const float value = + #if HAS_BED_PROBE + axis == Z_AXIS && motionAxisState.z_selection == Z_SELECTION_Z_PROBE ? + probe.offset.z : + #endif + NATIVE_TO_LOGICAL( + ui.manual_move.processing ? destination[axis] : current_position[axis] + TERN0(IS_KINEMATIC, ui.manual_move.offset), + axis + ); + xy_int_t pos; + uint16_t color; + switch (axis) { + case X_AXIS: pos = motionAxisState.xValuePos; color = X_BTN_COLOR; break; + case Y_AXIS: pos = motionAxisState.yValuePos; color = Y_BTN_COLOR; break; + case Z_AXIS: pos = motionAxisState.zValuePos; color = Z_BTN_COLOR; break; + case E_AXIS: pos = motionAxisState.eValuePos; color = E_BTN_COLOR; break; + default: return; + } + tft.canvas(pos.x, pos.y, BTN_WIDTH + X_MARGIN, BTN_HEIGHT); + tft.set_background(COLOR_BACKGROUND); + tft_string.set(ftostr52sp(value)); + tft.add_text(0, 0, color, tft_string); +} + +static void moveAxis(AxisEnum axis, const int8_t direction) { + quick_feedback(); + + if (axis == E_AXIS && thermalManager.temp_hotend[motionAxisState.e_selection].celsius < EXTRUDE_MINTEMP) { + drawMessage("Too cold"); + return; + } + + const float diff = motionAxisState.currentStepSize * direction; + + if (axis == Z_AXIS && motionAxisState.z_selection == Z_SELECTION_Z_PROBE) { + #if ENABLED(BABYSTEP_ZPROBE_OFFSET) + const int16_t babystep_increment = direction * BABYSTEP_SIZE_Z; + const bool do_probe = DISABLED(BABYSTEP_HOTEND_Z_OFFSET) || active_extruder == 0; + const float bsDiff = planner.steps_to_mm[Z_AXIS] * babystep_increment, + new_probe_offset = probe.offset.z + bsDiff, + new_offs = TERN(BABYSTEP_HOTEND_Z_OFFSET + , do_probe ? new_probe_offset : hotend_offset[active_extruder].z - bsDiff + , new_probe_offset + ); + if (WITHIN(new_offs, Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX)) { + babystep.add_steps(Z_AXIS, babystep_increment); + if (do_probe) + probe.offset.z = new_offs; + else + TERN(BABYSTEP_HOTEND_Z_OFFSET, hotend_offset[active_extruder].z = new_offs, NOOP); + drawMessage(""); // clear the error + drawAxisValue(axis); + } + else { + drawMessage(GET_TEXT(MSG_LCD_SOFT_ENDSTOPS)); + } + #elif HAS_BED_PROBE + // only change probe.offset.z + probe.offset.z += diff; + if (direction < 0 && current_position[axis] < Z_PROBE_OFFSET_RANGE_MIN) { + current_position[axis] = Z_PROBE_OFFSET_RANGE_MIN; + drawMessage(GET_TEXT(MSG_LCD_SOFT_ENDSTOPS)); + } + else if (direction > 0 && current_position[axis] > Z_PROBE_OFFSET_RANGE_MAX) { + current_position[axis] = Z_PROBE_OFFSET_RANGE_MAX; + drawMessage(GET_TEXT(MSG_LCD_SOFT_ENDSTOPS)); + } + else { + drawMessage(""); // clear the error + } + drawAxisValue(axis); + #endif + return; + } + + if (!ui.manual_move.processing) { + // Start with no limits to movement + float min = current_position[axis] - 1000, + max = current_position[axis] + 1000; + + // Limit to software endstops, if enabled + #if HAS_SOFTWARE_ENDSTOPS + if (soft_endstops_enabled) switch (axis) { + case X_AXIS: + TERN_(MIN_SOFTWARE_ENDSTOP_X, min = soft_endstop.min.x); + TERN_(MAX_SOFTWARE_ENDSTOP_X, max = soft_endstop.max.x); + break; + case Y_AXIS: + TERN_(MIN_SOFTWARE_ENDSTOP_Y, min = soft_endstop.min.y); + TERN_(MAX_SOFTWARE_ENDSTOP_Y, max = soft_endstop.max.y); + break; + case Z_AXIS: + TERN_(MIN_SOFTWARE_ENDSTOP_Z, min = soft_endstop.min.z); + TERN_(MAX_SOFTWARE_ENDSTOP_Z, max = soft_endstop.max.z); + default: break; + } + #endif // HAS_SOFTWARE_ENDSTOPS + + // Delta limits XY based on the current offset from center + // This assumes the center is 0,0 + #if ENABLED(DELTA) + if (axis != Z_AXIS && axis != E_AXIS) { + max = SQRT(sq((float)(DELTA_PRINTABLE_RADIUS)) - sq(current_position[Y_AXIS - axis])); // (Y_AXIS - axis) == the other axis + min = -max; + } + #endif + + // Get the new position + #if IS_KINEMATIC + ui.manual_move.offset += diff; + if (direction < 0) + NOLESS(ui.manual_move.offset, min - current_position[axis]); + else + NOMORE(ui.manual_move.offset, max - current_position[axis]); + #else + current_position[axis] += diff; + if (direction < 0 && current_position[axis] < min) { + current_position[axis] = min; + drawMessage(GET_TEXT(MSG_LCD_SOFT_ENDSTOPS)); + } + else if (direction > 0 && current_position[axis] > max) { + current_position[axis] = max; + drawMessage(GET_TEXT(MSG_LCD_SOFT_ENDSTOPS)); + } + else { + drawMessage(""); // clear the error + } + #endif + + ui.manual_move.soon(axis + #if MULTI_MANUAL + , motionAxisState.e_selection + #endif + ); + } + + drawAxisValue(axis); +} + +static void e_plus() { + moveAxis(E_AXIS, 1); +} + +static void e_minus() { + moveAxis(E_AXIS, -1); +} + +static void x_minus() { + moveAxis(X_AXIS, -1); +} + +static void x_plus() { + moveAxis(X_AXIS, 1); +} + +static void y_plus() { + moveAxis(Y_AXIS, 1); +} + +static void y_minus() { + moveAxis(Y_AXIS, -1); +} + +static void z_plus() { + moveAxis(Z_AXIS, 1); +} + +static void z_minus() { + moveAxis(Z_AXIS, -1); +} + +static void e_select() { + motionAxisState.e_selection++; + if (motionAxisState.e_selection >= EXTRUDERS) { + motionAxisState.e_selection = 0; + } + + quick_feedback(); + drawCurESelection(); + drawAxisValue(E_AXIS); +} + +static void do_home() { + quick_feedback(); + drawMessage(GET_TEXT(MSG_LEVEL_BED_HOMING)); + queue.inject_P(G28_STR); + // Disable touch until home is done + touch.disable(); + drawAxisValue(E_AXIS); + drawAxisValue(X_AXIS); + drawAxisValue(Y_AXIS); + drawAxisValue(Z_AXIS); +} + +static void step_size() { + motionAxisState.currentStepSize = motionAxisState.currentStepSize / 10.0; + if (motionAxisState.currentStepSize < 0.0015) motionAxisState.currentStepSize = 10.0; + quick_feedback(); + drawCurStepValue(); +} + +#if HAS_BED_PROBE + static void z_select() { + motionAxisState.z_selection *= -1; + quick_feedback(); + drawCurZSelection(); + drawAxisValue(Z_AXIS); + } +#endif + +static void disable_steppers() { + quick_feedback(); + queue.inject_P(PSTR("M84")); +} + +static void drawBtn(int x, int y, const char* label, int32_t data, MarlinImage img, uint16_t bgColor, bool enabled = true) { + uint16_t width = Images[imgBtn52Rounded].width; + uint16_t height = Images[imgBtn52Rounded].height; + + if (!enabled) bgColor = COLOR_CONTROL_DISABLED; + + tft.canvas(x, y, width, height); + tft.set_background(COLOR_BACKGROUND); + tft.add_image(0, 0, imgBtn52Rounded, bgColor, COLOR_BACKGROUND, COLOR_DARKGREY); + + // TODO: Make an add_text() taking a font arg + if (label != NULL) { + tft_string.set(label); + tft_string.trim(); + tft.add_text(tft_string.center(width), height / 2 - tft_string.font_height() / 2, bgColor, tft_string); + } + else { + tft.add_image(0, 0, img, bgColor, COLOR_BACKGROUND, COLOR_DARKGREY); + } + + if (enabled) touch.add_control(BUTTON, x, y, width, height, data); +} + +void MarlinUI::move_axis_screen() { + // Reset + defer_status_screen(true); + motionAxisState.blocked = false; + touch.enable(); + + ui.clear_lcd(); + + TERN_(TOUCH_SCREEN, touch.clear()); + + const bool busy = printingIsActive(); + + // if we have baby step and we are printing, select baby step + if (busy && ENABLED(BABYSTEP_ZPROBE_OFFSET)) motionAxisState.z_selection = Z_SELECTION_Z_PROBE; + + // ROW 1 -> E- Y- CurY Z+ + int x = X_MARGIN, y = Y_MARGIN, spacing = 0; + + drawBtn(x, y, "E+", (int32_t)e_plus, imgUp, E_BTN_COLOR, !busy); + + spacing = (TFT_WIDTH - X_MARGIN * 2 - 3 * BTN_WIDTH) / 2; + x += BTN_WIDTH + spacing; + drawBtn(x, y, "Y+", (int32_t)y_plus, imgUp, Y_BTN_COLOR, !busy); + + // Cur Y + x += BTN_WIDTH; + motionAxisState.yValuePos.x = x + 2; + motionAxisState.yValuePos.y = y; + drawAxisValue(Y_AXIS); + + x += spacing; + drawBtn(x, y, "Z+", (int32_t)z_plus, imgUp, Z_BTN_COLOR, !busy || ENABLED(BABYSTEP_ZPROBE_OFFSET)); //only enabled when not busy or have baby step + + // ROW 2 -> "Ex" X- HOME X+ "Z" + y += BTN_HEIGHT + (TFT_HEIGHT - Y_MARGIN * 2 - 4 * BTN_HEIGHT) / 3; + x = X_MARGIN; + spacing = (TFT_WIDTH - X_MARGIN * 2 - 5 * BTN_WIDTH) / 4; + + motionAxisState.eNamePos.x = x; + motionAxisState.eNamePos.y = y; + drawCurESelection(); + if (!busy) touch.add_control(BUTTON, x, y, BTN_WIDTH, BTN_HEIGHT, (int32_t)e_select); + + x += BTN_WIDTH + spacing; + drawBtn(x, y, "X-", (int32_t)x_minus, imgLeft, X_BTN_COLOR, !busy); + + x += BTN_WIDTH + spacing; //imgHome is 64x64 + add_control(TFT_WIDTH / 2 - Images[imgHome].width / 2, y - (Images[imgHome].width - BTN_HEIGHT) / 2, BUTTON, (int32_t)do_home, imgHome, !busy); + + x += BTN_WIDTH + spacing; + uint16_t xplus_x = x; + drawBtn(x, y, "X+", (int32_t)x_plus, imgRight, X_BTN_COLOR, !busy); + + x += BTN_WIDTH + spacing; + motionAxisState.zTypePos.x = x; + motionAxisState.zTypePos.y = y; + drawCurZSelection(); + #if HAS_BED_PROBE + if (!busy) touch.add_control(BUTTON, x, y, BTN_WIDTH, 34 * 2, (int32_t)z_select); + #endif + + // ROW 3 -> E- CurX Y- Z- + y += BTN_HEIGHT + (TFT_HEIGHT - Y_MARGIN * 2 - 4 * BTN_HEIGHT) / 3; + x = X_MARGIN; + spacing = (TFT_WIDTH - X_MARGIN * 2 - 3 * BTN_WIDTH) / 2; + + drawBtn(x, y, "E-", (int32_t)e_minus, imgDown, E_BTN_COLOR, !busy); + + // Cur E + motionAxisState.eValuePos.x = x; + motionAxisState.eValuePos.y = y + BTN_HEIGHT + 2; + drawAxisValue(E_AXIS); + + // Cur X + motionAxisState.xValuePos.x = BTN_WIDTH + (TFT_WIDTH - X_MARGIN * 2 - 5 * BTN_WIDTH) / 4; //X- pos + motionAxisState.xValuePos.y = y - 10; + drawAxisValue(X_AXIS); + + x += BTN_WIDTH + spacing; + drawBtn(x, y, "Y-", (int32_t)y_minus, imgDown, Y_BTN_COLOR, !busy); + + x += BTN_WIDTH + spacing; + drawBtn(x, y, "Z-", (int32_t)z_minus, imgDown, Z_BTN_COLOR, !busy || ENABLED(BABYSTEP_ZPROBE_OFFSET)); //only enabled when not busy or have baby step + + // Cur Z + motionAxisState.zValuePos.x = x; + motionAxisState.zValuePos.y = y + BTN_HEIGHT + 2; + drawAxisValue(Z_AXIS); + + // ROW 4 -> step_size disable steppers back + y = TFT_HEIGHT - Y_MARGIN - 32; // + x = TFT_WIDTH / 2 - CUR_STEP_VALUE_WIDTH / 2; + motionAxisState.stepValuePos.x = x; + motionAxisState.stepValuePos.y = y; + if (!busy) { + drawCurStepValue(); + touch.add_control(BUTTON, motionAxisState.stepValuePos.x, motionAxisState.stepValuePos.y, CUR_STEP_VALUE_WIDTH, BTN_HEIGHT, (int32_t)step_size); + } + + // alinged with x+ + drawBtn(xplus_x, TFT_HEIGHT - Y_MARGIN - BTN_HEIGHT, "off", (int32_t)disable_steppers, imgCancel, COLOR_WHITE, !busy); + + add_control(TFT_WIDTH - X_MARGIN - BTN_WIDTH, y, BACK, imgBack); +} + +#undef BTN_WIDTH +#undef BTN_HEIGHT + #endif // HAS_UI_480x320 diff --git a/Marlin/src/lcd/tft/ui_480x320.h b/Marlin/src/lcd/tft/ui_480x320.h index d803df4a24..053ee78158 100644 --- a/Marlin/src/lcd/tft/ui_480x320.h +++ b/Marlin/src/lcd/tft/ui_480x320.h @@ -73,6 +73,8 @@ const tImage Images[imgCount] = { Refresh_32x32x4, Leveling_32x32x4, Slider8x16x4, + Home_64x64x4, + BtnRounded_64x52x4, }; #if HAS_TEMP_CHAMBER && HOTENDS > 1 diff --git a/Marlin/src/lcd/thermistornames.h b/Marlin/src/lcd/thermistornames.h index bd0ca0e554..37f285d483 100644 --- a/Marlin/src/lcd/thermistornames.h +++ b/Marlin/src/lcd/thermistornames.h @@ -108,6 +108,8 @@ #define THERMISTOR_NAME "100k with 10k pull-up" // Modified thermistors +#elif THERMISTOR_ID == 30 + #define THERMISTOR_NAME "Kis3d EN AW NTC100K/3950" #elif THERMISTOR_ID == 51 #define THERMISTOR_NAME "EPCOS 1K" #elif THERMISTOR_ID == 52 diff --git a/Marlin/src/lcd/touch/touch_buttons.cpp b/Marlin/src/lcd/touch/touch_buttons.cpp index 8eae73df11..c97018c379 100644 --- a/Marlin/src/lcd/touch/touch_buttons.cpp +++ b/Marlin/src/lcd/touch/touch_buttons.cpp @@ -74,7 +74,7 @@ TouchButtons touch; void TouchButtons::init() { touchIO.Init(); } uint8_t TouchButtons::read_buttons() { - #ifdef HAS_SPI_LCD + #ifdef HAS_WIRED_LCD int16_t x, y; if (!touchIO.getRawPoint(&x, &y)) return 0; diff --git a/Marlin/src/lcd/ultralcd.cpp b/Marlin/src/lcd/ultralcd.cpp index b30f6e49c9..de534e4023 100644 --- a/Marlin/src/lcd/ultralcd.cpp +++ b/Marlin/src/lcd/ultralcd.cpp @@ -51,7 +51,7 @@ MarlinUI ui; constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #if ENABLED(STATUS_MESSAGE_SCROLLING) uint8_t MarlinUI::status_scroll_offset; // = 0 constexpr uint8_t MAX_MESSAGE_LENGTH = _MAX(LONG_FILENAME_LENGTH, MAX_LANG_CHARSIZE * 2 * (LCD_WIDTH)); @@ -62,7 +62,7 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; constexpr uint8_t MAX_MESSAGE_LENGTH = 63; #endif -#if EITHER(HAS_SPI_LCD, EXTENSIBLE_UI) +#if EITHER(HAS_WIRED_LCD, EXTENSIBLE_UI) uint8_t MarlinUI::alert_level; // = 0 char MarlinUI::status_message[MAX_MESSAGE_LENGTH + 1]; #endif @@ -114,9 +114,9 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; } #endif -#if HAS_SPI_LCD +#if HAS_WIRED_LCD -#if HAS_GRAPHICAL_LCD +#if HAS_MARLINUI_U8GLIB #include "dogm/ultralcd_DOGM.h" #endif @@ -167,7 +167,7 @@ uint8_t MarlinUI::lcd_status_update_delay = 1; // First update one loop delayed millis_t MarlinUI::next_button_update_ms; // = 0 -#if HAS_GRAPHICAL_LCD +#if HAS_MARLINUI_U8GLIB bool MarlinUI::drawing_screen, MarlinUI::first_page; // = false #endif @@ -372,7 +372,7 @@ void MarlinUI::init() { #endif // HAS_SHIFT_ENCODER - #if HAS_ENCODER_ACTION && HAS_SLOW_BUTTONS + #if BOTH(HAS_ENCODER_ACTION, HAS_SLOW_BUTTONS) slow_buttons = 0; #endif @@ -506,7 +506,7 @@ bool MarlinUI::get_blink() { * This is very display-dependent, so the lcd implementation draws this. */ -#if ENABLED(LCD_PROGRESS_BAR) +#if ENABLED(LCD_PROGRESS_BAR) && !IS_TFTGLCD_PANEL millis_t MarlinUI::progress_bar_ms; // = 0 #if PROGRESS_MSG_EXPIRE > 0 millis_t MarlinUI::expire_status_ms; // = 0 @@ -517,7 +517,7 @@ void MarlinUI::status_screen() { TERN_(HAS_LCD_MENU, ENCODER_RATE_MULTIPLY(false)); - #if ENABLED(LCD_PROGRESS_BAR) + #if ENABLED(LCD_PROGRESS_BAR) && !IS_TFTGLCD_PANEL // // HD44780 implements the following message blinking and @@ -695,7 +695,7 @@ void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) { #if IS_KINEMATIC - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER const int8_t old_extruder = active_extruder; if (axis == E_AXIS) active_extruder = e_index; #endif @@ -716,9 +716,7 @@ void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) { prepare_internal_move_to_destination(fr_mm_s); // will set current_position from destination processing = false; - #if EXTRUDERS > 1 - active_extruder = old_extruder; - #endif + TERN_(HAS_MULTI_EXTRUDER, active_extruder = old_extruder); #else @@ -875,7 +873,7 @@ void MarlinUI::update() { #endif // HAS_LCD_MENU - if (ELAPSED(ms, next_lcd_update_ms) || TERN0(HAS_GRAPHICAL_LCD, drawing_screen)) { + if (ELAPSED(ms, next_lcd_update_ms) || TERN0(HAS_MARLINUI_U8GLIB, drawing_screen)) { next_lcd_update_ms = ms + LCD_UPDATE_INTERVAL; @@ -917,7 +915,7 @@ void MarlinUI::update() { const bool encoderPastThreshold = (abs_diff >= epps); if (encoderPastThreshold || lcd_clicked) { - if (encoderPastThreshold) { + if (encoderPastThreshold && TERN1(IS_TFTGLCD_PANEL, !external_control)) { #if BOTH(HAS_LCD_MENU, ENCODER_RATE_MULTIPLIER) @@ -973,7 +971,7 @@ void MarlinUI::update() { // This runs every ~100ms when idling often enough. // Instead of tracking changes just redraw the Status Screen once per second. if (on_status_screen() && !lcd_status_update_delay--) { - lcd_status_update_delay = TERN(HAS_GRAPHICAL_LCD, 12, 9); + lcd_status_update_delay = TERN(HAS_MARLINUI_U8GLIB, 12, 9); if (max_display_update_time) max_display_update_time--; // Be sure never go to a very big number refresh(LCDVIEW_REDRAW_NOW); } @@ -1012,7 +1010,7 @@ void MarlinUI::update() { TERN_(HAS_ADC_BUTTONS, keypad_buttons = 0); - #if HAS_GRAPHICAL_LCD + #if HAS_MARLINUI_U8GLIB #if ENABLED(LIGHTWEIGHT_UI) const bool in_status = on_status_screen(), @@ -1262,6 +1260,12 @@ void MarlinUI::update() { TERN(REPRAPWORLD_KEYPAD, keypad_buttons, buttons) = ~val; #endif + #if IS_TFTGLCD_PANEL + next_button_update_ms = now + (LCD_UPDATE_INTERVAL / 2); + buttons = slow_buttons; + TERN_(AUTO_BED_LEVELING_UBL, external_encoder()); + #endif + } // next_button_update_ms #if HAS_ENCODER_WHEEL @@ -1296,7 +1300,7 @@ void MarlinUI::update() { #endif // HAS_ENCODER_ACTION -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD #if HAS_DISPLAY @@ -1333,7 +1337,7 @@ void MarlinUI::update() { const millis_t ms = millis(); #endif - #if ENABLED(LCD_PROGRESS_BAR) + #if ENABLED(LCD_PROGRESS_BAR) && !IS_TFTGLCD_PANEL progress_bar_ms = ms; #if PROGRESS_MSG_EXPIRE > 0 expire_status_ms = persist ? 0 : ms + PROGRESS_MSG_EXPIRE; @@ -1344,7 +1348,7 @@ void MarlinUI::update() { next_filament_display = ms + 5000UL; // Show status message for 5s #endif - #if BOTH(HAS_SPI_LCD, STATUS_MESSAGE_SCROLLING) + #if BOTH(HAS_WIRED_LCD, STATUS_MESSAGE_SCROLLING) status_scroll_offset = 0; #endif @@ -1503,7 +1507,7 @@ void MarlinUI::update() { set_status_P(print_paused); #if ENABLED(PARK_HEAD_ON_PAUSE) - TERN_(HAS_SPI_LCD, lcd_pause_show_message(PAUSE_MESSAGE_PARKING, PAUSE_MODE_PAUSE_PRINT)); // Show message immediately to let user know about pause in progress + TERN_(HAS_WIRED_LCD, lcd_pause_show_message(PAUSE_MESSAGE_PARKING, PAUSE_MODE_PAUSE_PRINT)); // Show message immediately to let user know about pause in progress queue.inject_P(PSTR("M25 P\nM24")); #elif ENABLED(SDSUPPORT) queue.inject_P(PSTR("M25")); @@ -1612,11 +1616,11 @@ void MarlinUI::update() { refresh(); - #if HAS_SPI_LCD || defined(LED_BACKLIGHT_TIMEOUT) + #if HAS_WIRED_LCD || defined(LED_BACKLIGHT_TIMEOUT) const millis_t ms = millis(); #endif - TERN_(HAS_SPI_LCD, next_lcd_update_ms = ms + LCD_UPDATE_INTERVAL); // Delay LCD update for SD activity + TERN_(HAS_WIRED_LCD, next_lcd_update_ms = ms + LCD_UPDATE_INTERVAL); // Delay LCD update for SD activity #ifdef LED_BACKLIGHT_TIMEOUT leds.reset_timeout(ms); diff --git a/Marlin/src/lcd/ultralcd.h b/Marlin/src/lcd/ultralcd.h index d6a9f31e6c..c7ef41596d 100644 --- a/Marlin/src/lcd/ultralcd.h +++ b/Marlin/src/lcd/ultralcd.h @@ -34,18 +34,18 @@ #if EITHER(HAS_LCD_MENU, ULTIPANEL_FEEDMULTIPLY) #define HAS_ENCODER_ACTION 1 #endif -#if (!HAS_ADC_BUTTONS && ENABLED(NEWPANEL)) || BUTTONS_EXIST(EN1, EN2) +#if ((!HAS_ADC_BUTTONS && ENABLED(NEWPANEL)) || BUTTONS_EXIST(EN1, EN2)) && !IS_TFTGLCD_PANEL #define HAS_ENCODER_WHEEL 1 #endif #if HAS_ENCODER_WHEEL || ANY_BUTTON(ENC, BACK, UP, DWN, LFT, RT) #define HAS_DIGITAL_BUTTONS 1 #endif -#if !HAS_ADC_BUTTONS && (ENABLED(REPRAPWORLD_KEYPAD) || (HAS_SPI_LCD && DISABLED(NEWPANEL))) +#if !HAS_ADC_BUTTONS && (ENABLED(REPRAPWORLD_KEYPAD) || (HAS_WIRED_LCD && DISABLED(NEWPANEL))) #define HAS_SHIFT_ENCODER 1 #endif // I2C buttons must be read in the main thread -#if EITHER(LCD_I2C_VIKI, LCD_I2C_PANELOLU2) +#if ANY(LCD_I2C_VIKI, LCD_I2C_PANELOLU2, IS_TFTGLCD_PANEL) #define HAS_SLOW_BUTTONS 1 #endif @@ -53,7 +53,7 @@ #define MULTI_MANUAL 1 #endif -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #include "../MarlinCore.h" @@ -104,7 +104,7 @@ #endif // HAS_LCD_MENU -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD // REPRAPWORLD_KEYPAD (and ADC_KEYPAD) #if ENABLED(REPRAPWORLD_KEYPAD) @@ -215,7 +215,7 @@ #endif -#if BUTTON_EXISTS(BACK) || HAS_TOUCH_XPT2046 +#if BUTTON_EXISTS(BACK) || EITHER(HAS_TOUCH_XPT2046, IS_TFTGLCD_PANEL) #define BLEN_D 3 #define EN_D _BV(BLEN_D) #define LCD_BACK_CLICKED() (buttons & EN_D) @@ -231,7 +231,7 @@ #endif #endif -#if HAS_GRAPHICAL_LCD +#if HAS_MARLINUI_U8GLIB enum MarlinFont : uint8_t { FONT_STATUSMENU = 1, FONT_EDIT, @@ -312,20 +312,53 @@ public: static void media_changed(const uint8_t old_stat, const uint8_t stat); #endif - #if HAS_SPI_LCD + #if ENABLED(DWIN_CREALITY_LCD) + static void refresh(); + #else + FORCE_INLINE static void refresh() { + TERN_(HAS_WIRED_LCD, refresh(LCDVIEW_CLEAR_CALL_REDRAW)); + } + #endif + + #if HAS_WIRED_LCD static bool detected(); static void init_lcd(); - FORCE_INLINE static void refresh() { refresh(LCDVIEW_CLEAR_CALL_REDRAW); } #else - #if ENABLED(DWIN_CREALITY_LCD) - static void refresh(); - #else - static inline void refresh() {} - #endif static inline bool detected() { return true; } static inline void init_lcd() {} #endif + #if HAS_PRINT_PROGRESS + #if HAS_PRINT_PROGRESS_PERMYRIAD + typedef uint16_t progress_t; + #define PROGRESS_SCALE 100U + #define PROGRESS_MASK 0x7FFF + #else + typedef uint8_t progress_t; + #define PROGRESS_SCALE 1U + #define PROGRESS_MASK 0x7F + #endif + #if ENABLED(LCD_SET_PROGRESS_MANUALLY) + static progress_t progress_override; + static void set_progress(const progress_t p) { progress_override = _MIN(p, 100U * (PROGRESS_SCALE)); } + static void set_progress_done() { progress_override = (PROGRESS_MASK + 1U) + 100U * (PROGRESS_SCALE); } + static void progress_reset() { if (progress_override & (PROGRESS_MASK + 1U)) set_progress(0); } + #if BOTH(LCD_SET_PROGRESS_MANUALLY, USE_M73_REMAINING_TIME) + static uint32_t remaining_time; + FORCE_INLINE static void set_remaining_time(const uint32_t r) { remaining_time = r; } + FORCE_INLINE static uint32_t get_remaining_time() { return remaining_time; } + FORCE_INLINE static void reset_remaining_time() { set_remaining_time(0); } + #endif + #endif + static progress_t _get_progress(); + #if HAS_PRINT_PROGRESS_PERMYRIAD + FORCE_INLINE static uint16_t get_progress_permyriad() { return _get_progress(); } + #endif + static uint8_t get_progress_percent() { return uint8_t(_get_progress() / (PROGRESS_SCALE)); } + #else + static constexpr uint8_t get_progress_percent() { return 0; } + #endif + #if HAS_DISPLAY static void init(); @@ -348,38 +381,7 @@ public: static void pause_print(); static void resume_print(); - #if HAS_PRINT_PROGRESS - #if HAS_PRINT_PROGRESS_PERMYRIAD - typedef uint16_t progress_t; - #define PROGRESS_SCALE 100U - #define PROGRESS_MASK 0x7FFF - #else - typedef uint8_t progress_t; - #define PROGRESS_SCALE 1U - #define PROGRESS_MASK 0x7F - #endif - #if ENABLED(LCD_SET_PROGRESS_MANUALLY) - static progress_t progress_override; - static void set_progress(const progress_t p) { progress_override = _MIN(p, 100U * (PROGRESS_SCALE)); } - static void set_progress_done() { progress_override = (PROGRESS_MASK + 1U) + 100U * (PROGRESS_SCALE); } - static void progress_reset() { if (progress_override & (PROGRESS_MASK + 1U)) set_progress(0); } - #if BOTH(LCD_SET_PROGRESS_MANUALLY, USE_M73_REMAINING_TIME) - static uint32_t remaining_time; - FORCE_INLINE static void set_remaining_time(const uint32_t r) { remaining_time = r; } - FORCE_INLINE static uint32_t get_remaining_time() { return remaining_time; } - FORCE_INLINE static void reset_remaining_time() { set_remaining_time(0); } - #endif - #endif - static progress_t _get_progress(); - #if HAS_PRINT_PROGRESS_PERMYRIAD - FORCE_INLINE static uint16_t get_progress_permyriad() { return _get_progress(); } - #endif - static uint8_t get_progress_percent() { return uint8_t(_get_progress() / (PROGRESS_SCALE)); } - #else - static constexpr uint8_t get_progress_percent() { return 0; } - #endif - - #if HAS_SPI_LCD + #if HAS_WIRED_LCD static millis_t next_button_update_ms; @@ -401,16 +403,12 @@ public: static void show_bootscreen(); #endif - #if HAS_GRAPHICAL_LCD - - static bool drawing_screen, first_page; + #if HAS_MARLINUI_U8GLIB static void set_font(const MarlinFont font_nr); #else - static constexpr bool drawing_screen = false, first_page = true; - static void set_custom_characters(const HD44780CharSet screen_charset=CHARSET_INFO); #if ENABLED(LCD_PROGRESS_BAR) @@ -460,6 +458,12 @@ public: #endif + #if HAS_MARLINUI_U8GLIB + static bool drawing_screen, first_page; + #else + static constexpr bool drawing_screen = false, first_page = true; + #endif + static bool get_blink(); static void kill_screen(PGM_P const lcd_error, PGM_P const lcd_component); static void draw_kill_screen(); @@ -573,7 +577,7 @@ public: static void draw_select_screen_prompt(PGM_P const pref, const char * const string=nullptr, PGM_P const suff=nullptr); - #elif HAS_SPI_LCD + #elif HAS_WIRED_LCD static constexpr bool lcd_clicked = false; static constexpr bool on_status_screen() { return true; } @@ -678,13 +682,17 @@ public: static void touch_calibration(); #endif + #if HAS_GRAPHICAL_TFT + static void move_axis_screen(); + #endif + private: #if HAS_DISPLAY static void finish_status(const bool persist); #endif - #if HAS_SPI_LCD + #if HAS_WIRED_LCD #if HAS_LCD_MENU && LCD_TIMEOUT_TO_STATUS > 0 static bool defer_return_to_status; #else diff --git a/Marlin/src/libs/W25Qxx.cpp b/Marlin/src/libs/W25Qxx.cpp index d51dfb819d..9abe45fbaf 100644 --- a/Marlin/src/libs/W25Qxx.cpp +++ b/Marlin/src/libs/W25Qxx.cpp @@ -24,9 +24,10 @@ #if HAS_SPI_FLASH +#include "W25Qxx.h" #include -#include "W25Qxx.h" +W25QXXFlash W25QXX; #ifndef SPI_FLASH_MISO_PIN #define SPI_FLASH_MISO_PIN W25QXX_MISO_PIN diff --git a/Marlin/src/libs/W25Qxx.h b/Marlin/src/libs/W25Qxx.h index 81e9643450..fb30d655dc 100644 --- a/Marlin/src/libs/W25Qxx.h +++ b/Marlin/src/libs/W25Qxx.h @@ -71,6 +71,4 @@ public: static void SPI_FLASH_BufferRead(uint8_t* pBuffer, uint32_t ReadAddr, uint16_t NumByteToRead); }; -//#ifdef __cplusplus -//} /* C-declarations for C++ */ -//#endif +extern W25QXXFlash W25QXX; diff --git a/Marlin/src/libs/least_squares_fit.cpp b/Marlin/src/libs/least_squares_fit.cpp index ef6ef9e90d..c7593c049f 100644 --- a/Marlin/src/libs/least_squares_fit.cpp +++ b/Marlin/src/libs/least_squares_fit.cpp @@ -29,7 +29,6 @@ * it saves roughly 10K of program memory. It also does not require all of * coordinates to be present during the calculations. Each point can be * probed and then discarded. - * */ #include "../inc/MarlinConfig.h" diff --git a/Marlin/src/libs/least_squares_fit.h b/Marlin/src/libs/least_squares_fit.h index 5cd6a02514..44ca8afc76 100644 --- a/Marlin/src/libs/least_squares_fit.h +++ b/Marlin/src/libs/least_squares_fit.h @@ -30,7 +30,6 @@ * it saves roughly 10K of program memory. And even better... the data * fed into the algorithm does not need to all be present at the same time. * A point can be probed and its values fed into the algorithm and then discarded. - * */ #include "../inc/MarlinConfig.h" diff --git a/Marlin/src/libs/numtostr.cpp b/Marlin/src/libs/numtostr.cpp index 3b36c180e8..c3efb2b25a 100644 --- a/Marlin/src/libs/numtostr.cpp +++ b/Marlin/src/libs/numtostr.cpp @@ -52,6 +52,13 @@ const char* ui8tostr3rj(const uint8_t i) { return &conv[4]; } +// Convert uint8_t to string with 12 format +const char* ui8tostr2(const uint8_t i) { + conv[5] = DIGIMOD(i, 10); + conv[6] = DIGIMOD(i, 1); + return &conv[5]; +} + // Convert signed 8bit int to rj string with 123 or -12 format const char* i8tostr3rj(const int8_t x) { int xx = x; diff --git a/Marlin/src/libs/numtostr.h b/Marlin/src/libs/numtostr.h index e52a7d9889..e7c1e67e12 100644 --- a/Marlin/src/libs/numtostr.h +++ b/Marlin/src/libs/numtostr.h @@ -26,6 +26,9 @@ // Convert a full-range unsigned 8bit int to a percentage const char* ui8tostr4pctrj(const uint8_t i); +// Convert uint8_t to string with 12 format +const char* ui8tostr2(const uint8_t x); + // Convert uint8_t to string with 123 format const char* ui8tostr3rj(const uint8_t i); diff --git a/Marlin/src/libs/private_spi.h b/Marlin/src/libs/private_spi.h index c2a054235b..9c0ffe7486 100644 --- a/Marlin/src/libs/private_spi.h +++ b/Marlin/src/libs/private_spi.h @@ -43,7 +43,7 @@ class SPIclass { SET_INPUT_PULLUP(MISO_PIN); } FORCE_INLINE static uint8_t receive() { - #if defined(__AVR__) || defined(__MK20DX256__) || defined(__MK64FX512__) || defined(__MK66FX1M0__) + #if defined(__AVR__) || defined(__MK20DX256__) || defined(__MK64FX512__) || defined(__MK66FX1M0__) || defined(__IMXRT1062__) SPDR = 0; for (;!TEST(SPSR, SPIF);); return SPDR; diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index 289270072d..712182a0ea 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -351,7 +351,7 @@ void Endstops::event_handler() { if (hit_state == prev_hit_state) return; prev_hit_state = hit_state; if (hit_state) { - #if HAS_SPI_LCD + #if HAS_WIRED_LCD char chrX = ' ', chrY = ' ', chrZ = ' ', chrP = ' '; #define _SET_STOP_CHAR(A,C) (chr## A = C) #else @@ -382,7 +382,7 @@ void Endstops::event_handler() { #endif SERIAL_EOL(); - TERN_(HAS_SPI_LCD, ui.status_printf_P(0, PSTR(S_FMT " %c %c %c %c"), GET_TEXT(MSG_LCD_ENDSTOPS), chrX, chrY, chrZ, chrP)); + TERN_(HAS_WIRED_LCD, ui.status_printf_P(0, PSTR(S_FMT " %c %c %c %c"), GET_TEXT(MSG_LCD_ENDSTOPS), chrX, chrY, chrZ, chrP)); #if BOTH(SD_ABORT_ON_ENDSTOP_HIT, SDSUPPORT) if (planner.abort_on_endstop_hit) { @@ -498,14 +498,14 @@ void Endstops::update() { #define UPDATE_ENDSTOP_BIT(AXIS, MINMAX) SET_BIT_TO(live_state, _ENDSTOP(AXIS, MINMAX), (READ(_ENDSTOP_PIN(AXIS, MINMAX)) != _ENDSTOP_INVERTING(AXIS, MINMAX))) #define COPY_LIVE_STATE(SRC_BIT, DST_BIT) SET_BIT_TO(live_state, DST_BIT, TEST(live_state, SRC_BIT)) - #if ENABLED(G38_PROBE_TARGET) && PIN_EXISTS(Z_MIN_PROBE) && !(CORE_IS_XY || CORE_IS_XZ) + #if ENABLED(G38_PROBE_TARGET) && PIN_EXISTS(Z_MIN_PROBE) && NONE(CORE_IS_XY, CORE_IS_XZ, MARKFORGED_XY) // If G38 command is active check Z_MIN_PROBE for ALL movement if (G38_move) UPDATE_ENDSTOP_BIT(Z, MIN_PROBE); #endif // With Dual X, endstops are only checked in the homing direction for the active extruder #if ENABLED(DUAL_X_CARRIAGE) - #define E0_ACTIVE stepper.movement_extruder() == 0 + #define E0_ACTIVE stepper.last_moved_extruder == 0 #define X_MIN_TEST() ((X_HOME_DIR < 0 && E0_ACTIVE) || (X2_HOME_DIR < 0 && !E0_ACTIVE)) #define X_MAX_TEST() ((X_HOME_DIR > 0 && E0_ACTIVE) || (X2_HOME_DIR > 0 && !E0_ACTIVE)) #else @@ -514,12 +514,12 @@ void Endstops::update() { #endif // Use HEAD for core axes, AXIS for others - #if CORE_IS_XY || CORE_IS_XZ + #if ANY(CORE_IS_XY, CORE_IS_XZ, MARKFORGED_XY) #define X_AXIS_HEAD X_HEAD #else #define X_AXIS_HEAD X_AXIS #endif - #if CORE_IS_XY || CORE_IS_YZ + #if ANY(CORE_IS_XY, CORE_IS_YZ, MARKFORGED_XY) #define Y_AXIS_HEAD Y_HEAD #else #define Y_AXIS_HEAD Y_AXIS @@ -736,7 +736,7 @@ void Endstops::update() { #define PROCESS_ENDSTOP_Z(MINMAX) PROCESS_DUAL_ENDSTOP(Z, MINMAX) #endif - #if ENABLED(G38_PROBE_TARGET) && PIN_EXISTS(Z_MIN_PROBE) && !(CORE_IS_XY || CORE_IS_XZ) + #if ENABLED(G38_PROBE_TARGET) && PIN_EXISTS(Z_MIN_PROBE) && NONE(CORE_IS_XY, CORE_IS_XZ, MARKFORGED_XY) #if ENABLED(G38_PROBE_AWAY) #define _G38_OPEN_STATE (G38_move >= 4) #else @@ -865,7 +865,7 @@ void Endstops::update() { bool hit = false; #if X_SPI_SENSORLESS if (tmc_spi_homing.x && (stepperX.test_stall_status() - #if CORE_IS_XY && Y_SPI_SENSORLESS + #if ANY(CORE_IS_XY, MARKFORGED_XY) && Y_SPI_SENSORLESS || stepperY.test_stall_status() #elif CORE_IS_XZ && Z_SPI_SENSORLESS || stepperZ.test_stall_status() @@ -877,7 +877,7 @@ void Endstops::update() { #endif #if Y_SPI_SENSORLESS if (tmc_spi_homing.y && (stepperY.test_stall_status() - #if CORE_IS_XY && X_SPI_SENSORLESS + #if ANY(CORE_IS_XY, MARKFORGED_XY) && X_SPI_SENSORLESS || stepperX.test_stall_status() #elif CORE_IS_YZ && Z_SPI_SENSORLESS || stepperZ.test_stall_status() diff --git a/Marlin/src/module/mks_wifi/mks_wifi_ui.cpp b/Marlin/src/module/mks_wifi/mks_wifi_ui.cpp index b777f7611f..47d314d505 100644 --- a/Marlin/src/module/mks_wifi/mks_wifi_ui.cpp +++ b/Marlin/src/module/mks_wifi/mks_wifi_ui.cpp @@ -19,8 +19,8 @@ void mks_update_status(char *filename,uint32_t current_filesize, uint32_t file_s thermalManager.setTargetBed(0); thermalManager.setTargetHotend(0,0); - OUT_WRITE(HEATER_1_PIN,HIGH); thermalManager.manage_heater(); + OUT_WRITE(HEATER_1_PIN,HIGH); //При расчете процентов размер файла превышает максимум для uint32_t if(current_filesize >= (UINT32_MAX/100) ){ @@ -47,7 +47,7 @@ void mks_update_status(char *filename,uint32_t current_filesize, uint32_t file_s tft.queue.sync(); last_value = percent_done; - ui.update(); + //ui.update(); }; } diff --git a/Marlin/src/module/mks_wifi/small_cmsis.h b/Marlin/src/module/mks_wifi/small_cmsis.h index 1ca98cd160..81f4750c71 100644 --- a/Marlin/src/module/mks_wifi/small_cmsis.h +++ b/Marlin/src/module/mks_wifi/small_cmsis.h @@ -160,7 +160,7 @@ typedef struct #define APB1PERIPH_BASE PERIPH_BASE #define APB2PERIPH_BASE (PERIPH_BASE + 0x00010000U) #define AHBPERIPH_BASE (PERIPH_BASE + 0x00020000U) -#define USART1_BASE (APB2PERIPH_BASE + 0x00003800U) +//#define USART1_BASE (APB2PERIPH_BASE + 0x00003800U) #define DMA1_BASE (AHBPERIPH_BASE + 0x00000000U) #define DMA1_Channel5_BASE (AHBPERIPH_BASE + 0x00000058U) #define DMA2_BASE (AHBPERIPH_BASE + 0x00000400U) @@ -190,186 +190,6 @@ typedef struct #define CoreDebug ((CoreDebug_Type *)CoreDebug_BASE) /*!< Core Debug configuration struct */ #define DWT ((DWT_Type *) DWT_BASE ) /*!< DWT configuration struct */ #define SPI2 ((SPI_TypeDef *)SPI2_BASE) -/******************************************************************************/ -/* */ -/* Universal Synchronous Asynchronous Receiver Transmitter */ -/* */ -/******************************************************************************/ - -/******************* Bit definition for USART_SR register *******************/ -#define USART_SR_PE_Pos (0U) -#define USART_SR_PE_Msk (0x1U << USART_SR_PE_Pos) /*!< 0x00000001 */ -#define USART_SR_PE USART_SR_PE_Msk /*!< Parity Error */ -#define USART_SR_FE_Pos (1U) -#define USART_SR_FE_Msk (0x1U << USART_SR_FE_Pos) /*!< 0x00000002 */ -#define USART_SR_FE USART_SR_FE_Msk /*!< Framing Error */ -#define USART_SR_NE_Pos (2U) -#define USART_SR_NE_Msk (0x1U << USART_SR_NE_Pos) /*!< 0x00000004 */ -#define USART_SR_NE USART_SR_NE_Msk /*!< Noise Error Flag */ -#define USART_SR_ORE_Pos (3U) -#define USART_SR_ORE_Msk (0x1U << USART_SR_ORE_Pos) /*!< 0x00000008 */ -#define USART_SR_ORE USART_SR_ORE_Msk /*!< OverRun Error */ -#define USART_SR_IDLE_Pos (4U) -#define USART_SR_IDLE_Msk (0x1U << USART_SR_IDLE_Pos) /*!< 0x00000010 */ -#define USART_SR_IDLE USART_SR_IDLE_Msk /*!< IDLE line detected */ -#define USART_SR_RXNE_Pos (5U) -#define USART_SR_RXNE_Msk (0x1U << USART_SR_RXNE_Pos) /*!< 0x00000020 */ -#define USART_SR_RXNE USART_SR_RXNE_Msk /*!< Read Data Register Not Empty */ -#define USART_SR_TC_Pos (6U) -#define USART_SR_TC_Msk (0x1U << USART_SR_TC_Pos) /*!< 0x00000040 */ -#define USART_SR_TC USART_SR_TC_Msk /*!< Transmission Complete */ -#define USART_SR_TXE_Pos (7U) -#define USART_SR_TXE_Msk (0x1U << USART_SR_TXE_Pos) /*!< 0x00000080 */ -#define USART_SR_TXE USART_SR_TXE_Msk /*!< Transmit Data Register Empty */ -#define USART_SR_LBD_Pos (8U) -#define USART_SR_LBD_Msk (0x1U << USART_SR_LBD_Pos) /*!< 0x00000100 */ -#define USART_SR_LBD USART_SR_LBD_Msk /*!< LIN Break Detection Flag */ -#define USART_SR_CTS_Pos (9U) -#define USART_SR_CTS_Msk (0x1U << USART_SR_CTS_Pos) /*!< 0x00000200 */ -#define USART_SR_CTS USART_SR_CTS_Msk /*!< CTS Flag */ - -/******************* Bit definition for USART_DR register *******************/ -#define USART_DR_DR_Pos (0U) -#define USART_DR_DR_Msk (0x1FFU << USART_DR_DR_Pos) /*!< 0x000001FF */ -#define USART_DR_DR USART_DR_DR_Msk /*!< Data value */ - -/****************** Bit definition for USART_BRR register *******************/ -#define USART_BRR_DIV_Fraction_Pos (0U) -#define USART_BRR_DIV_Fraction_Msk (0xFU << USART_BRR_DIV_Fraction_Pos) /*!< 0x0000000F */ -#define USART_BRR_DIV_Fraction USART_BRR_DIV_Fraction_Msk /*!< Fraction of USARTDIV */ -#define USART_BRR_DIV_Mantissa_Pos (4U) -#define USART_BRR_DIV_Mantissa_Msk (0xFFFU << USART_BRR_DIV_Mantissa_Pos) /*!< 0x0000FFF0 */ -#define USART_BRR_DIV_Mantissa USART_BRR_DIV_Mantissa_Msk /*!< Mantissa of USARTDIV */ - -/****************** Bit definition for USART_CR1 register *******************/ -#define USART_CR1_SBK_Pos (0U) -#define USART_CR1_SBK_Msk (0x1U << USART_CR1_SBK_Pos) /*!< 0x00000001 */ -#define USART_CR1_SBK USART_CR1_SBK_Msk /*!< Send Break */ -#define USART_CR1_RWU_Pos (1U) -#define USART_CR1_RWU_Msk (0x1U << USART_CR1_RWU_Pos) /*!< 0x00000002 */ -#define USART_CR1_RWU USART_CR1_RWU_Msk /*!< Receiver wakeup */ -#define USART_CR1_RE_Pos (2U) -#define USART_CR1_RE_Msk (0x1U << USART_CR1_RE_Pos) /*!< 0x00000004 */ -#define USART_CR1_RE USART_CR1_RE_Msk /*!< Receiver Enable */ -#define USART_CR1_TE_Pos (3U) -#define USART_CR1_TE_Msk (0x1U << USART_CR1_TE_Pos) /*!< 0x00000008 */ -#define USART_CR1_TE USART_CR1_TE_Msk /*!< Transmitter Enable */ -#define USART_CR1_IDLEIE_Pos (4U) -#define USART_CR1_IDLEIE_Msk (0x1U << USART_CR1_IDLEIE_Pos) /*!< 0x00000010 */ -#define USART_CR1_IDLEIE USART_CR1_IDLEIE_Msk /*!< IDLE Interrupt Enable */ -#define USART_CR1_RXNEIE_Pos (5U) -#define USART_CR1_RXNEIE_Msk (0x1U << USART_CR1_RXNEIE_Pos) /*!< 0x00000020 */ -#define USART_CR1_RXNEIE USART_CR1_RXNEIE_Msk /*!< RXNE Interrupt Enable */ -#define USART_CR1_TCIE_Pos (6U) -#define USART_CR1_TCIE_Msk (0x1U << USART_CR1_TCIE_Pos) /*!< 0x00000040 */ -#define USART_CR1_TCIE USART_CR1_TCIE_Msk /*!< Transmission Complete Interrupt Enable */ -#define USART_CR1_TXEIE_Pos (7U) -#define USART_CR1_TXEIE_Msk (0x1U << USART_CR1_TXEIE_Pos) /*!< 0x00000080 */ -#define USART_CR1_TXEIE USART_CR1_TXEIE_Msk /*!< PE Interrupt Enable */ -#define USART_CR1_PEIE_Pos (8U) -#define USART_CR1_PEIE_Msk (0x1U << USART_CR1_PEIE_Pos) /*!< 0x00000100 */ -#define USART_CR1_PEIE USART_CR1_PEIE_Msk /*!< PE Interrupt Enable */ -#define USART_CR1_PS_Pos (9U) -#define USART_CR1_PS_Msk (0x1U << USART_CR1_PS_Pos) /*!< 0x00000200 */ -#define USART_CR1_PS USART_CR1_PS_Msk /*!< Parity Selection */ -#define USART_CR1_PCE_Pos (10U) -#define USART_CR1_PCE_Msk (0x1U << USART_CR1_PCE_Pos) /*!< 0x00000400 */ -#define USART_CR1_PCE USART_CR1_PCE_Msk /*!< Parity Control Enable */ -#define USART_CR1_WAKE_Pos (11U) -#define USART_CR1_WAKE_Msk (0x1U << USART_CR1_WAKE_Pos) /*!< 0x00000800 */ -#define USART_CR1_WAKE USART_CR1_WAKE_Msk /*!< Wakeup method */ -#define USART_CR1_M_Pos (12U) -#define USART_CR1_M_Msk (0x1U << USART_CR1_M_Pos) /*!< 0x00001000 */ -#define USART_CR1_M USART_CR1_M_Msk /*!< Word length */ -#define USART_CR1_UE_Pos (13U) -#define USART_CR1_UE_Msk (0x1U << USART_CR1_UE_Pos) /*!< 0x00002000 */ -#define USART_CR1_UE USART_CR1_UE_Msk /*!< USART Enable */ - -/****************** Bit definition for USART_CR2 register *******************/ -#define USART_CR2_ADD_Pos (0U) -#define USART_CR2_ADD_Msk (0xFU << USART_CR2_ADD_Pos) /*!< 0x0000000F */ -#define USART_CR2_ADD USART_CR2_ADD_Msk /*!< Address of the USART node */ -#define USART_CR2_LBDL_Pos (5U) -#define USART_CR2_LBDL_Msk (0x1U << USART_CR2_LBDL_Pos) /*!< 0x00000020 */ -#define USART_CR2_LBDL USART_CR2_LBDL_Msk /*!< LIN Break Detection Length */ -#define USART_CR2_LBDIE_Pos (6U) -#define USART_CR2_LBDIE_Msk (0x1U << USART_CR2_LBDIE_Pos) /*!< 0x00000040 */ -#define USART_CR2_LBDIE USART_CR2_LBDIE_Msk /*!< LIN Break Detection Interrupt Enable */ -#define USART_CR2_LBCL_Pos (8U) -#define USART_CR2_LBCL_Msk (0x1U << USART_CR2_LBCL_Pos) /*!< 0x00000100 */ -#define USART_CR2_LBCL USART_CR2_LBCL_Msk /*!< Last Bit Clock pulse */ -#define USART_CR2_CPHA_Pos (9U) -#define USART_CR2_CPHA_Msk (0x1U << USART_CR2_CPHA_Pos) /*!< 0x00000200 */ -#define USART_CR2_CPHA USART_CR2_CPHA_Msk /*!< Clock Phase */ -#define USART_CR2_CPOL_Pos (10U) -#define USART_CR2_CPOL_Msk (0x1U << USART_CR2_CPOL_Pos) /*!< 0x00000400 */ -#define USART_CR2_CPOL USART_CR2_CPOL_Msk /*!< Clock Polarity */ -#define USART_CR2_CLKEN_Pos (11U) -#define USART_CR2_CLKEN_Msk (0x1U << USART_CR2_CLKEN_Pos) /*!< 0x00000800 */ -#define USART_CR2_CLKEN USART_CR2_CLKEN_Msk /*!< Clock Enable */ - -#define USART_CR2_STOP_Pos (12U) -#define USART_CR2_STOP_Msk (0x3U << USART_CR2_STOP_Pos) /*!< 0x00003000 */ -#define USART_CR2_STOP USART_CR2_STOP_Msk /*!< STOP[1:0] bits (STOP bits) */ -#define USART_CR2_STOP_0 (0x1U << USART_CR2_STOP_Pos) /*!< 0x00001000 */ -#define USART_CR2_STOP_1 (0x2U << USART_CR2_STOP_Pos) /*!< 0x00002000 */ - -#define USART_CR2_LINEN_Pos (14U) -#define USART_CR2_LINEN_Msk (0x1U << USART_CR2_LINEN_Pos) /*!< 0x00004000 */ -#define USART_CR2_LINEN USART_CR2_LINEN_Msk /*!< LIN mode enable */ - -/****************** Bit definition for USART_CR3 register *******************/ -#define USART_CR3_EIE_Pos (0U) -#define USART_CR3_EIE_Msk (0x1U << USART_CR3_EIE_Pos) /*!< 0x00000001 */ -#define USART_CR3_EIE USART_CR3_EIE_Msk /*!< Error Interrupt Enable */ -#define USART_CR3_IREN_Pos (1U) -#define USART_CR3_IREN_Msk (0x1U << USART_CR3_IREN_Pos) /*!< 0x00000002 */ -#define USART_CR3_IREN USART_CR3_IREN_Msk /*!< IrDA mode Enable */ -#define USART_CR3_IRLP_Pos (2U) -#define USART_CR3_IRLP_Msk (0x1U << USART_CR3_IRLP_Pos) /*!< 0x00000004 */ -#define USART_CR3_IRLP USART_CR3_IRLP_Msk /*!< IrDA Low-Power */ -#define USART_CR3_HDSEL_Pos (3U) -#define USART_CR3_HDSEL_Msk (0x1U << USART_CR3_HDSEL_Pos) /*!< 0x00000008 */ -#define USART_CR3_HDSEL USART_CR3_HDSEL_Msk /*!< Half-Duplex Selection */ -#define USART_CR3_NACK_Pos (4U) -#define USART_CR3_NACK_Msk (0x1U << USART_CR3_NACK_Pos) /*!< 0x00000010 */ -#define USART_CR3_NACK USART_CR3_NACK_Msk /*!< Smartcard NACK enable */ -#define USART_CR3_SCEN_Pos (5U) -#define USART_CR3_SCEN_Msk (0x1U << USART_CR3_SCEN_Pos) /*!< 0x00000020 */ -#define USART_CR3_SCEN USART_CR3_SCEN_Msk /*!< Smartcard mode enable */ -#define USART_CR3_DMAR_Pos (6U) -#define USART_CR3_DMAR_Msk (0x1U << USART_CR3_DMAR_Pos) /*!< 0x00000040 */ -#define USART_CR3_DMAR USART_CR3_DMAR_Msk /*!< DMA Enable Receiver */ -#define USART_CR3_DMAT_Pos (7U) -#define USART_CR3_DMAT_Msk (0x1U << USART_CR3_DMAT_Pos) /*!< 0x00000080 */ -#define USART_CR3_DMAT USART_CR3_DMAT_Msk /*!< DMA Enable Transmitter */ -#define USART_CR3_RTSE_Pos (8U) -#define USART_CR3_RTSE_Msk (0x1U << USART_CR3_RTSE_Pos) /*!< 0x00000100 */ -#define USART_CR3_RTSE USART_CR3_RTSE_Msk /*!< RTS Enable */ -#define USART_CR3_CTSE_Pos (9U) -#define USART_CR3_CTSE_Msk (0x1U << USART_CR3_CTSE_Pos) /*!< 0x00000200 */ -#define USART_CR3_CTSE USART_CR3_CTSE_Msk /*!< CTS Enable */ -#define USART_CR3_CTSIE_Pos (10U) -#define USART_CR3_CTSIE_Msk (0x1U << USART_CR3_CTSIE_Pos) /*!< 0x00000400 */ -#define USART_CR3_CTSIE USART_CR3_CTSIE_Msk /*!< CTS Interrupt Enable */ - -/****************** Bit definition for USART_GTPR register ******************/ -#define USART_GTPR_PSC_Pos (0U) -#define USART_GTPR_PSC_Msk (0xFFU << USART_GTPR_PSC_Pos) /*!< 0x000000FF */ -#define USART_GTPR_PSC USART_GTPR_PSC_Msk /*!< PSC[7:0] bits (Prescaler value) */ -#define USART_GTPR_PSC_0 (0x01U << USART_GTPR_PSC_Pos) /*!< 0x00000001 */ -#define USART_GTPR_PSC_1 (0x02U << USART_GTPR_PSC_Pos) /*!< 0x00000002 */ -#define USART_GTPR_PSC_2 (0x04U << USART_GTPR_PSC_Pos) /*!< 0x00000004 */ -#define USART_GTPR_PSC_3 (0x08U << USART_GTPR_PSC_Pos) /*!< 0x00000008 */ -#define USART_GTPR_PSC_4 (0x10U << USART_GTPR_PSC_Pos) /*!< 0x00000010 */ -#define USART_GTPR_PSC_5 (0x20U << USART_GTPR_PSC_Pos) /*!< 0x00000020 */ -#define USART_GTPR_PSC_6 (0x40U << USART_GTPR_PSC_Pos) /*!< 0x00000040 */ -#define USART_GTPR_PSC_7 (0x80U << USART_GTPR_PSC_Pos) /*!< 0x00000080 */ - -#define USART_GTPR_GT_Pos (8U) -#define USART_GTPR_GT_Msk (0xFFU << USART_GTPR_GT_Pos) /*!< 0x0000FF00 */ -#define USART_GTPR_GT USART_GTPR_GT_Msk /*!< Guard time value */ - /******************************************************************************/ /* */ diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index 401721140b..b904309018 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -111,7 +111,7 @@ xyze_pos_t destination; // {0} #endif // The active extruder (tool). Set with T command. -#if EXTRUDERS > 1 +#if HAS_MULTI_EXTRUDER uint8_t active_extruder = 0; // = 0 #endif @@ -1152,7 +1152,7 @@ feedRate_t get_homing_bump_feedrate(const AxisEnum axis) { #if AXIS_HAS_STALLGUARD(X2) stealth_states.x2 = tmc_enable_stallguard(stepperX2); #endif - #if CORE_IS_XY && Y_SENSORLESS + #if EITHER(CORE_IS_XY, MARKFORGED_XY) && Y_SENSORLESS stealth_states.y = tmc_enable_stallguard(stepperY); #elif CORE_IS_XZ && Z_SENSORLESS stealth_states.z = tmc_enable_stallguard(stepperZ); @@ -1165,7 +1165,7 @@ feedRate_t get_homing_bump_feedrate(const AxisEnum axis) { #if AXIS_HAS_STALLGUARD(Y2) stealth_states.y2 = tmc_enable_stallguard(stepperY2); #endif - #if CORE_IS_XY && X_SENSORLESS + #if EITHER(CORE_IS_XY, MARKFORGED_XY) && X_SENSORLESS stealth_states.x = tmc_enable_stallguard(stepperX); #elif CORE_IS_YZ && Z_SENSORLESS stealth_states.z = tmc_enable_stallguard(stepperZ); @@ -1216,7 +1216,7 @@ feedRate_t get_homing_bump_feedrate(const AxisEnum axis) { #if AXIS_HAS_STALLGUARD(X2) tmc_disable_stallguard(stepperX2, enable_stealth.x2); #endif - #if CORE_IS_XY && Y_SENSORLESS + #if EITHER(CORE_IS_XY, MARKFORGED_XY) && Y_SENSORLESS tmc_disable_stallguard(stepperY, enable_stealth.y); #elif CORE_IS_XZ && Z_SENSORLESS tmc_disable_stallguard(stepperZ, enable_stealth.z); @@ -1229,7 +1229,7 @@ feedRate_t get_homing_bump_feedrate(const AxisEnum axis) { #if AXIS_HAS_STALLGUARD(Y2) tmc_disable_stallguard(stepperY2, enable_stealth.y2); #endif - #if CORE_IS_XY && X_SENSORLESS + #if EITHER(CORE_IS_XY, MARKFORGED_XY) && X_SENSORLESS tmc_disable_stallguard(stepperX, enable_stealth.x); #elif CORE_IS_YZ && Z_SENSORLESS tmc_disable_stallguard(stepperZ, enable_stealth.z); @@ -1789,7 +1789,7 @@ void homeaxis(const AxisEnum axis) { do_homing_move(axis, adjDistance, get_homing_bump_feedrate(axis)); } - #else // CARTESIAN / CORE + #else // CARTESIAN / CORE / MARKFORGED_XY set_axis_is_at_home(axis); sync_plan_position(); @@ -1818,8 +1818,11 @@ void homeaxis(const AxisEnum axis) { #if ENABLED(SENSORLESS_HOMING) planner.synchronize(); - if (TERN0(IS_CORE, axis != NORMAL_AXIS)) - safe_delay(200); // Short delay to allow belts to spring back + if (false + #if EITHER(IS_CORE, MARKFORGED_XY) + || axis != NORMAL_AXIS + #endif + ) safe_delay(200); // Short delay to allow belts to spring back #endif } #endif diff --git a/Marlin/src/module/motion.h b/Marlin/src/module/motion.h index c3f2d9b779..2b108b0531 100644 --- a/Marlin/src/module/motion.h +++ b/Marlin/src/module/motion.h @@ -98,7 +98,7 @@ extern feedRate_t feedrate_mm_s; extern int16_t feedrate_percentage; // The active extruder (tool). Set with T command. -#if EXTRUDERS > 1 +#if HAS_MULTI_EXTRUDER extern uint8_t active_extruder; #else constexpr uint8_t active_extruder = 0; @@ -108,22 +108,28 @@ extern int16_t feedrate_percentage; extern float e_move_accumulator; #endif -inline float pgm_read_any(const float *p) { return pgm_read_float(p); } -inline signed char pgm_read_any(const signed char *p) { return pgm_read_byte(p); } +#ifdef __IMXRT1062__ + #define DEFS_PROGMEM +#else + #define DEFS_PROGMEM PROGMEM +#endif + +inline float pgm_read_any(const float *p) { return TERN(__IMXRT1062__, *p, pgm_read_float(p)); } +inline int8_t pgm_read_any(const int8_t *p) { return TERN(__IMXRT1062__, *p, pgm_read_byte(p)); } #define XYZ_DEFS(T, NAME, OPT) \ inline T NAME(const AxisEnum axis) { \ - static const XYZval NAME##_P PROGMEM = { X_##OPT, Y_##OPT, Z_##OPT }; \ + static const XYZval NAME##_P DEFS_PROGMEM = { X_##OPT, Y_##OPT, Z_##OPT }; \ return pgm_read_any(&NAME##_P[axis]); \ } XYZ_DEFS(float, base_min_pos, MIN_POS); XYZ_DEFS(float, base_max_pos, MAX_POS); XYZ_DEFS(float, base_home_pos, HOME_POS); XYZ_DEFS(float, max_length, MAX_LENGTH); -XYZ_DEFS(signed char, home_dir, HOME_DIR); +XYZ_DEFS(int8_t, home_dir, HOME_DIR); inline float home_bump_mm(const AxisEnum axis) { - static const xyz_pos_t home_bump_mm_P PROGMEM = HOMING_BUMP_MM; + static const xyz_pos_t home_bump_mm_P DEFS_PROGMEM = HOMING_BUMP_MM; return pgm_read_any(&home_bump_mm_P[axis]); } diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 931daa3322..4ad7c4ccf0 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -234,7 +234,7 @@ float Planner::previous_nominal_speed_sqr; xyze_pos_t Planner::position_cart; #endif -#if HAS_SPI_LCD +#if HAS_WIRED_LCD volatile uint32_t Planner::block_buffer_runtime_us = 0; #endif @@ -339,7 +339,6 @@ void Planner::init() { * const uint32_t r = _BV(24) - x * d; // Estimate remainder * if (r >= d) x++; // Check whether to adjust result * return uint32_t(x); // x holds the proper estimation - * */ static uint32_t get_period_inverse(uint32_t d) { @@ -747,7 +746,7 @@ block_t* Planner::get_current_block() { if (TEST(block->flag, BLOCK_BIT_RECALCULATE)) return nullptr; // We can't be sure how long an active block will take, so don't count it. - TERN_(HAS_SPI_LCD, block_buffer_runtime_us -= block->segment_time_us); + TERN_(HAS_WIRED_LCD, block_buffer_runtime_us -= block->segment_time_us); // As this block is busy, advance the nonbusy block pointer block_buffer_nonbusy = next_block_index(block_buffer_tail); @@ -761,7 +760,7 @@ block_t* Planner::get_current_block() { } // The queue became empty - TERN_(HAS_SPI_LCD, clear_block_buffer_runtime()); // paranoia. Buffer is empty now - so reset accumulated time to zero. + TERN_(HAS_WIRED_LCD, clear_block_buffer_runtime()); // paranoia. Buffer is empty now - so reset accumulated time to zero. return nullptr; } @@ -1578,7 +1577,7 @@ void Planner::quick_stop() { // forced to empty, there's no risk the ISR will touch this. delay_before_delivering = BLOCK_DELAY_FOR_1ST_MOVE; - #if HAS_SPI_LCD + #if HAS_WIRED_LCD // Clear the accumulated runtime clear_block_buffer_runtime(); #endif @@ -1614,6 +1613,7 @@ void Planner::finish_and_disable() { float Planner::get_axis_position_mm(const AxisEnum axis) { float axis_steps; #if IS_CORE + // Requesting one of the "core" axes? if (axis == CORE_AXIS_1 || axis == CORE_AXIS_2) { @@ -1631,9 +1631,30 @@ float Planner::get_axis_position_mm(const AxisEnum axis) { } else axis_steps = stepper.position(axis); + + #elif ENABLED(MARKFORGED_XY) + + // Requesting one of the joined axes? + if (axis == CORE_AXIS_1 || axis == CORE_AXIS_2) { + // Protect the access to the position. + const bool was_enabled = stepper.suspend(); + + const int32_t p1 = stepper.position(CORE_AXIS_1), + p2 = stepper.position(CORE_AXIS_2); + + if (was_enabled) stepper.wake_up(); + + axis_steps = ((axis == CORE_AXIS_1) ? p1 - p2 : p2); + } + else + axis_steps = stepper.position(axis); + #else + axis_steps = stepper.position(axis); + #endif + return axis_steps * steps_to_mm[axis]; } @@ -1808,6 +1829,12 @@ bool Planner::_populate_block(block_t * const block, bool split_move, if (dc < 0) SBI(dm, Z_HEAD); // ...and Z if (db + dc < 0) SBI(dm, B_AXIS); // Motor B direction if (CORESIGN(db - dc) < 0) SBI(dm, C_AXIS); // Motor C direction + #elif ENABLED(MARKFORGED_XY) + if (da < 0) SBI(dm, X_HEAD); // Save the real Extruder (head) direction in X Axis + if (db < 0) SBI(dm, Y_HEAD); // ...and Y + if (dc < 0) SBI(dm, Z_AXIS); + if (da + db < 0) SBI(dm, A_AXIS); // Motor A direction + if (db < 0) SBI(dm, B_AXIS); // Motor B direction #else if (da < 0) SBI(dm, X_AXIS); if (db < 0) SBI(dm, Y_AXIS); @@ -1843,6 +1870,8 @@ bool Planner::_populate_block(block_t * const block, bool split_move, block->steps.set(ABS(da + dc), ABS(db), ABS(da - dc)); #elif CORE_IS_YZ block->steps.set(ABS(da), ABS(db + dc), ABS(db - dc)); + #elif ENABLED(MARKFORGED_XY) + block->steps.set(ABS(da + db), ABS(db), ABS(dc)); #elif IS_SCARA block->steps.set(ABS(da), ABS(db), ABS(dc)); #else @@ -1859,7 +1888,9 @@ bool Planner::_populate_block(block_t * const block, bool split_move, * Having the real displacement of the head, we can calculate the total movement length and apply the desired speed. */ struct DistanceMM : abce_float_t { - TERN_(IS_CORE, xyz_pos_t head); + #if EITHER(IS_CORE, MARKFORGED_XY) + xyz_pos_t head; + #endif } steps_dist_mm; #if IS_CORE #if CORE_IS_XY @@ -1881,6 +1912,12 @@ bool Planner::_populate_block(block_t * const block, bool split_move, steps_dist_mm.b = (db + dc) * steps_to_mm[B_AXIS]; steps_dist_mm.c = CORESIGN(db - dc) * steps_to_mm[C_AXIS]; #endif + #elif ENABLED(MARKFORGED_XY) + steps_dist_mm.head.x = da * steps_to_mm[A_AXIS]; + steps_dist_mm.head.y = db * steps_to_mm[B_AXIS]; + steps_dist_mm.z = dc * steps_to_mm[Z_AXIS]; + steps_dist_mm.a = (da - db) * steps_to_mm[A_AXIS]; + steps_dist_mm.b = db * steps_to_mm[B_AXIS]; #else steps_dist_mm.a = da * steps_to_mm[A_AXIS]; steps_dist_mm.b = db * steps_to_mm[B_AXIS]; @@ -1907,7 +1944,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, block->millimeters = millimeters; else block->millimeters = SQRT( - #if CORE_IS_XY + #if EITHER(CORE_IS_XY, MARKFORGED_XY) sq(steps_dist_mm.head.x) + sq(steps_dist_mm.head.y) + sq(steps_dist_mm.z) #elif CORE_IS_XZ sq(steps_dist_mm.head.x) + sq(steps_dist_mm.y) + sq(steps_dist_mm.head.z) @@ -1954,7 +1991,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, block->e_to_p_pressure = baricuda_e_to_p_pressure; #endif - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER block->extruder = extruder; #endif @@ -1964,7 +2001,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, #endif // Enable active axes - #if CORE_IS_XY + #if EITHER(CORE_IS_XY, MARKFORGED_XY) if (block->steps.a || block->steps.b) { ENABLE_AXIS_X(); ENABLE_AXIS_Y(); @@ -2043,7 +2080,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, const uint8_t moves_queued = nonbusy_movesplanned(); // Slow down when the buffer starts to empty, rather than wait at the corner for a buffer refill - #if EITHER(SLOWDOWN, HAS_SPI_LCD) || defined(XY_FREQUENCY_LIMIT) + #if EITHER(SLOWDOWN, HAS_WIRED_LCD) || defined(XY_FREQUENCY_LIMIT) // Segment time im micro seconds int32_t segment_time_us = LROUND(1000000.0f / inverse_secs); #endif @@ -2058,14 +2095,14 @@ bool Planner::_populate_block(block_t * const block, bool split_move, // Buffer is draining so add extra time. The amount of time added increases if the buffer is still emptied more. const int32_t nst = segment_time_us + LROUND(2 * time_diff / moves_queued); inverse_secs = 1000000.0f / nst; - #if defined(XY_FREQUENCY_LIMIT) || HAS_SPI_LCD + #if defined(XY_FREQUENCY_LIMIT) || HAS_WIRED_LCD segment_time_us = nst; #endif } } #endif - #if HAS_SPI_LCD + #if HAS_WIRED_LCD // Protect the access to the position. const bool was_enabled = stepper.suspend(); @@ -2205,7 +2242,6 @@ bool Planner::_populate_block(block_t * const block, bool split_move, #define MAX_E_JERK(N) TERN(HAS_LINEAR_E_JERK, max_e_jerk[E_INDEX_N(N)], max_jerk.e) /** - * * Use LIN_ADVANCE for blocks if all these are true: * * esteps : This is a print move, because we checked for A, B, C steps before. @@ -2325,9 +2361,9 @@ bool Planner::_populate_block(block_t * const block, bool split_move, * On CoreXY the length of the vector [A,B] is SQRT(2) times the length of the head movement vector [X,Y]. * So taking Z and E into account, we cannot scale to a unit vector with "inverse_millimeters". * => normalize the complete junction vector. - * Elsewise, when needed JD factors in the E component + * Elsewise, when needed JD will factor-in the E component */ - if (ENABLED(IS_CORE) || esteps > 0) + if (EITHER(IS_CORE, MARKFORGED_XY) || esteps > 0) normalize_junction_vector(unit_vec); // Normalize with XYZE components else unit_vec *= inverse_millimeters; // Use pre-calculated (1 / SQRT(x^2 + y^2 + z^2)) @@ -2805,7 +2841,7 @@ bool Planner::buffer_line(const float &rx, const float &ry, const float &rz, con FANS_LOOP(i) block->fan_speed[i] = thermalManager.fan_speed[i]; #endif - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER block->extruder = extruder; #endif @@ -2991,7 +3027,7 @@ void Planner::set_max_jerk(const AxisEnum axis, float targetValue) { #endif } -#if HAS_SPI_LCD +#if HAS_WIRED_LCD uint16_t Planner::block_buffer_runtime() { #ifdef __AVR__ diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index f3a3a0e0fc..c4e11490b1 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -164,7 +164,7 @@ typedef struct block_t { }; uint32_t step_event_count; // The number of step events required to complete this block - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER uint8_t extruder; // The extruder to move (if E move) #else static constexpr uint8_t extruder = 0; @@ -218,7 +218,7 @@ typedef struct block_t { uint8_t valve_pressure, e_to_p_pressure; #endif - #if HAS_SPI_LCD + #if HAS_WIRED_LCD uint32_t segment_time_us; #endif @@ -438,7 +438,7 @@ class Planner { static uint8_t g_uc_extruder_last_move[EXTRUDERS]; #endif - #if HAS_SPI_LCD + #if HAS_WIRED_LCD volatile static uint32_t block_buffer_runtime_us; // Theoretical block buffer runtime in µs #endif @@ -871,7 +871,7 @@ class Planner { block_buffer_tail = next_block_index(block_buffer_tail); } - #if HAS_SPI_LCD + #if HAS_WIRED_LCD static uint16_t block_buffer_runtime(); static void clear_block_buffer_runtime(); #endif diff --git a/Marlin/src/module/planner_bezier.cpp b/Marlin/src/module/planner_bezier.cpp index 4025b773ed..02d878d5f5 100644 --- a/Marlin/src/module/planner_bezier.cpp +++ b/Marlin/src/module/planner_bezier.cpp @@ -24,7 +24,6 @@ * planner_bezier.cpp * * Compute and buffer movement commands for bezier curves - * */ #include "../inc/MarlinConfig.h" diff --git a/Marlin/src/module/planner_bezier.h b/Marlin/src/module/planner_bezier.h index 41a88b4058..72048c4273 100644 --- a/Marlin/src/module/planner_bezier.h +++ b/Marlin/src/module/planner_bezier.h @@ -25,7 +25,6 @@ * planner_bezier.h * * Compute and buffer movement commands for Bézier curves - * */ #include "../core/types.h" diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index 12b617ec43..defc22b1fe 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -270,7 +270,13 @@ FORCE_INLINE void probe_specific_action(const bool deploy) { #if ENABLED(PAUSE_BEFORE_DEPLOY_STOW) do { #if ENABLED(PAUSE_PROBE_DEPLOY_WHEN_TRIGGERED) - if (deploy == (READ(Z_MIN_PROBE_PIN) == Z_MIN_PROBE_ENDSTOP_INVERTING)) break; + if (deploy == ( + #if HAS_CUSTOM_PROBE_PIN + READ(Z_MIN_PROBE_PIN) == Z_MIN_PROBE_ENDSTOP_INVERTING + #else + READ(Z_MIN_PIN) == Z_MIN_ENDSTOP_INVERTING + #endif + )) break; #endif BUZZ(100, 659); @@ -723,7 +729,6 @@ float Probe::probe_at_point(const float &rx, const float &ry, const ProbePtRaise * when starting up the machine or rebooting the board. * There's no way to know where the nozzle is positioned until * homing has been done - no homing with z-probe without init! - * */ STOW_Z_SERVO(); } diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index d5f41a3246..3ccd8ffd91 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -33,7 +33,6 @@ * ALSO: Variables in the Store and Retrieve sections must be in the same order. * If a feature is disabled, some data must still be written that, when read, * either sets a Sane Default, or results in No Change to the existing value. - * */ // Change EEPROM version if the structure changes @@ -52,7 +51,7 @@ #include "temperature.h" #if ENABLED(DWIN_CREALITY_LCD) - #include "../lcd/dwin/dwin.h" + #include "../lcd/dwin/e3v2/dwin.h" #endif #include "../lcd/ultralcd.h" @@ -115,7 +114,7 @@ extern float other_extruder_advance_K[EXTRUDERS]; #endif -#if EXTRUDERS > 1 +#if HAS_MULTI_EXTRUDER #include "tool_change.h" void M217_report(const bool eeprom); #endif @@ -138,7 +137,7 @@ void M710_report(const bool forReplay); #endif -#if ENABLED(CASE_LIGHT_MENU) && DISABLED(CASE_LIGHT_NO_BRIGHTNESS) +#if ENABLED(CASE_LIGHT_ENABLE) && DISABLED(CASE_LIGHT_NO_BRIGHTNESS) #include "../feature/caselight.h" #define HAS_CASE_LIGHT_BRIGHTNESS 1 #endif @@ -388,7 +387,7 @@ typedef struct SettingsDataStruct { // // Tool-change settings // - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER toolchange_settings_t toolchange_settings; // M217 S P R #endif @@ -1191,60 +1190,60 @@ void MarlinSettings::postprocess() { #if HAS_STEALTHCHOP #if AXIS_HAS_STEALTHCHOP(X) - tmc_stealth_enabled.X = stepperX.get_stealthChop_status(); + tmc_stealth_enabled.X = stepperX.get_stored_stealthChop_status(); #endif #if AXIS_HAS_STEALTHCHOP(Y) - tmc_stealth_enabled.Y = stepperY.get_stealthChop_status(); + tmc_stealth_enabled.Y = stepperY.get_stored_stealthChop_status(); #endif #if AXIS_HAS_STEALTHCHOP(Z) - tmc_stealth_enabled.Z = stepperZ.get_stealthChop_status(); + tmc_stealth_enabled.Z = stepperZ.get_stored_stealthChop_status(); #endif #if AXIS_HAS_STEALTHCHOP(X2) - tmc_stealth_enabled.X2 = stepperX2.get_stealthChop_status(); + tmc_stealth_enabled.X2 = stepperX2.get_stored_stealthChop_status(); #endif #if AXIS_HAS_STEALTHCHOP(Y2) - tmc_stealth_enabled.Y2 = stepperY2.get_stealthChop_status(); + tmc_stealth_enabled.Y2 = stepperY2.get_stored_stealthChop_status(); #endif #if AXIS_HAS_STEALTHCHOP(Z2) - tmc_stealth_enabled.Z2 = stepperZ2.get_stealthChop_status(); + tmc_stealth_enabled.Z2 = stepperZ2.get_stored_stealthChop_status(); #endif #if AXIS_HAS_STEALTHCHOP(Z3) - tmc_stealth_enabled.Z3 = stepperZ3.get_stealthChop_status(); + tmc_stealth_enabled.Z3 = stepperZ3.get_stored_stealthChop_status(); #endif #if AXIS_HAS_STEALTHCHOP(Z4) - tmc_stealth_enabled.Z4 = stepperZ4.get_stealthChop_status(); + tmc_stealth_enabled.Z4 = stepperZ4.get_stored_stealthChop_status(); #endif #if MAX_EXTRUDERS #if AXIS_HAS_STEALTHCHOP(E0) - tmc_stealth_enabled.E0 = stepperE0.get_stealthChop_status(); + tmc_stealth_enabled.E0 = stepperE0.get_stored_stealthChop_status(); #endif #if MAX_EXTRUDERS > 1 #if AXIS_HAS_STEALTHCHOP(E1) - tmc_stealth_enabled.E1 = stepperE1.get_stealthChop_status(); + tmc_stealth_enabled.E1 = stepperE1.get_stored_stealthChop_status(); #endif #if MAX_EXTRUDERS > 2 #if AXIS_HAS_STEALTHCHOP(E2) - tmc_stealth_enabled.E2 = stepperE2.get_stealthChop_status(); + tmc_stealth_enabled.E2 = stepperE2.get_stored_stealthChop_status(); #endif #if MAX_EXTRUDERS > 3 #if AXIS_HAS_STEALTHCHOP(E3) - tmc_stealth_enabled.E3 = stepperE3.get_stealthChop_status(); + tmc_stealth_enabled.E3 = stepperE3.get_stored_stealthChop_status(); #endif #if MAX_EXTRUDERS > 4 #if AXIS_HAS_STEALTHCHOP(E4) - tmc_stealth_enabled.E4 = stepperE4.get_stealthChop_status(); + tmc_stealth_enabled.E4 = stepperE4.get_stored_stealthChop_status(); #endif #if MAX_EXTRUDERS > 5 #if AXIS_HAS_STEALTHCHOP(E5) - tmc_stealth_enabled.E5 = stepperE5.get_stealthChop_status(); + tmc_stealth_enabled.E5 = stepperE5.get_stored_stealthChop_status(); #endif #if MAX_EXTRUDERS > 6 #if AXIS_HAS_STEALTHCHOP(E6) - tmc_stealth_enabled.E6 = stepperE6.get_stealthChop_status(); + tmc_stealth_enabled.E6 = stepperE6.get_stored_stealthChop_status(); #endif #if MAX_EXTRUDERS > 7 #if AXIS_HAS_STEALTHCHOP(E7) - tmc_stealth_enabled.E7 = stepperE7.get_stealthChop_status(); + tmc_stealth_enabled.E7 = stepperE7.get_stored_stealthChop_status(); #endif #endif // MAX_EXTRUDERS > 7 #endif // MAX_EXTRUDERS > 6 @@ -1320,7 +1319,7 @@ void MarlinSettings::postprocess() { // Multiple Extruders // - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER _FIELD_TEST(toolchange_settings); EEPROM_WRITE(toolchange_settings); #endif @@ -1804,10 +1803,11 @@ void MarlinSettings::postprocess() { // { _FIELD_TEST(lcd_contrast); - int16_t lcd_contrast; EEPROM_READ(lcd_contrast); - TERN_(HAS_LCD_CONTRAST, ui.set_contrast(lcd_contrast)); + if (!validating) { + TERN_(HAS_LCD_CONTRAST, ui.set_contrast(lcd_contrast)); + } } // @@ -2167,7 +2167,7 @@ void MarlinSettings::postprocess() { // // Tool-change settings // - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER _FIELD_TEST(toolchange_settings); EEPROM_READ(toolchange_settings); #endif @@ -2488,7 +2488,7 @@ void MarlinSettings::reset() { // Tool-change Settings // - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER #if ENABLED(TOOLCHANGE_FILAMENT_SWAP) toolchange_settings.swap_length = TOOLCHANGE_FS_LENGTH; toolchange_settings.extra_resume = TOOLCHANGE_FS_EXTRA_RESUME_LENGTH; @@ -3595,17 +3595,17 @@ void MarlinSettings::reset() { #if HAS_STEALTHCHOP CONFIG_ECHO_HEADING("Driver stepping mode:"); #if AXIS_HAS_STEALTHCHOP(X) - const bool chop_x = stepperX.get_stealthChop_status(); + const bool chop_x = stepperX.get_stored_stealthChop_status(); #else constexpr bool chop_x = false; #endif #if AXIS_HAS_STEALTHCHOP(Y) - const bool chop_y = stepperY.get_stealthChop_status(); + const bool chop_y = stepperY.get_stored_stealthChop_status(); #else constexpr bool chop_y = false; #endif #if AXIS_HAS_STEALTHCHOP(Z) - const bool chop_z = stepperZ.get_stealthChop_status(); + const bool chop_z = stepperZ.get_stored_stealthChop_status(); #else constexpr bool chop_z = false; #endif @@ -3619,17 +3619,17 @@ void MarlinSettings::reset() { } #if AXIS_HAS_STEALTHCHOP(X2) - const bool chop_x2 = stepperX2.get_stealthChop_status(); + const bool chop_x2 = stepperX2.get_stored_stealthChop_status(); #else constexpr bool chop_x2 = false; #endif #if AXIS_HAS_STEALTHCHOP(Y2) - const bool chop_y2 = stepperY2.get_stealthChop_status(); + const bool chop_y2 = stepperY2.get_stored_stealthChop_status(); #else constexpr bool chop_y2 = false; #endif #if AXIS_HAS_STEALTHCHOP(Z2) - const bool chop_z2 = stepperZ2.get_stealthChop_status(); + const bool chop_z2 = stepperZ2.get_stored_stealthChop_status(); #else constexpr bool chop_z2 = false; #endif @@ -3643,36 +3643,36 @@ void MarlinSettings::reset() { } #if AXIS_HAS_STEALTHCHOP(Z3) - if (stepperZ3.get_stealthChop_status()) { say_M569(forReplay, PSTR("I2 Z"), true); } + if (stepperZ3.get_stored_stealthChop_status()) { say_M569(forReplay, PSTR("I2 Z"), true); } #endif #if AXIS_HAS_STEALTHCHOP(Z4) - if (stepperZ4.get_stealthChop_status()) { say_M569(forReplay, PSTR("I3 Z"), true); } + if (stepperZ4.get_stored_stealthChop_status()) { say_M569(forReplay, PSTR("I3 Z"), true); } #endif #if AXIS_HAS_STEALTHCHOP(E0) - if (stepperE0.get_stealthChop_status()) { say_M569(forReplay, PSTR("T0 E"), true); } + if (stepperE0.get_stored_stealthChop_status()) { say_M569(forReplay, PSTR("T0 E"), true); } #endif #if AXIS_HAS_STEALTHCHOP(E1) - if (stepperE1.get_stealthChop_status()) { say_M569(forReplay, PSTR("T1 E"), true); } + if (stepperE1.get_stored_stealthChop_status()) { say_M569(forReplay, PSTR("T1 E"), true); } #endif #if AXIS_HAS_STEALTHCHOP(E2) - if (stepperE2.get_stealthChop_status()) { say_M569(forReplay, PSTR("T2 E"), true); } + if (stepperE2.get_stored_stealthChop_status()) { say_M569(forReplay, PSTR("T2 E"), true); } #endif #if AXIS_HAS_STEALTHCHOP(E3) - if (stepperE3.get_stealthChop_status()) { say_M569(forReplay, PSTR("T3 E"), true); } + if (stepperE3.get_stored_stealthChop_status()) { say_M569(forReplay, PSTR("T3 E"), true); } #endif #if AXIS_HAS_STEALTHCHOP(E4) - if (stepperE4.get_stealthChop_status()) { say_M569(forReplay, PSTR("T4 E"), true); } + if (stepperE4.get_stored_stealthChop_status()) { say_M569(forReplay, PSTR("T4 E"), true); } #endif #if AXIS_HAS_STEALTHCHOP(E5) - if (stepperE5.get_stealthChop_status()) { say_M569(forReplay, PSTR("T5 E"), true); } + if (stepperE5.get_stored_stealthChop_status()) { say_M569(forReplay, PSTR("T5 E"), true); } #endif #if AXIS_HAS_STEALTHCHOP(E6) - if (stepperE6.get_stealthChop_status()) { say_M569(forReplay, PSTR("T6 E"), true); } + if (stepperE6.get_stored_stealthChop_status()) { say_M569(forReplay, PSTR("T6 E"), true); } #endif #if AXIS_HAS_STEALTHCHOP(E7) - if (stepperE7.get_stealthChop_status()) { say_M569(forReplay, PSTR("T7 E"), true); } + if (stepperE7.get_stored_stealthChop_status()) { say_M569(forReplay, PSTR("T7 E"), true); } #endif #endif // HAS_STEALTHCHOP @@ -3719,7 +3719,7 @@ void MarlinSettings::reset() { #endif #endif - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER CONFIG_ECHO_HEADING("Tool-changing:"); CONFIG_ECHO_START(); M217_report(true); diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index 0e70fd370c..56a75d1b48 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -155,7 +155,7 @@ uint8_t Stepper::last_direction_bits, // = 0 bool Stepper::abort_current_block; -#if DISABLED(MIXING_EXTRUDER) && EXTRUDERS > 1 +#if DISABLED(MIXING_EXTRUDER) && HAS_MULTI_EXTRUDER uint8_t Stepper::last_moved_extruder = 0xFF; #endif @@ -191,7 +191,7 @@ uint32_t Stepper::advance_divisor = 0, Stepper::decelerate_after, // The count at which to start decelerating Stepper::step_event_count; // The total event count for the current block -#if EXTRUDERS > 1 || ENABLED(MIXING_EXTRUDER) +#if EITHER(HAS_MULTI_EXTRUDER, MIXING_EXTRUDER) uint8_t Stepper::stepper_extruder; #else constexpr uint8_t Stepper::stepper_extruder; @@ -357,11 +357,11 @@ xyze_int8_t Stepper::count_direction{0}; #elif ENABLED(DUAL_X_CARRIAGE) #define X_APPLY_DIR(v,ALWAYS) do{ \ if (extruder_duplication_enabled || ALWAYS) { X_DIR_WRITE(v); X2_DIR_WRITE(mirrored_duplication_mode ? !(v) : v); } \ - else if (movement_extruder()) X2_DIR_WRITE(v); else X_DIR_WRITE(v); \ + else if (last_moved_extruder) X2_DIR_WRITE(v); else X_DIR_WRITE(v); \ }while(0) #define X_APPLY_STEP(v,ALWAYS) do{ \ if (extruder_duplication_enabled || ALWAYS) { X_STEP_WRITE(v); X2_STEP_WRITE(v); } \ - else if (movement_extruder()) X2_STEP_WRITE(v); else X_STEP_WRITE(v); \ + else if (last_moved_extruder) X2_STEP_WRITE(v); else X_STEP_WRITE(v); \ }while(0) #else #define X_APPLY_DIR(v,Q) X_DIR_WRITE(v) @@ -2041,6 +2041,8 @@ uint32_t Stepper::block_phase_isr() { #define X_CMP(A,B) ((A)!=(B)) #endif #define X_MOVE_TEST ( S_(1) != S_(2) || (S_(1) > 0 && X_CMP(D_(1),D_(2))) ) + #elif ENABLED(MARKFORGED_XY) + #define X_MOVE_TEST (current_block->steps.a != current_block->steps.b) #else #define X_MOVE_TEST !!current_block->steps.a #endif @@ -2129,7 +2131,7 @@ uint32_t Stepper::block_phase_isr() { MIXER_STEPPER_SETUP(); #endif - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER stepper_extruder = current_block->extruder; #endif @@ -2154,7 +2156,7 @@ uint32_t Stepper::block_phase_isr() { || TERN(MIXING_EXTRUDER, false, stepper_extruder != last_moved_extruder) ) { last_direction_bits = current_block->direction_bits; - #if EXTRUDERS > 1 + #if HAS_MULTI_EXTRUDER last_moved_extruder = stepper_extruder; #endif @@ -2614,6 +2616,8 @@ void Stepper::_set_position(const int32_t &a, const int32_t &b, const int32_t &c #elif CORE_IS_YZ // coreyz planning count_position.set(a, b + c, CORESIGN(b - c)); + #elif ENABLED(MARKFORGED_XY) + count_position.set(a - b, b, c); #else // default non-h-bot planning count_position.set(a, b, c); @@ -2680,6 +2684,10 @@ void Stepper::endstop_triggered(const AxisEnum axis) { ? CORESIGN(count_position[CORE_AXIS_1] - count_position[CORE_AXIS_2]) : count_position[CORE_AXIS_1] + count_position[CORE_AXIS_2] ) * double(0.5) + #elif ENABLED(MARKFORGED_XY) + axis == CORE_AXIS_1 + ? count_position[CORE_AXIS_1] - count_position[CORE_AXIS_2] + : count_position[CORE_AXIS_2] #else // !IS_CORE count_position[axis] #endif @@ -2709,12 +2717,12 @@ int32_t Stepper::triggered_position(const AxisEnum axis) { } void Stepper::report_a_position(const xyz_long_t &pos) { - #if CORE_IS_XY || CORE_IS_XZ || ENABLED(DELTA) || IS_SCARA + #if ANY(CORE_IS_XY, CORE_IS_XZ, MARKFORGED_XY, DELTA, IS_SCARA) SERIAL_ECHOPAIR(STR_COUNT_A, pos.x, " B:", pos.y); #else SERIAL_ECHOPAIR_P(PSTR(STR_COUNT_X), pos.x, SP_Y_LBL, pos.y); #endif - #if CORE_IS_XZ || CORE_IS_YZ || ENABLED(DELTA) + #if ANY(CORE_IS_XZ, CORE_IS_YZ, DELTA) SERIAL_ECHOLNPAIR(" C:", pos.z); #else SERIAL_ECHOLNPAIR_P(SP_Z_LBL, pos.z); diff --git a/Marlin/src/module/stepper.h b/Marlin/src/module/stepper.h index 3b68553689..da38192d8e 100644 --- a/Marlin/src/module/stepper.h +++ b/Marlin/src/module/stepper.h @@ -253,6 +253,13 @@ class Stepper { static bool initialized; #endif + // Last-moved extruder, as set when the last movement was fetched from planner + #if HAS_MULTI_EXTRUDER + static uint8_t last_moved_extruder; + #else + static constexpr uint8_t last_moved_extruder = 0; + #endif + private: static block_t* current_block; // A pointer to the block currently being traced @@ -262,13 +269,6 @@ class Stepper { static bool abort_current_block; // Signals to the stepper that current block should be aborted - // Last-moved extruder, as set when the last movement was fetched from planner - #if EXTRUDERS < 2 - static constexpr uint8_t last_moved_extruder = 0; - #elif DISABLED(MIXING_EXTRUDER) - static uint8_t last_moved_extruder; - #endif - #if ENABLED(X_DUAL_ENDSTOPS) static bool locked_X_motor, locked_X2_motor; #endif @@ -304,7 +304,7 @@ class Stepper { decelerate_after, // The point from where we need to start decelerating step_event_count; // The total event count for the current block - #if EXTRUDERS > 1 || ENABLED(MIXING_EXTRUDER) + #if EITHER(HAS_MULTI_EXTRUDER, MIXING_EXTRUDER) static uint8_t stepper_extruder; #else static constexpr uint8_t stepper_extruder = 0; @@ -451,11 +451,6 @@ class Stepper { // The last movement direction was not null on the specified axis. Note that motor direction is not necessarily the same. FORCE_INLINE static bool axis_is_moving(const AxisEnum axis) { return TEST(axis_did_move, axis); } - // The extruder associated to the last movement - FORCE_INLINE static uint8_t movement_extruder() { - return (EXTRUDERS > 1 && DISABLED(MIXING_EXTRUDER)) ? last_moved_extruder : 0; - } - // Handle a triggered endstop static void endstop_triggered(const AxisEnum axis); diff --git a/Marlin/src/module/stepper/trinamic.cpp b/Marlin/src/module/stepper/trinamic.cpp index 3dda98698b..d5a861d71b 100644 --- a/Marlin/src/module/stepper/trinamic.cpp +++ b/Marlin/src/module/stepper/trinamic.cpp @@ -209,113 +209,145 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; #if AXIS_HAS_UART(X) #ifdef X_HARDWARE_SERIAL TMC_UART_DEFINE(HW, X, X); + #define X_HAS_HW_SERIAL 1 #else TMC_UART_DEFINE(SW, X, X); + #define X_HAS_SW_SERIAL 1 #endif #endif #if AXIS_HAS_UART(X2) #ifdef X2_HARDWARE_SERIAL TMC_UART_DEFINE(HW, X2, X); + #define X2_HAS_HW_SERIAL 1 #else TMC_UART_DEFINE(SW, X2, X); + #define X2_HAS_SW_SERIAL 1 #endif #endif #if AXIS_HAS_UART(Y) #ifdef Y_HARDWARE_SERIAL TMC_UART_DEFINE(HW, Y, Y); + #define Y_HAS_HW_SERIAL 1 #else TMC_UART_DEFINE(SW, Y, Y); + #define Y_HAS_SW_SERIAL 1 #endif #endif #if AXIS_HAS_UART(Y2) #ifdef Y2_HARDWARE_SERIAL TMC_UART_DEFINE(HW, Y2, Y); + #define Y2_HAS_HW_SERIAL 1 #else TMC_UART_DEFINE(SW, Y2, Y); + #define Y2_HAS_SW_SERIAL 1 #endif #endif #if AXIS_HAS_UART(Z) #ifdef Z_HARDWARE_SERIAL TMC_UART_DEFINE(HW, Z, Z); + #define Z_HAS_HW_SERIAL 1 #else TMC_UART_DEFINE(SW, Z, Z); + #define Z_HAS_SW_SERIAL 1 #endif #endif #if AXIS_HAS_UART(Z2) #ifdef Z2_HARDWARE_SERIAL TMC_UART_DEFINE(HW, Z2, Z); + #define Z2_HAS_HW_SERIAL 1 #else TMC_UART_DEFINE(SW, Z2, Z); + #define Z2_HAS_SW_SERIAL 1 #endif #endif #if AXIS_HAS_UART(Z3) #ifdef Z3_HARDWARE_SERIAL TMC_UART_DEFINE(HW, Z3, Z); + #define Z3_HAS_HW_SERIAL 1 #else TMC_UART_DEFINE(SW, Z3, Z); + #define Z3_HAS_SW_SERIAL 1 #endif #endif #if AXIS_HAS_UART(Z4) #ifdef Z4_HARDWARE_SERIAL TMC_UART_DEFINE(HW, Z4, Z); + #define Z4_HAS_HW_SERIAL 1 #else TMC_UART_DEFINE(SW, Z4, Z); + #define Z4_HAS_SW_SERIAL 1 #endif #endif #if AXIS_HAS_UART(E0) #ifdef E0_HARDWARE_SERIAL TMC_UART_DEFINE_E(HW, 0); + #define E0_HAS_HW_SERIAL 1 #else TMC_UART_DEFINE_E(SW, 0); + #define E0_HAS_SW_SERIAL 1 #endif #endif #if AXIS_HAS_UART(E1) #ifdef E1_HARDWARE_SERIAL TMC_UART_DEFINE_E(HW, 1); + #define E1_HAS_HW_SERIAL 1 #else TMC_UART_DEFINE_E(SW, 1); + #define E1_HAS_SW_SERIAL 1 #endif #endif #if AXIS_HAS_UART(E2) #ifdef E2_HARDWARE_SERIAL TMC_UART_DEFINE_E(HW, 2); + #define E2_HAS_HW_SERIAL 1 #else TMC_UART_DEFINE_E(SW, 2); + #define E2_HAS_SW_SERIAL 1 #endif #endif #if AXIS_HAS_UART(E3) #ifdef E3_HARDWARE_SERIAL TMC_UART_DEFINE_E(HW, 3); + #define E3_HAS_HW_SERIAL 1 #else TMC_UART_DEFINE_E(SW, 3); + #define E3_HAS_SW_SERIAL 1 #endif #endif #if AXIS_HAS_UART(E4) #ifdef E4_HARDWARE_SERIAL TMC_UART_DEFINE_E(HW, 4); + #define E4_HAS_HW_SERIAL 1 #else TMC_UART_DEFINE_E(SW, 4); + #define E4_HAS_SW_SERIAL 1 #endif #endif #if AXIS_HAS_UART(E5) #ifdef E5_HARDWARE_SERIAL TMC_UART_DEFINE_E(HW, 5); + #define E5_HAS_HW_SERIAL 1 #else TMC_UART_DEFINE_E(SW, 5); + #define E5_HAS_SW_SERIAL 1 #endif #endif #if AXIS_HAS_UART(E6) #ifdef E6_HARDWARE_SERIAL TMC_UART_DEFINE_E(HW, 6); + #define E6_HAS_HW_SERIAL 1 #else TMC_UART_DEFINE_E(SW, 6); + #define E6_HAS_SW_SERIAL 1 #endif #endif #if AXIS_HAS_UART(E7) #ifdef E7_HARDWARE_SERIAL TMC_UART_DEFINE_E(HW, 7); + #define E7_HAS_HW_SERIAL 1 #else TMC_UART_DEFINE_E(SW, 7); + #define E7_HAS_SW_SERIAL 1 #endif #endif @@ -769,4 +801,77 @@ void reset_trinamic_drivers() { stepper.set_directions(); } +// TMC Slave Address Conflict Detection +// +// Conflict detection is performed in the following way. Similar methods are used for +// hardware and software serial, but the implementations are indepenent. +// +// 1. Populate a data structure with UART parameters and addresses for all possible axis. +// If an axis is not in use, populate it with recognizable placeholder data. +// 2. For each axis in use, static_assert using a constexpr function, which counts the +// number of matching/conflicting axis. If the value is not exactly 1, fail. + +#if ANY_AXIS_HAS(HW_SERIAL) + // Hardware serial names are compared as strings, since actually resolving them cannot occur in a constexpr. + // Using a fixed-length character array for the port name allows this to be constexpr compatible. + struct SanityHwSerialDetails { const char port[20]; uint32_t address; }; + #define TMC_HW_DETAIL_ARGS(A) TERN(A##_HAS_HW_SERIAL, STRINGIFY(A##_HARDWARE_SERIAL), ""), TERN0(A##_HAS_HW_SERIAL, A##_SLAVE_ADDRESS) + #define TMC_HW_DETAIL(A) {TMC_HW_DETAIL_ARGS(A)} + constexpr SanityHwSerialDetails sanity_tmc_hw_details[] = { + TMC_HW_DETAIL(X), TMC_HW_DETAIL(X2), + TMC_HW_DETAIL(Y), TMC_HW_DETAIL(Y2), + TMC_HW_DETAIL(Z), TMC_HW_DETAIL(Z2), TMC_HW_DETAIL(Z3), TMC_HW_DETAIL(Z4), + TMC_HW_DETAIL(E0), TMC_HW_DETAIL(E1), TMC_HW_DETAIL(E2), TMC_HW_DETAIL(E3), TMC_HW_DETAIL(E4), TMC_HW_DETAIL(E5), TMC_HW_DETAIL(E6), TMC_HW_DETAIL(E7) + }; + + // constexpr compatible string comparison + constexpr bool str_eq_ce(const char * a, const char * b) { + return *a == *b && (*a == '\0' || str_eq_ce(a+1,b+1)); + } + + constexpr bool sc_hw_done(size_t start, size_t end) { return start == end; } + constexpr bool sc_hw_skip(const char* port_name) { return !(*port_name); } + constexpr bool sc_hw_match(const char* port_name, uint32_t address, size_t start, size_t end) { + return !sc_hw_done(start, end) && !sc_hw_skip(port_name) && (address == sanity_tmc_hw_details[start].address && str_eq_ce(port_name, sanity_tmc_hw_details[start].port)); + } + constexpr int count_tmc_hw_serial_matches(const char* port_name, uint32_t address, size_t start, size_t end) { + return sc_hw_done(start, end) ? 0 : ((sc_hw_skip(port_name) ? 0 : (sc_hw_match(port_name, address, start, end) ? 1 : 0)) + count_tmc_hw_serial_matches(port_name, address, start + 1, end)); + } + + #define TMC_HWSERIAL_CONFLICT_MSG(A) STRINGIFY(A) "_SLAVE_ADDRESS conflicts with another driver using the same " STRINGIFY(A) "_HARDWARE_SERIAL" + #define SA_NO_TMC_HW_C(A) static_assert(1 >= count_tmc_hw_serial_matches(TMC_HW_DETAIL_ARGS(A), 0, COUNT(sanity_tmc_hw_details)), TMC_HWSERIAL_CONFLICT_MSG(A)); + SA_NO_TMC_HW_C(X);SA_NO_TMC_HW_C(X2); + SA_NO_TMC_HW_C(Y);SA_NO_TMC_HW_C(Y2); + SA_NO_TMC_HW_C(Z);SA_NO_TMC_HW_C(Z2);SA_NO_TMC_HW_C(Z3);SA_NO_TMC_HW_C(Z4); + SA_NO_TMC_HW_C(E0);SA_NO_TMC_HW_C(E1);SA_NO_TMC_HW_C(E2);SA_NO_TMC_HW_C(E3);SA_NO_TMC_HW_C(E4);SA_NO_TMC_HW_C(E5);SA_NO_TMC_HW_C(E6);SA_NO_TMC_HW_C(E7); +#endif + +#if ANY_AXIS_HAS(SW_SERIAL) + struct SanitySwSerialDetails { int32_t txpin; int32_t rxpin; uint32_t address; }; + #define TMC_SW_DETAIL_ARGS(A) TERN(A##_HAS_SW_SERIAL, A##_SERIAL_TX_PIN, -1), TERN(A##_HAS_SW_SERIAL, A##_SERIAL_RX_PIN, -1), TERN0(A##_HAS_SW_SERIAL, A##_SLAVE_ADDRESS) + #define TMC_SW_DETAIL(A) TMC_SW_DETAIL_ARGS(A) + constexpr SanitySwSerialDetails sanity_tmc_sw_details[] = { + TMC_SW_DETAIL(X), TMC_SW_DETAIL(X2), + TMC_SW_DETAIL(Y), TMC_SW_DETAIL(Y2), + TMC_SW_DETAIL(Z), TMC_SW_DETAIL(Z2), TMC_SW_DETAIL(Z3), TMC_SW_DETAIL(Z4), + TMC_SW_DETAIL(E0), TMC_SW_DETAIL(E1), TMC_SW_DETAIL(E2), TMC_SW_DETAIL(E3), TMC_SW_DETAIL(E4), TMC_SW_DETAIL(E5), TMC_SW_DETAIL(E6), TMC_SW_DETAIL(E7) + }; + + constexpr bool sc_sw_done(size_t start, size_t end) { return start == end; } + constexpr bool sc_sw_skip(int32_t txpin) { return txpin < 0; } + constexpr bool sc_sw_match(int32_t txpin, int32_t rxpin, uint32_t address, size_t start, size_t end) { + return !sc_sw_done(start, end) && !sc_sw_skip(txpin) && (txpin == sanity_tmc_sw_details[start].txpin || rxpin == sanity_tmc_sw_details[start].rxpin) && (address == sanity_tmc_sw_details[start].address); + } + constexpr int count_tmc_sw_serial_matches(int32_t txpin, int32_t rxpin, uint32_t address, size_t start, size_t end) { + return sc_sw_done(start, end) ? 0 : ((sc_sw_skip(txpin) ? 0 : (sc_sw_match(txpin, rxpin, address, start, end) ? 1 : 0)) + count_tmc_sw_serial_matches(txpin, rxpin, address, start + 1, end)); + } + + #define TMC_SWSERIAL_CONFLICT_MSG(A) STRINGIFY(A) "_SLAVE_ADDRESS conflicts with another driver using the same " STRINGIFY(A) "_SERIAL_RX_PIN or " STRINGIFY(A) "_SERIAL_TX_PIN" + #define SA_NO_TMC_SW_C(A) static_assert(1 >= count_tmc_sw_serial_matches(TMC_SW_DETAIL_ARGS(A), 0, COUNT(sanity_tmc_sw_details)), TMC_SWSERIAL_CONFLICT_MSG(A)); + SA_NO_TMC_SW_C(X);SA_NO_TMC_SW_C(X2); + SA_NO_TMC_SW_C(Y);SA_NO_TMC_SW_C(Y2); + SA_NO_TMC_SW_C(Z);SA_NO_TMC_SW_C(Z2);SA_NO_TMC_SW_C(Z3);SA_NO_TMC_SW_C(Z4); + SA_NO_TMC_SW_C(E0);SA_NO_TMC_SW_C(E1);SA_NO_TMC_SW_C(E2);SA_NO_TMC_SW_C(E3);SA_NO_TMC_SW_C(E4);SA_NO_TMC_SW_C(E5);SA_NO_TMC_SW_C(E6);SA_NO_TMC_SW_C(E7); +#endif + #endif // HAS_TRINAMIC_CONFIG diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index a4bbd7e6b2..36fcf99dba 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -37,7 +37,7 @@ #include "../lcd/ultralcd.h" #if ENABLED(DWIN_CREALITY_LCD) - #include "../lcd/dwin/dwin.h" + #include "../lcd/dwin/e3v2/dwin.h" #endif #if ENABLED(EXTENSIBLE_UI) @@ -252,7 +252,7 @@ const char str_t_thermal_runaway[] PROGMEM = STR_T_THERMAL_RUNAWAY, hotend_watch_t Temperature::watch_hotend[HOTENDS]; // = { { 0 } } #endif #if HEATER_IDLE_HANDLER - hotend_idle_t Temperature::hotend_idle[HOTENDS]; // = { { 0 } } + Temperature::heater_idle_t Temperature::heater_idle[NR_HEATER_IDLE]; // = { { 0 } } #endif #if HAS_HEATED_BED @@ -266,7 +266,6 @@ const char str_t_thermal_runaway[] PROGMEM = STR_T_THERMAL_RUNAWAY, #endif TERN_(WATCH_BED, bed_watch_t Temperature::watch_bed); // = { 0 } TERN(PIDTEMPBED,, millis_t Temperature::next_bed_check_ms); - TERN_(HEATER_IDLE_HANDLER, hotend_idle_t Temperature::bed_idle); // = { 0 } #endif // HAS_HEATED_BED #if HAS_TEMP_CHAMBER @@ -377,7 +376,7 @@ volatile bool Temperature::raw_temps_ready = false; * Needs sufficient heater power to make some overshoot at target * temperature to succeed. */ - void Temperature::PID_autotune(const float &target, const heater_ind_t heater, const int8_t ncycles, const bool set_result/*=false*/) { + void Temperature::PID_autotune(const float &target, const heater_id_t heater_id, const int8_t ncycles, const bool set_result/*=false*/) { float current_temp = 0.0; int cycles = 0; bool heating = true; @@ -389,11 +388,11 @@ volatile bool Temperature::raw_temps_ready = false; PID_t tune_pid = { 0, 0, 0 }; float maxT = 0, minT = 10000; - const bool isbed = (heater == H_BED); + const bool isbed = (heater_id == H_BED); #if HAS_PID_FOR_BOTH #define GHV(B,H) (isbed ? (B) : (H)) - #define SHV(B,H) do{ if (isbed) temp_bed.soft_pwm_amount = B; else temp_hotend[heater].soft_pwm_amount = H; }while(0) + #define SHV(B,H) do{ if (isbed) temp_bed.soft_pwm_amount = B; else temp_hotend[heater_id].soft_pwm_amount = H; }while(0) #define ONHEATINGSTART() (isbed ? printerEventLEDs.onBedHeatingStart() : printerEventLEDs.onHotendHeatingStart()) #define ONHEATING(S,C,T) (isbed ? printerEventLEDs.onBedHeating(S,C,T) : printerEventLEDs.onHotendHeating(S,C,T)) #elif ENABLED(PIDTEMPBED) @@ -403,7 +402,7 @@ volatile bool Temperature::raw_temps_ready = false; #define ONHEATING(S,C,T) printerEventLEDs.onBedHeating(S,C,T) #else #define GHV(B,H) H - #define SHV(B,H) (temp_hotend[heater].soft_pwm_amount = H) + #define SHV(B,H) (temp_hotend[heater_id].soft_pwm_amount = H) #define ONHEATINGSTART() printerEventLEDs.onHotendHeatingStart() #define ONHEATING(S,C,T) printerEventLEDs.onHotendHeating(S,C,T) #endif @@ -427,7 +426,7 @@ volatile bool Temperature::raw_temps_ready = false; TERN_(HAS_AUTO_FAN, next_auto_fan_check_ms = next_temp_ms + 2500UL); - if (target > GHV(BED_MAX_TARGET, temp_range[heater].maxtemp - HOTEND_OVERSHOOT)) { + if (target > GHV(BED_MAX_TARGET, temp_range[heater_id].maxtemp - HOTEND_OVERSHOOT)) { SERIAL_ECHOLNPGM(STR_PID_TEMP_TOO_HIGH); TERN_(EXTENSIBLE_UI, ExtUI::onPidTuning(ExtUI::result_t::PID_TEMP_TOO_HIGH)); return; @@ -440,15 +439,15 @@ volatile bool Temperature::raw_temps_ready = false; SHV(bias = d = (MAX_BED_POWER) >> 1, bias = d = (PID_MAX) >> 1); - wait_for_heatup = true; // Can be interrupted with M108 #if ENABLED(PRINTER_EVENT_LEDS) - const float start_temp = GHV(temp_bed.celsius, temp_hotend[heater].celsius); + const float start_temp = GHV(temp_bed.celsius, temp_hotend[heater_id].celsius); LEDColor color = ONHEATINGSTART(); #endif TERN_(NO_FAN_SLOWING_IN_PID_TUNING, adaptive_fan_slowing = false); // PID Tuning loop + wait_for_heatup = true; // Can be interrupted with M108 while (wait_for_heatup) { const millis_t ms = millis(); @@ -457,7 +456,7 @@ volatile bool Temperature::raw_temps_ready = false; updateTemperaturesFromRawValues(); // Get the current temperature and constrain it - current_temp = GHV(temp_bed.celsius, temp_hotend[heater].celsius); + current_temp = GHV(temp_bed.celsius, temp_hotend[heater_id].celsius); NOLESS(maxT, current_temp); NOMORE(minT, current_temp); @@ -549,7 +548,7 @@ volatile bool Temperature::raw_temps_ready = false; // Report heater states every 2 seconds if (ELAPSED(ms, next_temp_ms)) { #if HAS_TEMP_SENSOR - print_heater_states(isbed ? active_extruder : heater); + print_heater_states(isbed ? active_extruder : heater_id); SERIAL_EOL(); #endif next_temp_ms = ms + 2000UL; @@ -564,10 +563,10 @@ volatile bool Temperature::raw_temps_ready = false; if (current_temp > watch_temp_target) heated = true; // - Flag if target temperature reached } else if (ELAPSED(ms, temp_change_ms)) // Watch timer expired - _temp_error(heater, str_t_heating_failed, GET_TEXT(MSG_HEATING_FAILED_LCD)); + _temp_error(heater_id, str_t_heating_failed, GET_TEXT(MSG_HEATING_FAILED_LCD)); } else if (current_temp < target - (MAX_OVERSHOOT_PID_AUTOTUNE)) // Heated, then temperature fell too far? - _temp_error(heater, str_t_thermal_runaway, GET_TEXT(MSG_THERMAL_RUNAWAY)); + _temp_error(heater_id, str_t_thermal_runaway, GET_TEXT(MSG_THERMAL_RUNAWAY)); } #endif } // every 2 seconds @@ -577,7 +576,7 @@ volatile bool Temperature::raw_temps_ready = false; #define MAX_CYCLE_TIME_PID_AUTOTUNE 20L #endif if ((ms - _MIN(t1, t2)) > (MAX_CYCLE_TIME_PID_AUTOTUNE * 60L * 1000L)) { - TERN_(DWIN_CREALITY_LCD, Popup_Window_Temperature(0)); + TERN_(DWIN_CREALITY_LCD, DWIN_Popup_Temperature(0)); TERN_(EXTENSIBLE_UI, ExtUI::onPidTuning(ExtUI::result_t::PID_TUNING_TIMEOUT)); SERIAL_ECHOLNPGM(STR_PID_TIMEOUT); break; @@ -608,9 +607,9 @@ volatile bool Temperature::raw_temps_ready = false; }while(0) #define _SET_EXTRUDER_PID() do { \ - PID_PARAM(Kp, heater) = tune_pid.Kp; \ - PID_PARAM(Ki, heater) = scalePID_i(tune_pid.Ki); \ - PID_PARAM(Kd, heater) = scalePID_d(tune_pid.Kd); \ + PID_PARAM(Kp, heater_id) = tune_pid.Kp; \ + PID_PARAM(Ki, heater_id) = scalePID_i(tune_pid.Ki); \ + PID_PARAM(Kd, heater_id) = scalePID_d(tune_pid.Kd); \ updatePID(); }while(0) // Use the result? (As with "M303 U1") @@ -632,6 +631,7 @@ volatile bool Temperature::raw_temps_ready = false; } TERN(DWIN_CREALITY_LCD, DWIN_Update(), ui.update()); } + wait_for_heatup = false; disable_all_heaters(); @@ -650,7 +650,7 @@ volatile bool Temperature::raw_temps_ready = false; * Class and Instance Methods */ -int16_t Temperature::getHeaterPower(const heater_ind_t heater_id) { +int16_t Temperature::getHeaterPower(const heater_id_t heater_id) { switch (heater_id) { #if HAS_HEATED_BED case H_BED: return temp_bed.soft_pwm_amount; @@ -757,7 +757,7 @@ int16_t Temperature::getHeaterPower(const heater_ind_t heater_id) { // Temperature Error Handlers // -inline void loud_kill(PGM_P const lcd_msg, const heater_ind_t heater) { +inline void loud_kill(PGM_P const lcd_msg, const heater_id_t heater_id) { marlin_state = MF_KILLED; #if USE_BEEPER for (uint8_t i = 20; i--;) { @@ -766,10 +766,10 @@ inline void loud_kill(PGM_P const lcd_msg, const heater_ind_t heater) { } WRITE(BEEPER_PIN, HIGH); #endif - kill(lcd_msg, HEATER_PSTR(heater)); + kill(lcd_msg, HEATER_PSTR(heater_id)); } -void Temperature::_temp_error(const heater_ind_t heater, PGM_P const serial_msg, PGM_P const lcd_msg) { +void Temperature::_temp_error(const heater_id_t heater_id, PGM_P const serial_msg, PGM_P const lcd_msg) { static uint8_t killed = 0; @@ -777,9 +777,9 @@ void Temperature::_temp_error(const heater_ind_t heater, PGM_P const serial_msg, SERIAL_ERROR_START(); serialprintPGM(serial_msg); SERIAL_ECHOPGM(STR_STOPPED_HEATER); - if (heater >= 0) - SERIAL_ECHO((int)heater); - else if (TERN0(HAS_HEATED_CHAMBER, heater == H_CHAMBER)) + if (heater_id >= 0) + SERIAL_ECHO((int)heater_id); + else if (TERN0(HAS_HEATED_CHAMBER, heater_id == H_CHAMBER)) SERIAL_ECHOPGM(STR_HEATER_CHAMBER); else SERIAL_ECHOPGM(STR_HEATER_BED); @@ -800,25 +800,29 @@ void Temperature::_temp_error(const heater_ind_t heater, PGM_P const serial_msg, if (ELAPSED(ms, expire_ms)) ++killed; break; case 2: - loud_kill(lcd_msg, heater); + loud_kill(lcd_msg, heater_id); ++killed; break; } #elif defined(BOGUS_TEMPERATURE_GRACE_PERIOD) UNUSED(killed); #else - if (!killed) { killed = 1; loud_kill(lcd_msg, heater); } + if (!killed) { killed = 1; loud_kill(lcd_msg, heater_id); } #endif } -void Temperature::max_temp_error(const heater_ind_t heater) { - TERN_(DWIN_CREALITY_LCD, Popup_Window_Temperature(1)); - _temp_error(heater, PSTR(STR_T_MAXTEMP), GET_TEXT(MSG_ERR_MAXTEMP)); +void Temperature::max_temp_error(const heater_id_t heater_id) { + #if ENABLED(DWIN_CREALITY_LCD) && (HAS_HOTEND || HAS_HEATED_BED) + DWIN_Popup_Temperature(1); + #endif + _temp_error(heater_id, PSTR(STR_T_MAXTEMP), GET_TEXT(MSG_ERR_MAXTEMP)); } -void Temperature::min_temp_error(const heater_ind_t heater) { - TERN_(DWIN_CREALITY_LCD, Popup_Window_Temperature(0)); - _temp_error(heater, PSTR(STR_T_MINTEMP), GET_TEXT(MSG_ERR_MINTEMP)); +void Temperature::min_temp_error(const heater_id_t heater_id) { + #if ENABLED(DWIN_CREALITY_LCD) && (HAS_HOTEND || HAS_HEATED_BED) + DWIN_Popup_Temperature(0); + #endif + _temp_error(heater_id, PSTR(STR_T_MINTEMP), GET_TEXT(MSG_ERR_MINTEMP)); } #if HAS_HOTEND @@ -840,7 +844,7 @@ void Temperature::min_temp_error(const heater_ind_t heater) { if (temp_hotend[ee].target == 0 || pid_error < -(PID_FUNCTIONAL_RANGE) - || TERN0(HEATER_IDLE_HANDLER, hotend_idle[ee].timed_out) + || TERN0(HEATER_IDLE_HANDLER, heater_idle[ee].timed_out) ) { pid_output = 0; pid_reset[ee] = true; @@ -925,7 +929,7 @@ void Temperature::min_temp_error(const heater_ind_t heater) { #else // No PID enabled - const bool is_idling = TERN0(HEATER_IDLE_HANDLER, hotend_idle[ee].timed_out); + const bool is_idling = TERN0(HEATER_IDLE_HANDLER, heater_idle[ee].timed_out); const float pid_output = (!is_idling && temp_hotend[ee].celsius < temp_hotend[ee].target) ? BANG_MAX : 0; #endif @@ -1039,15 +1043,14 @@ void Temperature::manage_heater() { HOTEND_LOOP() { #if ENABLED(THERMAL_PROTECTION_HOTENDS) - if (degHotend(e) > temp_range[e].maxtemp) - _temp_error((heater_ind_t)e, str_t_thermal_runaway, GET_TEXT(MSG_THERMAL_RUNAWAY)); + if (degHotend(e) > temp_range[e].maxtemp) max_temp_error((heater_id_t)e); #endif - TERN_(HEATER_IDLE_HANDLER, hotend_idle[e].update(ms)); + TERN_(HEATER_IDLE_HANDLER, heater_idle[e].update(ms)); #if ENABLED(THERMAL_PROTECTION_HOTENDS) // Check for thermal runaway - thermal_runaway_protection(tr_state_machine[e], temp_hotend[e].celsius, temp_hotend[e].target, (heater_ind_t)e, THERMAL_PROTECTION_PERIOD, THERMAL_PROTECTION_HYSTERESIS); + tr_state_machine[e].run(temp_hotend[e].celsius, temp_hotend[e].target, (heater_id_t)e, THERMAL_PROTECTION_PERIOD, THERMAL_PROTECTION_HYSTERESIS); #endif temp_hotend[e].soft_pwm_amount = (temp_hotend[e].celsius > temp_range[e].mintemp || is_preheating(e)) && temp_hotend[e].celsius < temp_range[e].maxtemp ? (int)get_pid_output_hotend(e) >> 1 : 0; @@ -1056,8 +1059,8 @@ void Temperature::manage_heater() { // Make sure temperature is increasing if (watch_hotend[e].next_ms && ELAPSED(ms, watch_hotend[e].next_ms)) { // Time to check this extruder? if (degHotend(e) < watch_hotend[e].target) { // Failed to increase enough? - TERN_(DWIN_CREALITY_LCD, Popup_Window_Temperature(0)); - _temp_error((heater_ind_t)e, str_t_heating_failed, GET_TEXT(MSG_HEATING_FAILED_LCD)); + TERN_(DWIN_CREALITY_LCD, DWIN_Popup_Temperature(0)); + _temp_error((heater_id_t)e, str_t_heating_failed, GET_TEXT(MSG_HEATING_FAILED_LCD)); } else // Start again if the target is still far off start_watching_hotend(e); @@ -1092,15 +1095,14 @@ void Temperature::manage_heater() { #if HAS_HEATED_BED #if ENABLED(THERMAL_PROTECTION_BED) - if (degBed() > BED_MAXTEMP) - _temp_error(H_BED, str_t_thermal_runaway, GET_TEXT(MSG_THERMAL_RUNAWAY)); + if (degBed() > BED_MAXTEMP) max_temp_error(H_BED); #endif #if WATCH_BED // Make sure temperature is increasing if (watch_bed.elapsed(ms)) { // Time to check the bed? if (degBed() < watch_bed.target) { // Failed to increase enough? - TERN_(DWIN_CREALITY_LCD, Popup_Window_Temperature(0)); + TERN_(DWIN_CREALITY_LCD, DWIN_Popup_Temperature(0)); _temp_error(H_BED, str_t_heating_failed, GET_TEXT(MSG_HEATING_FAILED_LCD)); } else // Start again if the target is still far off @@ -1126,12 +1128,14 @@ void Temperature::manage_heater() { TERN_(PAUSE_CHANGE_REQD, last_pause_state = paused); #endif - TERN_(HEATER_IDLE_HANDLER, bed_idle.update(ms)); + TERN_(HEATER_IDLE_HANDLER, heater_idle[IDLE_INDEX_BED].update(ms)); - TERN_(HAS_THERMALLY_PROTECTED_BED, thermal_runaway_protection(tr_state_machine_bed, temp_bed.celsius, temp_bed.target, H_BED, THERMAL_PROTECTION_BED_PERIOD, THERMAL_PROTECTION_BED_HYSTERESIS)); + #if HAS_THERMALLY_PROTECTED_BED + tr_state_machine[RUNAWAY_IND_BED].run(temp_bed.celsius, temp_bed.target, H_BED, THERMAL_PROTECTION_BED_PERIOD, THERMAL_PROTECTION_BED_HYSTERESIS); + #endif #if HEATER_IDLE_HANDLER - if (bed_idle.timed_out) { + if (heater_idle[IDLE_INDEX_BED].timed_out) { temp_bed.soft_pwm_amount = 0; #if DISABLED(PIDTEMPBED) WRITE_HEATER_BED(LOW); @@ -1172,8 +1176,7 @@ void Temperature::manage_heater() { #endif #if ENABLED(THERMAL_PROTECTION_CHAMBER) - if (degChamber() > CHAMBER_MAXTEMP) - _temp_error(H_CHAMBER, str_t_thermal_runaway, GET_TEXT(MSG_THERMAL_RUNAWAY)); + if (degChamber() > CHAMBER_MAXTEMP) max_temp_error(H_CHAMBER); #endif #if WATCH_CHAMBER @@ -1204,7 +1207,9 @@ void Temperature::manage_heater() { WRITE_HEATER_CHAMBER(LOW); } - TERN_(THERMAL_PROTECTION_CHAMBER, thermal_runaway_protection(tr_state_machine_chamber, temp_chamber.celsius, temp_chamber.target, H_CHAMBER, THERMAL_PROTECTION_CHAMBER_PERIOD, THERMAL_PROTECTION_CHAMBER_HYSTERESIS)); + #if ENABLED(THERMAL_PROTECTION_CHAMBER) + tr_state_machine[RUNAWAY_IND_CHAMBER].run(temp_chamber.celsius, temp_chamber.target, H_CHAMBER, THERMAL_PROTECTION_CHAMBER_PERIOD, THERMAL_PROTECTION_CHAMBER_HYSTERESIS); + #endif } // TODO: Implement true PID pwm @@ -1562,6 +1567,7 @@ void Temperature::updateTemperaturesFromRawValues() { } #if MAX6675_SEPARATE_SPI + template SoftSPI SPIclass::softSPI; SPIclass max6675_spi; #endif @@ -1937,61 +1943,66 @@ void Temperature::init() { #if HAS_THERMAL_PROTECTION - #if ENABLED(THERMAL_PROTECTION_HOTENDS) - Temperature::tr_state_machine_t Temperature::tr_state_machine[HOTENDS]; // = { { TRInactive, 0 } }; - #endif - #if HAS_THERMALLY_PROTECTED_BED - Temperature::tr_state_machine_t Temperature::tr_state_machine_bed; // = { TRInactive, 0 }; - #endif - #if ENABLED(THERMAL_PROTECTION_CHAMBER) - Temperature::tr_state_machine_t Temperature::tr_state_machine_chamber; // = { TRInactive, 0 }; - #endif + Temperature::tr_state_machine_t Temperature::tr_state_machine[NR_HEATER_RUNAWAY]; // = { { TRInactive, 0 } }; - void Temperature::thermal_runaway_protection(Temperature::tr_state_machine_t &sm, const float ¤t, const float &target, const heater_ind_t heater_id, const uint16_t period_seconds, const uint16_t hysteresis_degc) { + /** + * @brief Thermal Runaway state machine for a single heater + * @param current current measured temperature + * @param target current target temperature + * @param heater_id extruder index + * @param period_seconds missed temperature allowed time + * @param hysteresis_degc allowed distance from target + * + * TODO: Embed the last 3 parameters during init, if not less optimal + */ + void Temperature::tr_state_machine_t::run(const float ¤t, const float &target, const heater_id_t heater_id, const uint16_t period_seconds, const uint16_t hysteresis_degc) { - static float tr_target_temperature[HOTENDS + 1] = { 0.0 }; + #if HEATER_IDLE_HANDLER + // Convert the given heater_id_t to an idle array index + const IdleIndex idle_index = idle_index_for_id(heater_id); + #endif /** SERIAL_ECHO_START(); SERIAL_ECHOPGM("Thermal Runaway Running. Heater ID: "); - if (heater_id == H_CHAMBER) SERIAL_ECHOPGM("chamber"); - if (heater_id < 0) SERIAL_ECHOPGM("bed"); else SERIAL_ECHO(heater_id); - SERIAL_ECHOPAIR(" ; State:", sm.state, " ; Timer:", sm.timer, " ; Temperature:", current, " ; Target Temp:", target); - if (heater_id >= 0) - SERIAL_ECHOPAIR(" ; Idle Timeout:", hotend_idle[heater_id].timed_out); - else - SERIAL_ECHOPAIR(" ; Idle Timeout:", bed_idle.timed_out); - SERIAL_EOL(); + switch (heater_id) { + case H_BED: SERIAL_ECHOPGM("bed"); break; + case H_CHAMBER: SERIAL_ECHOPGM("chamber"); break; + default: SERIAL_ECHO(heater_id); + } + SERIAL_ECHOLNPAIR( + " ; sizeof(running_temp):", sizeof(running_temp), + " ; State:", state, " ; Timer:", timer, " ; Temperature:", current, " ; Target Temp:", target + #if HEATER_IDLE_HANDLER + , " ; Idle Timeout:", heater_idle[idle_index].timed_out + #endif + ); //*/ - const int heater_index = heater_id >= 0 ? heater_id : HOTENDS; - #if HEATER_IDLE_HANDLER // If the heater idle timeout expires, restart - if ((heater_id >= 0 && hotend_idle[heater_id].timed_out) - || TERN0(HAS_HEATED_BED, (heater_id < 0 && bed_idle.timed_out)) - ) { - sm.state = TRInactive; - tr_target_temperature[heater_index] = 0; + if (heater_idle[idle_index].timed_out) { + state = TRInactive; + running_temp = 0; } else #endif { // If the target temperature changes, restart - if (tr_target_temperature[heater_index] != target) { - tr_target_temperature[heater_index] = target; - sm.state = target > 0 ? TRFirstHeating : TRInactive; + if (running_temp != target) { + running_temp = target; + state = target > 0 ? TRFirstHeating : TRInactive; } } - switch (sm.state) { + switch (state) { // Inactive state waits for a target temperature to be set case TRInactive: break; // When first heating, wait for the temperature to be reached then go to Stable state case TRFirstHeating: - if (current < tr_target_temperature[heater_index]) break; - sm.state = TRStable; + if (current < running_temp) break; + state = TRStable; // While the temperature is stable watch for a bad temperature case TRStable: @@ -1999,28 +2010,28 @@ void Temperature::init() { #if ENABLED(ADAPTIVE_FAN_SLOWING) if (adaptive_fan_slowing && heater_id >= 0) { const int fan_index = _MIN(heater_id, FAN_COUNT - 1); - if (fan_speed[fan_index] == 0 || current >= tr_target_temperature[heater_id] - (hysteresis_degc * 0.25f)) + if (fan_speed[fan_index] == 0 || current >= running_temp - (hysteresis_degc * 0.25f)) fan_speed_scaler[fan_index] = 128; - else if (current >= tr_target_temperature[heater_id] - (hysteresis_degc * 0.3335f)) + else if (current >= running_temp - (hysteresis_degc * 0.3335f)) fan_speed_scaler[fan_index] = 96; - else if (current >= tr_target_temperature[heater_id] - (hysteresis_degc * 0.5f)) + else if (current >= running_temp - (hysteresis_degc * 0.5f)) fan_speed_scaler[fan_index] = 64; - else if (current >= tr_target_temperature[heater_id] - (hysteresis_degc * 0.8f)) + else if (current >= running_temp - (hysteresis_degc * 0.8f)) fan_speed_scaler[fan_index] = 32; else fan_speed_scaler[fan_index] = 0; } #endif - if (current >= tr_target_temperature[heater_index] - hysteresis_degc) { - sm.timer = millis() + SEC_TO_MS(period_seconds); + if (current >= running_temp - hysteresis_degc) { + timer = millis() + SEC_TO_MS(period_seconds); break; } - else if (PENDING(millis(), sm.timer)) break; - sm.state = TRRunaway; + else if (PENDING(millis(), timer)) break; + state = TRRunaway; case TRRunaway: - TERN_(DWIN_CREALITY_LCD, Popup_Window_Temperature(0)); + TERN_(DWIN_CREALITY_LCD, DWIN_Popup_Temperature(0)); _temp_error(heater_id, str_t_thermal_runaway, GET_TEXT(MSG_THERMAL_RUNAWAY)); } } @@ -2088,8 +2099,8 @@ void Temperature::disable_all_heaters() { if (p != paused) { paused = p; if (p) { - HOTEND_LOOP() hotend_idle[e].expire(); // Timeout immediately - TERN_(HAS_HEATED_BED, bed_idle.expire()); // Timeout immediately + HOTEND_LOOP() heater_idle[e].expire(); // Timeout immediately + TERN_(HAS_HEATED_BED, heater_idle[IDLE_INDEX_BED].expire()); // Timeout immediately } else { HOTEND_LOOP() reset_hotend_idle_timer(e); @@ -2313,12 +2324,12 @@ void Temperature::readings_ready() { const bool heater_on = (temp_hotend[e].target > 0 || TERN0(PIDTEMP, temp_hotend[e].soft_pwm_amount) > 0 ); - if (rawtemp > temp_range[e].raw_max * tdir) max_temp_error((heater_ind_t)e); + if (rawtemp > temp_range[e].raw_max * tdir) max_temp_error((heater_id_t)e); if (heater_on && rawtemp < temp_range[e].raw_min * tdir && !is_preheating(e)) { #ifdef MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED if (++consecutive_low_temperature_error[e] >= MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED) #endif - min_temp_error((heater_ind_t)e); + min_temp_error((heater_id_t)e); } #ifdef MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED else @@ -2335,9 +2346,7 @@ void Temperature::readings_ready() { #else #define BEDCMP(A,B) ((A)>(B)) #endif - const bool bed_on = temp_bed.target > 0 - || TERN0(PIDTEMPBED, temp_bed.soft_pwm_amount) > 0 - ; + const bool bed_on = (temp_bed.target > 0) || TERN0(PIDTEMPBED, temp_bed.soft_pwm_amount > 0); if (BEDCMP(temp_bed.raw, maxtemp_raw_BED)) max_temp_error(H_BED); if (bed_on && BEDCMP(mintemp_raw_BED, temp_bed.raw)) min_temp_error(H_BED); #endif @@ -2439,14 +2448,8 @@ void Temperature::tick() { #if DISABLED(SLOW_PWM_HEATERS) - #if HAS_HOTEND || HAS_HEATED_BED || HAS_HEATED_CHAMBER - constexpr uint8_t pwm_mask = - #if ENABLED(SOFT_PWM_DITHER) - _BV(SOFT_PWM_SCALE) - 1 - #else - 0 - #endif - ; + #if ANY(HAS_HOTEND, HAS_HEATED_BED, HAS_HEATED_CHAMBER, FAN_SOFT_PWM) + constexpr uint8_t pwm_mask = TERN0(SOFT_PWM_DITHER, _BV(SOFT_PWM_SCALE) - 1); #define _PWM_MOD(N,S,T) do{ \ const bool on = S.add(pwm_mask, T.soft_pwm_amount); \ WRITE_HEATER_##N(on); \ @@ -2885,7 +2888,7 @@ void Temperature::tick() { #if ENABLED(SHOW_TEMP_ADC_VALUES) , const float r #endif - , const heater_ind_t e=INDEX_NONE + , const heater_id_t e=INDEX_NONE ) { char k; switch (e) { @@ -2976,10 +2979,10 @@ void Temperature::tick() { #if ENABLED(SHOW_TEMP_ADC_VALUES) , rawHotendTemp(e) #endif - , (heater_ind_t)e + , (heater_id_t)e ); #endif - SERIAL_ECHOPAIR(" @:", getHeaterPower((heater_ind_t)target_extruder)); + SERIAL_ECHOPAIR(" @:", getHeaterPower((heater_id_t)target_extruder)); #if HAS_HEATED_BED SERIAL_ECHOPAIR(" B@:", getHeaterPower(H_BED)); #endif @@ -2990,7 +2993,7 @@ void Temperature::tick() { HOTEND_LOOP() { SERIAL_ECHOPAIR(" @", e); SERIAL_CHAR(':'); - SERIAL_ECHO(getHeaterPower((heater_ind_t)e)); + SERIAL_ECHO(getHeaterPower((heater_id_t)e)); } #endif } @@ -3063,10 +3066,10 @@ void Temperature::tick() { printerEventLEDs.onHotendHeatingStart(); #endif - float target_temp = -1.0, old_temp = 9999.0; bool wants_to_cool = false; - wait_for_heatup = true; + float target_temp = -1.0, old_temp = 9999.0; millis_t now, next_temp_ms = 0, next_cool_check_ms = 0; + wait_for_heatup = true; do { // Target temperature might be changed during the loop if (target_temp != degTargetHotend(target_extruder)) { @@ -3140,6 +3143,7 @@ void Temperature::tick() { } while (wait_for_heatup && TEMP_CONDITIONS); if (wait_for_heatup) { + wait_for_heatup = false; #if ENABLED(DWIN_CREALITY_LCD) HMI_flag.heat_flag = 0; duration_t elapsed = print_job_timer.duration(); // print timer @@ -3148,9 +3152,10 @@ void Temperature::tick() { ui.reset_status(); #endif TERN_(PRINTER_EVENT_LEDS, printerEventLEDs.onHeatingDone()); + return true; } - return wait_for_heatup; + return false; } #endif // HAS_TEMP_HOTEND @@ -3179,11 +3184,6 @@ void Temperature::tick() { #define TEMP_BED_CONDITIONS (wants_to_cool ? isCoolingBed() : isHeatingBed()) #endif - float target_temp = -1, old_temp = 9999; - bool wants_to_cool = false; - wait_for_heatup = true; - millis_t now, next_temp_ms = 0, next_cool_check_ms = 0; - #if DISABLED(BUSY_WHILE_HEATING) && ENABLED(HOST_KEEPALIVE_FEATURE) KEEPALIVE_STATE(NOT_BUSY); #endif @@ -3193,6 +3193,10 @@ void Temperature::tick() { printerEventLEDs.onBedHeatingStart(); #endif + bool wants_to_cool = false; + float target_temp = -1, old_temp = 9999; + millis_t now, next_temp_ms = 0, next_cool_check_ms = 0; + wait_for_heatup = true; do { // Target temperature might be changed during the loop if (target_temp != degTargetBed()) { @@ -3267,9 +3271,13 @@ void Temperature::tick() { } while (wait_for_heatup && TEMP_BED_CONDITIONS); - if (wait_for_heatup) ui.reset_status(); + if (wait_for_heatup) { + wait_for_heatup = false; + ui.reset_status(); + return true; + } - return wait_for_heatup; + return false; } void Temperature::wait_for_bed_heating() { @@ -3283,6 +3291,77 @@ void Temperature::tick() { #endif // HAS_HEATED_BED + #if HAS_TEMP_PROBE + + #ifndef MIN_DELTA_SLOPE_DEG_PROBE + #define MIN_DELTA_SLOPE_DEG_PROBE 1.0 + #endif + #ifndef MIN_DELTA_SLOPE_TIME_PROBE + #define MIN_DELTA_SLOPE_TIME_PROBE 600 + #endif + + bool Temperature::wait_for_probe(const float target_temp, bool no_wait_for_cooling/*=true*/) { + + const bool wants_to_cool = isProbeAboveTemp(target_temp); + const bool will_wait = !(wants_to_cool && no_wait_for_cooling); + if (will_wait) + SERIAL_ECHOLNPAIR("Waiting for probe to ", (wants_to_cool ? PSTR("cool down") : PSTR("heat up")), " to ", target_temp, " degrees."); + + #if DISABLED(BUSY_WHILE_HEATING) && ENABLED(HOST_KEEPALIVE_FEATURE) + KEEPALIVE_STATE(NOT_BUSY); + #endif + + float old_temp = 9999; + millis_t next_temp_ms = 0, next_delta_check_ms = 0; + wait_for_heatup = true; + while (will_wait && wait_for_heatup) { + + // Print Temp Reading every 10 seconds while heating up. + millis_t now = millis(); + if (!next_temp_ms || ELAPSED(now, next_temp_ms)) { + next_temp_ms = now + 10000UL; + print_heater_states(active_extruder); + SERIAL_EOL(); + } + + idle(); + gcode.reset_stepper_timeout(); // Keep steppers powered + + // Break after MIN_DELTA_SLOPE_TIME_PROBE seconds if the temperature + // did not drop at least MIN_DELTA_SLOPE_DEG_PROBE. This avoids waiting + // forever as the probe is not actively heated. + if (!next_delta_check_ms || ELAPSED(now, next_delta_check_ms)) { + const float temp = degProbe(), + delta_temp = old_temp > temp ? old_temp - temp : temp - old_temp; + if (delta_temp < float(MIN_DELTA_SLOPE_DEG_PROBE)) { + SERIAL_ECHOLNPGM("Timed out waiting for probe temperature."); + break; + } + next_delta_check_ms = now + 1000UL * MIN_DELTA_SLOPE_TIME_PROBE; + old_temp = temp; + } + + // Loop until the temperature is very close target + if (!(wants_to_cool ? isProbeAboveTemp(target_temp) : isProbeBelowTemp(target_temp))) { + SERIAL_ECHOLN(wants_to_cool ? PSTR("Cooldown") : PSTR("Heatup")); + SERIAL_ECHOLNPGM(" complete, target probe temperature reached."); + break; + } + } + + if (wait_for_heatup) { + wait_for_heatup = false; + ui.reset_status(); + return true; + } + else if (will_wait) + SERIAL_ECHOLNPGM("Canceled wait for probe temperature."); + + return false; + } + + #endif // HAS_TEMP_PROBE + #if HAS_HEATED_CHAMBER #ifndef MIN_COOLING_SLOPE_DEG_CHAMBER @@ -3303,15 +3382,14 @@ void Temperature::tick() { #define TEMP_CHAMBER_CONDITIONS (wants_to_cool ? isCoolingChamber() : isHeatingChamber()) #endif - float target_temp = -1, old_temp = 9999; - bool wants_to_cool = false; - wait_for_heatup = true; - millis_t now, next_temp_ms = 0, next_cool_check_ms = 0; - #if DISABLED(BUSY_WHILE_HEATING) && ENABLED(HOST_KEEPALIVE_FEATURE) KEEPALIVE_STATE(NOT_BUSY); #endif + bool wants_to_cool = false; + float target_temp = -1, old_temp = 9999; + millis_t now, next_temp_ms = 0, next_cool_check_ms = 0; + wait_for_heatup = true; do { // Target temperature might be changed during the loop if (target_temp != degTargetChamber()) { @@ -3370,9 +3448,13 @@ void Temperature::tick() { } } while (wait_for_heatup && TEMP_CHAMBER_CONDITIONS); - if (wait_for_heatup) ui.reset_status(); + if (wait_for_heatup) { + wait_for_heatup = false; + ui.reset_status(); + return true; + } - return wait_for_heatup; + return false; } #endif // HAS_HEATED_CHAMBER diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index 94eb42fd0f..57b0fecbcc 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -40,12 +40,12 @@ #define HOTEND_INDEX TERN(HAS_MULTI_HOTEND, e, 0) #define E_NAME TERN_(HAS_MULTI_HOTEND, e) -// Identifiers for other heaters +// Heater identifiers. Positive values are hotends. Negative values are other heaters. typedef enum : int8_t { INDEX_NONE = -5, H_PROBE, H_REDUNDANT, H_CHAMBER, H_BED, H_E0, H_E1, H_E2, H_E3, H_E4, H_E5, H_E6, H_E7 -} heater_ind_t; +} heater_id_t; // PID storage typedef struct { float Kp, Ki, Kd; } PID_t; @@ -211,16 +211,6 @@ struct PIDHeaterInfo : public HeaterInfo { typedef temp_info_t chamber_info_t; #endif -// Heater idle handling -typedef struct { - millis_t timeout_ms; - bool timed_out; - inline void update(const millis_t &ms) { if (!timed_out && timeout_ms && ELAPSED(ms, timeout_ms)) timed_out = true; } - inline void start(const millis_t &ms) { timeout_ms = millis() + ms; timed_out = false; } - inline void reset() { timeout_ms = 0; timed_out = false; } - inline void expire() { start(0); } -} hotend_idle_t; - // Heater watch handling template struct HeaterWatch { @@ -330,7 +320,7 @@ class Temperature { #if ENABLED(PREVENT_COLD_EXTRUSION) static bool allow_cold_extrude; static int16_t extrude_min_temp; - FORCE_INLINE static bool tooCold(const int16_t temp) { return allow_cold_extrude ? false : temp < extrude_min_temp; } + FORCE_INLINE static bool tooCold(const int16_t temp) { return allow_cold_extrude ? false : temp < extrude_min_temp - (TEMP_WINDOW); } FORCE_INLINE static bool tooColdToExtrude(const uint8_t E_NAME) { return tooCold(degHotend(HOTEND_INDEX)); } @@ -346,9 +336,38 @@ class Temperature { FORCE_INLINE static bool targetHotEnoughToExtrude(const uint8_t e) { return !targetTooColdToExtrude(e); } #if HEATER_IDLE_HANDLER - static hotend_idle_t hotend_idle[HOTENDS]; - TERN_(HAS_HEATED_BED, static hotend_idle_t bed_idle); - TERN_(HAS_HEATED_CHAMBER, static hotend_idle_t chamber_idle); + + // Heater idle handling. Marlin creates one per hotend and one for the heated bed. + typedef struct { + millis_t timeout_ms; + bool timed_out; + inline void update(const millis_t &ms) { if (!timed_out && timeout_ms && ELAPSED(ms, timeout_ms)) timed_out = true; } + inline void start(const millis_t &ms) { timeout_ms = millis() + ms; timed_out = false; } + inline void reset() { timeout_ms = 0; timed_out = false; } + inline void expire() { start(0); } + } heater_idle_t; + + // Indices and size for the heater_idle array + #define _ENUM_FOR_E(N) IDLE_INDEX_E##N, + enum IdleIndex : uint8_t { + REPEAT(HOTENDS, _ENUM_FOR_E) + #if ENABLED(HAS_HEATED_BED) + IDLE_INDEX_BED, + #endif + NR_HEATER_IDLE + }; + #undef _ENUM_FOR_E + + // Convert the given heater_id_t to idle array index + static inline IdleIndex idle_index_for_id(const int8_t heater_id) { + #if HAS_HEATED_BED + if (heater_id == H_BED) return IDLE_INDEX_BED; + #endif + return (IdleIndex)_MAX(heater_id, 0); + } + + static heater_idle_t heater_idle[NR_HEATER_IDLE]; + #endif private: @@ -654,6 +673,9 @@ class Temperature { FORCE_INLINE static int16_t rawProbeTemp() { return temp_probe.raw; } #endif FORCE_INLINE static float degProbe() { return temp_probe.celsius; } + FORCE_INLINE static bool isProbeBelowTemp(const float target_temp) { return temp_probe.celsius < target_temp; } + FORCE_INLINE static bool isProbeAboveTemp(const float target_temp) { return temp_probe.celsius > target_temp; } + static bool wait_for_probe(const float target_temp, bool no_wait_for_cooling=true); #endif #if WATCH_PROBE @@ -698,7 +720,7 @@ class Temperature { /** * The software PWM power for a heater */ - static int16_t getHeaterPower(const heater_ind_t heater); + static int16_t getHeaterPower(const heater_id_t heater_id); /** * Switch off all heaters, set all target temperatures to 0 @@ -717,7 +739,7 @@ class Temperature { * Perform auto-tuning for hotend or bed in response to M303 */ #if HAS_PID_HEATING - static void PID_autotune(const float &target, const heater_ind_t hotend, const int8_t ncycles, const bool set_result=false); + static void PID_autotune(const float &target, const heater_id_t heater_id, const int8_t ncycles, const bool set_result=false); #if ENABLED(NO_FAN_SLOWING_IN_PID_TUNING) static bool adaptive_fan_slowing; @@ -744,13 +766,13 @@ class Temperature { #if HEATER_IDLE_HANDLER static void reset_hotend_idle_timer(const uint8_t E_NAME) { - hotend_idle[HOTEND_INDEX].reset(); + heater_idle[HOTEND_INDEX].reset(); start_watching_hotend(HOTEND_INDEX); } #if HAS_HEATED_BED static void reset_bed_idle_timer() { - bed_idle.reset(); + heater_idle[IDLE_INDEX_BED].reset(); start_watching_bed(); } #endif @@ -808,26 +830,51 @@ class Temperature { TERN_(HAS_HEATED_CHAMBER, static float get_pid_output_chamber()); - static void _temp_error(const heater_ind_t e, PGM_P const serial_msg, PGM_P const lcd_msg); - static void min_temp_error(const heater_ind_t e); - static void max_temp_error(const heater_ind_t e); + static void _temp_error(const heater_id_t e, PGM_P const serial_msg, PGM_P const lcd_msg); + static void min_temp_error(const heater_id_t e); + static void max_temp_error(const heater_id_t e); - #define HAS_THERMAL_PROTECTION (EITHER(THERMAL_PROTECTION_HOTENDS, THERMAL_PROTECTION_CHAMBER) || HAS_THERMALLY_PROTECTED_BED) + #define HAS_THERMAL_PROTECTION ANY(THERMAL_PROTECTION_HOTENDS, THERMAL_PROTECTION_CHAMBER, HAS_THERMALLY_PROTECTED_BED) #if HAS_THERMAL_PROTECTION + // Indices and size for the tr_state_machine array. One for each protected heater. + #define _ENUM_FOR_E(N) RUNAWAY_IND_E##N, + enum RunawayIndex : uint8_t { + #if ENABLED(THERMAL_PROTECTION_HOTENDS) + REPEAT(HOTENDS, _ENUM_FOR_E) + #endif + #if ENABLED(HAS_THERMALLY_PROTECTED_BED) + RUNAWAY_IND_BED, + #endif + #if ENABLED(THERMAL_PROTECTION_CHAMBER) + RUNAWAY_IND_CHAMBER, + #endif + NR_HEATER_RUNAWAY + }; + #undef _ENUM_FOR_E + + // Convert the given heater_id_t to runaway state array index + static inline RunawayIndex runaway_index_for_id(const int8_t heater_id) { + #if HAS_THERMALLY_PROTECTED_CHAMBER + if (heater_id == H_CHAMBER) return RUNAWAY_IND_CHAMBER; + #endif + #if HAS_THERMALLY_PROTECTED_BED + if (heater_id == H_BED) return RUNAWAY_IND_BED; + #endif + return (RunawayIndex)_MAX(heater_id, 0); + } + enum TRState : char { TRInactive, TRFirstHeating, TRStable, TRRunaway }; typedef struct { millis_t timer = 0; TRState state = TRInactive; + float running_temp; + void run(const float ¤t, const float &target, const heater_id_t heater_id, const uint16_t period_seconds, const uint16_t hysteresis_degc); } tr_state_machine_t; - TERN_(THERMAL_PROTECTION_HOTENDS, static tr_state_machine_t tr_state_machine[HOTENDS]); - TERN_(HAS_THERMALLY_PROTECTED_BED, static tr_state_machine_t tr_state_machine_bed); - TERN_(THERMAL_PROTECTION_CHAMBER, static tr_state_machine_t tr_state_machine_chamber); - - static void thermal_runaway_protection(tr_state_machine_t &state, const float ¤t, const float &target, const heater_ind_t heater_id, const uint16_t period_seconds, const uint16_t hysteresis_degc); + static tr_state_machine_t tr_state_machine[NR_HEATER_RUNAWAY]; #endif // HAS_THERMAL_PROTECTION }; diff --git a/Marlin/src/module/thermistor/thermistor_30.h b/Marlin/src/module/thermistor/thermistor_30.h new file mode 100644 index 0000000000..bc1781b135 --- /dev/null +++ b/Marlin/src/module/thermistor/thermistor_30.h @@ -0,0 +1,66 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +// R25 = 100 kOhm, beta25 = 3950 K, 4.7 kOhm pull-up +// Resistance 100k Ohms at 25deg. C +// Resistance Tolerance + / -1% +// B Value 3950K at 25/50 deg. C +// B Value Tolerance + / - 1% +// Kis3d Silicone Heater 24V 200W/300W with 6mm Precision cast plate (EN AW 5083) +// Temperature setting time 10 min to determine the 12Bit ADC value on the surface. (le3tspeak) +const temp_entry_t temptable_30[] PROGMEM = { + { OV( 1), 938 }, + { OV( 298), 125 }, // 1193 - 125° + { OV( 321), 121 }, // 1285 - 121° + { OV( 348), 117 }, // 1392 - 117° + { OV( 387), 113 }, // 1550 - 113° + { OV( 411), 110 }, // 1644 - 110° + { OV( 445), 106 }, // 1780 - 106° + { OV( 480), 101 }, // 1920 - 101° + { OV( 516), 97 }, // 2064 - 97° + { OV( 553), 92 }, // 2212 - 92° + { OV( 591), 88 }, // 2364 - 88° + { OV( 628), 84 }, // 2512 - 84° + { OV( 665), 79 }, // 2660 - 79° + { OV( 702), 75 }, // 2808 - 75° + { OV( 736), 71 }, // 2945 - 71° + { OV( 770), 67 }, // 3080 - 67° + { OV( 801), 63 }, // 3204 - 63° + { OV( 830), 59 }, // 3320 - 59° + { OV( 857), 55 }, // 3428 - 55° + { OV( 881), 51 }, // 3524 - 51° + { OV( 902), 47 }, // 3611 - 47° + { OV( 922), 42 }, // 3688 - 42° + { OV( 938), 38 }, // 3754 - 38° + { OV( 952), 34 }, // 3811 - 34° + { OV( 964), 29 }, // 3857 - 29° + { OV( 975), 25 }, // 3900 - 25° + { OV( 980), 23 }, // 3920 - 23° + { OV( 991), 17 }, // 3964 - 17° + { OV(1001), 9 }, // Calculated + { OV(1004), 5 }, // Calculated + { OV(1008), 0 }, // Calculated + { OV(1012), -5 }, // Calculated + { OV(1016), -10 }, // Calculated + { OV(1020), -15 } // Calculated +}; diff --git a/Marlin/src/module/thermistor/thermistors.h b/Marlin/src/module/thermistor/thermistors.h index 56921c6d18..0b0419c520 100644 --- a/Marlin/src/module/thermistor/thermistors.h +++ b/Marlin/src/module/thermistor/thermistors.h @@ -120,6 +120,9 @@ typedef struct { int16_t value, celsius; } temp_entry_t; #if ANY_THERMISTOR_IS(23) // By AluOne #12622. Formerly 22 above. May need calibration/checking. #include "thermistor_23.h" #endif +#if ANY_THERMISTOR_IS(30) // Kis3d Silicone mat 24V 200W/300W with 6mm Precision cast plate (EN AW 5083) + #include "thermistor_30.h" +#endif #if ANY_THERMISTOR_IS(51) // beta25 = 4092 K, R25 = 100 kOhm, Pull-up = 1 kOhm, "EPCOS" #include "thermistor_51.h" #endif diff --git a/Marlin/src/module/tool_change.cpp b/Marlin/src/module/tool_change.cpp index 8557560266..0f823cfbd0 100644 --- a/Marlin/src/module/tool_change.cpp +++ b/Marlin/src/module/tool_change.cpp @@ -36,7 +36,7 @@ #define DEBUG_OUT ENABLED(DEBUG_TOOL_CHANGE) #include "../core/debug_out.h" -#if EXTRUDERS > 1 +#if HAS_MULTI_EXTRUDER toolchange_settings_t toolchange_settings; // Initialized by settings.load() #endif @@ -870,7 +870,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { if (new_tool) invalid_extruder_error(new_tool); return; - #else // EXTRUDERS > 1 + #elif HAS_MULTI_EXTRUDER planner.synchronize(); @@ -1197,7 +1197,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { SERIAL_ECHO_START(); SERIAL_ECHOLNPAIR(STR_ACTIVE_EXTRUDER, int(active_extruder)); - #endif // EXTRUDERS > 1 + #endif // HAS_MULTI_EXTRUDER } #if ENABLED(TOOLCHANGE_MIGRATION_FEATURE) diff --git a/Marlin/src/module/tool_change.h b/Marlin/src/module/tool_change.h index d0cb57841b..38347191d3 100644 --- a/Marlin/src/module/tool_change.h +++ b/Marlin/src/module/tool_change.h @@ -24,7 +24,7 @@ #include "../inc/MarlinConfigPre.h" #include "../core/types.h" -#if EXTRUDERS > 1 +#if HAS_MULTI_EXTRUDER typedef struct { #if ENABLED(TOOLCHANGE_FILAMENT_SWAP) diff --git a/Marlin/src/pins/esp32/pins_E4D.h b/Marlin/src/pins/esp32/pins_E4D.h index e66bb669f7..7b5595444c 100644 --- a/Marlin/src/pins/esp32/pins_E4D.h +++ b/Marlin/src/pins/esp32/pins_E4D.h @@ -27,7 +27,7 @@ * for more info check https://atbox.tech/ and join to Facebook page E4d@box. */ -#ifndef ARDUINO_ARCH_ESP32 +#if NOT_TARGET(ARDUINO_ARCH_ESP32) #error "Oops! Select an ESP32 board in 'Tools > Board.'" #elif EXTRUDERS > 1 || E_STEPPERS > 1 #error "E4d@box only supports one E Stepper. Comment out this line to continue." diff --git a/Marlin/src/pins/esp32/pins_ESP32.h b/Marlin/src/pins/esp32/pins_ESP32.h index 5f793f1cf2..d54a92b9c4 100644 --- a/Marlin/src/pins/esp32/pins_ESP32.h +++ b/Marlin/src/pins/esp32/pins_ESP32.h @@ -25,7 +25,7 @@ * Espressif ESP32 (Tensilica Xtensa LX6) pin assignments */ -#ifndef ARDUINO_ARCH_ESP32 +#if NOT_TARGET(ARDUINO_ARCH_ESP32) "Oops! Select an ESP32 board in 'Tools > Board.'" #endif diff --git a/Marlin/src/pins/esp32/pins_MRR_ESPA.h b/Marlin/src/pins/esp32/pins_MRR_ESPA.h index 8a5b11ed71..0457b0afca 100644 --- a/Marlin/src/pins/esp32/pins_MRR_ESPA.h +++ b/Marlin/src/pins/esp32/pins_MRR_ESPA.h @@ -27,7 +27,7 @@ * Supports 4 stepper drivers, heated bed, single hotend. */ -#ifndef ARDUINO_ARCH_ESP32 +#if NOT_TARGET(ARDUINO_ARCH_ESP32) #error "Oops! Select an ESP32 board in 'Tools > Board.'" #elif EXTRUDERS > 1 || E_STEPPERS > 1 #error "MRR ESPA only supports one E Stepper. Comment out this line to continue." diff --git a/Marlin/src/pins/esp32/pins_MRR_ESPE.h b/Marlin/src/pins/esp32/pins_MRR_ESPE.h index b38a88351d..95f761f26a 100644 --- a/Marlin/src/pins/esp32/pins_MRR_ESPE.h +++ b/Marlin/src/pins/esp32/pins_MRR_ESPE.h @@ -28,7 +28,7 @@ * single hotend, and LCD controller. */ -#ifndef ARDUINO_ARCH_ESP32 +#if NOT_TARGET(ARDUINO_ARCH_ESP32) #error "Oops! Select an ESP32 board in 'Tools > Board.'" #elif EXTRUDERS > 2 || E_STEPPERS > 2 #error "MRR ESPE only supports two E Steppers. Comment out this line to continue." @@ -124,7 +124,7 @@ // LCDs and Controllers // ////////////////////////// -#if HAS_GRAPHICAL_LCD +#if HAS_MARLINUI_U8GLIB #define LCD_PINS_RS 13 #define LCD_PINS_ENABLE 17 @@ -152,7 +152,7 @@ #define BTN_EN2 12 #define BTN_ENC 14 -#endif // HAS_GRAPHICAL_LCD +#endif // HAS_MARLINUI_U8GLIB // Hardware serial pins // Add the following to Configuration.h or Configuration_adv.h to assign diff --git a/Marlin/src/pins/linux/pins_RAMPS_LINUX.h b/Marlin/src/pins/linux/pins_RAMPS_LINUX.h index 2b7909221e..002d2ebd9c 100644 --- a/Marlin/src/pins/linux/pins_RAMPS_LINUX.h +++ b/Marlin/src/pins/linux/pins_RAMPS_LINUX.h @@ -389,7 +389,7 @@ // LCDs and Controllers // ////////////////////////// -#if HAS_SPI_LCD +#if HAS_WIRED_LCD // // LCD Display output pins @@ -632,4 +632,4 @@ #endif #endif // NEWPANEL -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h b/Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h index ffc149279c..78e7426674 100644 --- a/Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h +++ b/Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h @@ -25,7 +25,7 @@ * AZSMZ MINI pin assignments */ -#ifndef MCU_LPC1768 +#if NOT_TARGET(MCU_LPC1768) #error "Oops! Make sure you have the LPC1768 environment selected in your IDE." #endif diff --git a/Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h b/Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h index 6ccfca1cac..df182049f9 100644 --- a/Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h +++ b/Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h @@ -27,10 +27,9 @@ * Applies to the following boards: * * BOARD_BIQU_BQ111_A4 (Hotend, Fan, Bed) - * */ -#ifndef MCU_LPC1768 +#if NOT_TARGET(MCU_LPC1768) #error "Oops! Make sure you have the LPC1768 environment selected in your IDE." #endif @@ -126,7 +125,7 @@ * for the onboard SD card, and a chip select signal is not provided for the remote * SD card. */ -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #define BEEPER_PIN P1_31 // EXP1-1 @@ -139,7 +138,7 @@ #define LCD_PINS_ENABLE P0_18 // (MOSI) EXP1-3 #define LCD_PINS_D4 P0_15 // (SCK) EXP1-5 - #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) && HAS_CHARACTER_LCD + #if BOTH(HAS_MARLINUI_HD44780, REPRAP_DISCOUNT_SMART_CONTROLLER) #error "REPRAP_DISCOUNT_SMART_CONTROLLER is not supported by the BIQU B300 v1.0" #endif @@ -147,7 +146,7 @@ #error "SDSUPPORT is not supported by the BIQU B300 v1.0 when an LCD controller is used" #endif -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD /** * SD Card Reader diff --git a/Marlin/src/pins/lpc1768/pins_BIQU_BQ111_A4.h b/Marlin/src/pins/lpc1768/pins_BIQU_BQ111_A4.h index 20edcb07a7..bcff04eb85 100644 --- a/Marlin/src/pins/lpc1768/pins_BIQU_BQ111_A4.h +++ b/Marlin/src/pins/lpc1768/pins_BIQU_BQ111_A4.h @@ -27,10 +27,9 @@ * Applies to the following boards: * * BOARD_BIQU_BQ111_A4 (Hotend, Fan, Bed) - * */ -#ifndef MCU_LPC1768 +#if NOT_TARGET(MCU_LPC1768) #error "Oops! Make sure you have the LPC1768 environment selected in your IDE." #endif @@ -97,7 +96,7 @@ * for the onboard SD card, and a chip select signal is not provided for the remote * SD card. */ -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #define BEEPER_PIN P1_31 // EXP1-1 @@ -110,7 +109,7 @@ #define LCD_PINS_ENABLE P0_18 // (MOSI) EXP1-3 #define LCD_PINS_D4 P0_15 // (SCK) EXP1-5 - #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) && HAS_CHARACTER_LCD + #if BOTH(HAS_MARLINUI_HD44780, REPRAP_DISCOUNT_SMART_CONTROLLER) #error "REPRAP_DISCOUNT_SMART_CONTROLLER is not supported by the BIQU BQ111-A4" #endif @@ -118,7 +117,7 @@ #error "SDSUPPORT is not supported by the BIQU BQ111-A4 when an LCD controller is used" #endif -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD /** * SD Card Reader diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h index d5e2560662..0701e45992 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h @@ -65,7 +65,16 @@ * by redrawing the screen after SD card accesses. */ -#if HAS_SPI_LCD +#if IS_TFTGLCD_PANEL + + #if ENABLED(TFTGLCD_PANEL_SPI) + #define TFTGLCD_CS P3_26 + #endif + + #define SD_DETECT_PIN P1_31 + +#elif HAS_WIRED_LCD + #define BTN_EN1 P3_26 #define BTN_EN2 P3_25 #define BTN_ENC P2_11 @@ -80,7 +89,8 @@ #define DOGLCD_CS P2_06 #define DOGLCD_A0 P0_16 #endif -#endif + +#endif // HAS_WIRED_LCD // // SD Support @@ -89,7 +99,7 @@ // requires jumpers on the SKR V1.1 board as documented here: // https://www.facebook.com/groups/505736576548648/permalink/630639874058317/ #ifndef SDCARD_CONNECTION - #if EITHER(MKS_MINI_12864, ENDER2_STOCKDISPLAY) + #if ANY(MKS_MINI_12864, ENDER2_STOCKDISPLAY, IS_TFTGLCD_PANEL) #define SDCARD_CONNECTION LCD #else #define SDCARD_CONNECTION ONBOARD 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 fb1218068e..31373fedff 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h @@ -151,7 +151,7 @@ * Hardware serial communication ports. * If undefined software serial is used according to the pins below */ - //#define X_HARDWARE_SERIAL Serial + //#define X_HARDWARE_SERIAL Serial1 //#define X2_HARDWARE_SERIAL Serial1 //#define Y_HARDWARE_SERIAL Serial1 //#define Y2_HARDWARE_SERIAL Serial1 @@ -214,7 +214,7 @@ #define EXPA2_09_PIN P0_15 #define EXPA2_10_PIN P0_17 -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #if ENABLED(ANET_FULL_GRAPHICS_LCD) @@ -265,6 +265,14 @@ #error "ADC BUTTONS do not work unmodifed on SKR 1.3, The ADC ports cannot take more than 3.3v." + #elif IS_TFTGLCD_PANEL + + #if ENABLED(TFTGLCD_PANEL_SPI) + #define TFTGLCD_CS EXPA2_08_PIN + #endif + + #define SD_DETECT_PIN EXPA2_04_PIN + #else // !CR10_STOCKDISPLAY #define LCD_PINS_RS EXPA1_07_PIN @@ -350,7 +358,7 @@ #endif // !CR10_STOCKDISPLAY -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD // // SD Support diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h index b32f99c68d..6f9f4bcf63 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h @@ -25,6 +25,10 @@ #define BOARD_INFO_NAME "BTT SKR V1.4" #endif +#ifndef BOARD_CUSTOM_BUILD_FLAGS + #define BOARD_CUSTOM_BUILD_FLAGS -DLPC_PINCFG_UART3_P4_28 +#endif + // // SD Connection // @@ -149,8 +153,8 @@ #define E1_CS_PIN P1_01 #endif -#define TEMP_1_PIN P0_23_A0 // A2 (T2) - (69) - TEMP_1_PIN -#define TEMP_BED_PIN P0_25_A2 // A0 (T0) - (67) - TEMP_BED_PIN +#define TEMP_1_PIN P0_23_A0 // A0 (T0) - (67) - TEMP_1_PIN +#define TEMP_BED_PIN P0_25_A2 // A2 (T2) - (69) - TEMP_BED_PIN // // Software SPI pins for TMC2130 stepper drivers @@ -174,7 +178,7 @@ * Hardware serial communication ports. * If undefined software serial is used according to the pins below */ - //#define X_HARDWARE_SERIAL Serial + //#define X_HARDWARE_SERIAL Serial1 //#define X2_HARDWARE_SERIAL Serial1 //#define Y_HARDWARE_SERIAL Serial1 //#define Y2_HARDWARE_SERIAL Serial1 @@ -228,7 +232,7 @@ * ----- ----- * EXP2 EXP1 */ -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #if ENABLED(ANET_FULL_GRAPHICS_LCD) #define LCD_PINS_RS P1_23 @@ -275,9 +279,6 @@ #define LCD_BACKLIGHT_PIN -1 #elif HAS_SPI_TFT // Config for Classic UI (emulated DOGM) and Color UI - #define SS_PIN -1 - //#define ONBOARD_SD_CS_PIN -1 - #define TFT_CS_PIN P1_22 #define TFT_A0_PIN P1_23 #define TFT_DC_PIN P1_23 @@ -285,7 +286,6 @@ #define TFT_BACKLIGHT_PIN P1_18 #define TFT_RESET_PIN P1_19 - #define LPC_HW_SPI_DEV 0 #define LCD_USE_DMA_SPI #define TOUCH_INT_PIN P1_21 @@ -297,15 +297,26 @@ #define GRAPHICAL_TFT_UPSCALE 3 #endif - // SPI 1 - #define SCK_PIN P0_15 - #define MISO_PIN P0_17 - #define MOSI_PIN P0_18 - // Disable any LCD related PINs config #define LCD_PINS_ENABLE -1 #define LCD_PINS_RS -1 + // Emulated DOGM have xpt calibration values independent of display resolution + #if ENABLED(SPI_GRAPHICAL_TFT) + #define XPT2046_X_CALIBRATION -11245 + #define XPT2046_Y_CALIBRATION 8629 + #define XPT2046_X_OFFSET 685 + #define XPT2046_Y_OFFSET -285 + #endif + + #elif IS_TFTGLCD_PANEL + + #if ENABLED(TFTGLCD_PANEL_SPI) + #define TFTGLCD_CS P3_26 + #endif + + #define SD_DETECT_PIN P1_31 + #else #define BTN_ENC P0_28 // (58) open-drain @@ -368,9 +379,9 @@ #endif // !FYSETC_MINI_12864 - #endif // HAS_GRAPHICAL_LCD + #endif // HAS_MARLINUI_U8GLIB -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD #if HAS_ADC_BUTTONS #error "ADC BUTTONS do not work unmodifed on SKR 1.4, The ADC ports cannot take more than 3.3v." diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h index bfae569cc4..fd902afda4 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h @@ -22,10 +22,10 @@ #pragma once #ifdef SKR_HAS_LPC1769 - #ifndef MCU_LPC1769 + #if NOT_TARGET(MCU_LPC1769) #error "Oops! Make sure you have the LPC1769 environment selected in your IDE." #endif -#elif !defined(MCU_LPC1768) +#elif NOT_TARGET(MCU_LPC1768) #error "Oops! Make sure you have the LPC1768 environment selected in your IDE." #endif @@ -92,7 +92,7 @@ // // LCD / Controller // -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #define BEEPER_PIN P1_30 // (37) not 5V tolerant #endif diff --git a/Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h b/Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h index 6bba067cbe..5132081a55 100644 --- a/Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h +++ b/Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h @@ -21,7 +21,7 @@ */ #pragma once -#ifndef MCU_LPC1768 +#if NOT_TARGET(MCU_LPC1768) #error "Oops! Make sure you have the LPC1768 environment selected in your IDE." #endif diff --git a/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h b/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h index c898072278..196503c822 100644 --- a/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h +++ b/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h @@ -25,9 +25,9 @@ * MKS SBASE pin assignments */ -#if defined(MKS_HAS_LPC1769) && !defined(MCU_LPC1769) +#if defined(MKS_HAS_LPC1769) && NOT_TARGET(MCU_LPC1769) #error "Oops! Make sure you have the LPC1769 environment selected in your IDE." -#elif !defined(MKS_HAS_LPC1769) && !defined(MCU_LPC1768) +#elif NOT_TARGET(MKS_HAS_LPC1769, MCU_LPC1768) #error "Oops! Make sure you have the LPC1768 environment selected in your IDE." #endif @@ -217,7 +217,18 @@ * that the garbage/lines are erased immediately after the SD card accesses are completed. */ -#if HAS_SPI_LCD +#if IS_TFTGLCD_PANEL + + #if ENABLED(TFTGLCD_PANEL_SPI) + #define TFTGLCD_CS P3_25 // EXP2.3 + #endif + + #if SD_CONNECTION_IS(LCD) + #define SD_DETECT_PIN P0_28 // EXP2.4 + #endif + +#elif HAS_WIRED_LCD + #define BEEPER_PIN P1_31 // EXP1.1 #define BTN_ENC P1_30 // EXP1.2 #define BTN_EN1 P3_26 // EXP2.5 @@ -273,7 +284,7 @@ //#define LCD_SCREEN_ROT_270 #endif -#endif +#endif // HAS_WIRED_LCD /** * Example for trinamic drivers using the J8 connector on MKs Sbase. @@ -289,20 +300,21 @@ #define E0_CS_PIN P2_11 #define E1_CS_PIN P4_28 -// Hardware SPI is on EXP2. See if you can make it work: -// https://github.com/makerbase-mks/MKS-SBASE/issues/25 -#define TMC_USE_SW_SPI -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI P0_03 // AUX1 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO P0_02 // AUX1 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK P0_26 // TH4 + // Hardware SPI is on EXP2. See if you can make it work: + // https://github.com/makerbase-mks/MKS-SBASE/issues/25 + #define TMC_USE_SW_SPI + #if ENABLED(TMC_USE_SW_SPI) + #ifndef TMC_SW_MOSI + #define TMC_SW_MOSI P0_03 // AUX1 + #endif + #ifndef TMC_SW_MISO + #define TMC_SW_MISO P0_02 // AUX1 + #endif + #ifndef TMC_SW_SCK + #define TMC_SW_SCK P0_26 // TH4 + #endif #endif - #endif + #endif #if MB(MKS_SBASE) && HAS_TMC_UART @@ -360,7 +372,6 @@ * P1_31 - not 5V tolerant - EXP1 * P0_27 - open collector - EXP2 * P0_28 - open collector - EXP2 - * */ /** @@ -375,5 +386,4 @@ * P0_03 - AUX1 * P0_29 - Port -1 * P0_30 - USB - * */ diff --git a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h index 733751eb0a..d269ecbdc9 100644 --- a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h +++ b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h @@ -25,7 +25,7 @@ * MKS SGEN-L pin assignments */ -#ifndef MCU_LPC1768 +#if NOT_TARGET(MCU_LPC1768) #error "Oops! Make sure you have the LPC1768 environment selected in your IDE." #endif @@ -153,7 +153,7 @@ * Hardware serial communication ports. * If undefined software serial is used according to the pins below */ - //#define X_HARDWARE_SERIAL Serial + //#define X_HARDWARE_SERIAL Serial1 //#define X2_HARDWARE_SERIAL Serial1 //#define Y_HARDWARE_SERIAL Serial1 //#define Y2_HARDWARE_SERIAL Serial1 @@ -229,13 +229,14 @@ * _____ _____ * (BEEPER) 1.31 | · · | 1.30 (BTN_ENC) (MISO) 0.8 | · · | 0.7 (SD_SCK) * (LCD_EN) 0.18 | · · | 0.16 (LCD_RS) (BTN_EN1) 3.25 | · · | 0.28 (SD_CS2) - * (LCD_D4) 0.15 | · · | 0.17 (LCD_D5) (BTN_EN2) 3.26 | · · | 1.20 (SD_MOSI) + * (LCD_D4) 0.15 | · · | 0.17 (LCD_D5) (BTN_EN2) 3.26 | · · | 0.9 (SD_MOSI) * (LCD_D6) 1.0 | · · | 1.22 (LCD_D7) (SD_DETECT) 0.27 | · · | RST * GND | · · | 5V GND | · · | NC * ----- ----- * EXP1 EXP2 */ -#if HAS_SPI_LCD +#if HAS_WIRED_LCD + #define BEEPER_PIN P1_31 #define BTN_ENC P1_30 @@ -248,6 +249,15 @@ #define LCD_PINS_ENABLE P1_22 #define LCD_PINS_D4 P0_17 + #elif IS_TFTGLCD_PANEL + + #undef BEEPER_PIN + #undef BTN_ENC + + #if ENABLED(TFTGLCD_PANEL_SPI) + #define TFTGLCD_CS P3_25 + #endif + #else #define BTN_EN1 P3_25 @@ -279,7 +289,7 @@ #define DOGLCD_CS P0_18 #define DOGLCD_A0 P0_16 #define DOGLCD_SCK P0_07 - #define DOGLCD_MOSI P1_20 + #define DOGLCD_MOSI P0_09 #define LCD_BACKLIGHT_PIN -1 @@ -321,7 +331,7 @@ #endif // !CR10_STOCKDISPLAY -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD #ifndef SDCARD_CONNECTION #define SDCARD_CONNECTION ONBOARD diff --git a/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h b/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h index 32c9ad2711..c602af1c30 100644 --- a/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h +++ b/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h @@ -31,12 +31,11 @@ * RAMPS_14_EFF (Hotend, Fan0, Fan1) * RAMPS_14_EEF (Hotend0, Hotend1, Fan) * RAMPS_14_SF (Spindle, Controller Fan) - * */ // Numbers in parentheses () are the corresponding mega2560 pin numbers -#ifndef MCU_LPC1768 +#if NOT_TARGET(MCU_LPC1768) #error "Oops! Make sure you have the LPC1768 environment selected in your IDE." #endif @@ -326,7 +325,16 @@ #define LCD_PINS_ENABLE P0_18 // J3-10 & AUX-3 (SID, MOSI) #define LCD_PINS_D4 P2_06 // J3-8 & AUX-3 (SCK, CLK) -#elif HAS_SPI_LCD +#elif IS_TFTGLCD_PANEL + + #if ENABLED(TFTGLCD_PANEL_SPI) + #define TFTGLCD_CS P3_26 // (31) J3-2 & AUX-4 + #endif + + #define SD_DETECT_PIN P1_31 // (49) J3-1 & AUX-3 (NOT 5V tolerant) + #define KILL_PIN P1_22 // (41) J5-4 & AUX-4 + +#elif HAS_WIRED_LCD //#define SCK_PIN P0_15 // (52) system defined J3-9 & AUX-3 //#define MISO_PIN P0_17 // (50) system defined J3-10 & AUX-3 @@ -370,8 +378,9 @@ #define DOGLCD_SCK SCK_PIN #define DOGLCD_MOSI MOSI_PIN - #define STAT_LED_BLUE_PIN P0_26 //(63) may change if cable changes + #define STAT_LED_BLUE_PIN P0_26 // (63) may change if cable changes #define STAT_LED_RED_PIN P1_21 // ( 6) may change if cable changes + #else #if ENABLED(FYSETC_MINI_12864) @@ -420,9 +429,9 @@ //#define LCD_SCREEN_ROT_90 //#define LCD_SCREEN_ROT_180 //#define LCD_SCREEN_ROT_270 - #endif + #endif -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD // // Ethernet pins diff --git a/Marlin/src/pins/lpc1768/pins_SELENA_COMPACT.h b/Marlin/src/pins/lpc1768/pins_SELENA_COMPACT.h index e717511c12..f9b9db918d 100644 --- a/Marlin/src/pins/lpc1768/pins_SELENA_COMPACT.h +++ b/Marlin/src/pins/lpc1768/pins_SELENA_COMPACT.h @@ -25,7 +25,7 @@ * Selena Compact pin assignments */ -#ifndef MCU_LPC1768 +#if NOT_TARGET(MCU_LPC1768) #error "Oops! Make sure you have the LPC1768 environment selected in your IDE." #endif diff --git a/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_GT.h b/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_GT.h index 83cf17eee9..adf9085262 100644 --- a/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_GT.h +++ b/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_GT.h @@ -25,7 +25,7 @@ * Azteeg X5 GT pin assignments */ -#ifndef MCU_LPC1769 +#if NOT_TARGET(MCU_LPC1769) #error "Oops! Make sure you have the LPC1769 environment selected in your IDE." #endif diff --git a/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI.h b/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI.h index 8d5080b280..6331d6aa7c 100644 --- a/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI.h +++ b/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI.h @@ -25,7 +25,7 @@ * Azteeg X5 MINI pin assignments */ -#ifndef MCU_LPC1769 +#if NOT_TARGET(MCU_LPC1769) #error "Oops! Make sure you have the LPC1769 environment selected in your IDE." #endif @@ -109,7 +109,7 @@ // // Display // -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #if ENABLED(CR10_STOCKDISPLAY) @@ -185,7 +185,7 @@ #endif -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD // // SD Support diff --git a/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI_WIFI.h b/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI_WIFI.h index 592f666e39..99ff0fd25a 100644 --- a/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI_WIFI.h +++ b/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI_WIFI.h @@ -25,7 +25,7 @@ * Azteeg X5 MINI pin assignments */ -#ifndef MCU_LPC1769 +#if NOT_TARGET(MCU_LPC1769) #error "Oops! Make sure you have the LPC1769 environment selected in your IDE." #endif diff --git a/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h b/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h new file mode 100644 index 0000000000..76c54c3bba --- /dev/null +++ b/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h @@ -0,0 +1,260 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#ifndef BOARD_INFO_NAME + #define BOARD_INFO_NAME "BTT SKR E3 Turbo" +#endif + +// Onboard I2C EEPROM +#define I2C_EEPROM +#define MARLIN_EEPROM_SIZE 0x1000 // 4KB (AT24C32) + +// +// Servos +// +#define SERVO0_PIN P1_23 + +// +// TMC StallGuard DIAG pins +// +#define X_DIAG_PIN P1_29 // X-STOP +#define Y_DIAG_PIN P1_28 // Y-STOP +#define Z_DIAG_PIN P1_27 // Z-STOP +#define E0_DIAG_PIN P1_26 // E0DET +#define E1_DIAG_PIN P1_25 // E1DET + +// +// Limit Switches +#define X_STOP_PIN X_DIAG_PIN +#define Y_STOP_PIN Y_DIAG_PIN +#define Z_STOP_PIN Z_DIAG_PIN + +// +// Z Probe +// +#ifndef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN P1_22 +#endif + +// +// Filament Runout Sensor +// +#define FIL_RUNOUT_PIN P1_26 // E0DET +#define FIL_RUNOUT2_PIN P1_25 // E1DET + +// +// Power Supply Control +// +#ifndef PS_ON_PIN + #define PS_ON_PIN P1_21 +#endif + +// LED driving pin +#define NEOPIXEL_PIN P1_24 + +// +// Power Loss Detection +// +#ifndef POWER_LOSS_PIN + #define POWER_LOSS_PIN P1_20 // PWRDET +#endif + +// +// Steppers +// +#define X_STEP_PIN P1_04 +#define X_DIR_PIN P1_08 +#define X_ENABLE_PIN P1_00 +#ifndef X_CS_PIN + #define X_CS_PIN P1_01 +#endif + +#define Y_STEP_PIN P1_14 +#define Y_DIR_PIN P1_15 +#define Y_ENABLE_PIN P1_09 +#ifndef Y_CS_PIN + #define Y_CS_PIN P1_10 +#endif + +#define Z_STEP_PIN P4_29 +#define Z_DIR_PIN P4_28 +#define Z_ENABLE_PIN P1_16 +#ifndef Z_CS_PIN + #define Z_CS_PIN P1_17 +#endif + +#define E0_STEP_PIN P2_06 +#define E0_DIR_PIN P2_07 +#define E0_ENABLE_PIN P0_04 +#ifndef E0_CS_PIN + #define E0_CS_PIN P0_05 +#endif + +#define E1_STEP_PIN P2_11 +#define E1_DIR_PIN P2_12 +#define E1_ENABLE_PIN P0_21 +#ifndef E1_CS_PIN + #define E1_CS_PIN P0_22 +#endif + +#if HAS_TMC_UART + /** + * TMC2208/TMC2209 stepper drivers + * + * Hardware serial communication ports. + * If undefined software serial is used according to the pins below + */ + + // + // Software serial + // + #define X_SERIAL_TX_PIN P1_01 + #define X_SERIAL_RX_PIN P1_01 + + #define Y_SERIAL_TX_PIN P1_10 + #define Y_SERIAL_RX_PIN P1_10 + + #define Z_SERIAL_TX_PIN P1_17 + #define Z_SERIAL_RX_PIN P1_17 + + #define E0_SERIAL_TX_PIN P0_05 + #define E0_SERIAL_RX_PIN P0_05 + + #define E1_SERIAL_TX_PIN P0_22 + #define E1_SERIAL_RX_PIN P0_22 + + // Reduce baud rate to improve software serial reliability + #define TMC_BAUD_RATE 19200 +#endif + +// +// TMC Low Power Standby pins +// +#define X_STDBY_PIN P3_26 +#define Y_STDBY_PIN P3_25 +#define Z_STDBY_PIN P1_18 +#define E0_STDBY_PIN P1_19 +#define E1_STDBY_PIN P2_13 + +// +// Temperature Sensors +// +#define TEMP_0_PIN P0_24 +#define TEMP_1_PIN P0_23 +//#define TEMP_2_PIN P1_30 // Onboard thermistor +#define TEMP_BED_PIN P0_25 + +// +// Heaters / Fans +// +#define HEATER_0_PIN P2_03 // EXTRUDER 0 +#define HEATER_1_PIN P2_04 // EXTRUDER 1 +#define HEATER_BED_PIN P2_05 // BED +#define FAN_PIN P2_01 +#define FAN1_PIN P2_02 + +/** + * _____ + * 5V | 1 2 | GND + * (LCD_EN) P0_18 | 3 4 | P0_17 (LCD_RS) + * (LCD_D4) P0_15 | 5 6 P0_20 (BTN_EN2) + * RESET | 7 8 | P0_19 (BTN_EN1) + * (BTN_ENC) P0_16 | 9 10| P2_08 (BEEPER) + * ----- + * EXP + */ + +#define EXPA1_03_PIN P0_18 +#define EXPA1_04_PIN P0_17 +#define EXPA1_05_PIN P0_15 +#define EXPA1_06_PIN P0_20 +#define EXPA1_07_PIN -1 +#define EXPA1_08_PIN P0_19 +#define EXPA1_09_PIN P0_16 +#define EXPA1_10_PIN P2_08 + +#if HAS_WIRED_LCD + + #if ENABLED(CR10_STOCKDISPLAY) + + #define BEEPER_PIN EXPA1_10_PIN + + #define BTN_EN1 EXPA1_08_PIN + #define BTN_EN2 EXPA1_06_PIN + #define BTN_ENC EXPA1_09_PIN + + #define LCD_PINS_RS EXPA1_04_PIN + #define LCD_PINS_ENABLE EXPA1_03_PIN + #define LCD_PINS_D4 EXPA1_05_PIN + + #elif ENABLED(ZONESTAR_LCD) // ANET A8 LCD Controller - Must convert to 3.3V - CONNECTING TO 5V WILL DAMAGE THE BOARD! + + #error "CAUTION! ZONESTAR_LCD requires wiring modifications. See 'pins_BTT_SKR_E3_TURBO.h' for details. Comment out this line to continue." + + #define LCD_PINS_RS EXPA1_05_PIN + #define LCD_PINS_ENABLE EXPA1_09_PIN + #define LCD_PINS_D4 EXPA1_04_PIN + #define LCD_PINS_D5 EXPA1_06_PIN + #define LCD_PINS_D6 EXPA1_08_PIN + #define LCD_PINS_D7 EXPA1_10_PIN + #define ADC_KEYPAD_PIN P1_23 // Repurpose servo pin for ADC - CONNECTING TO 5V WILL DAMAGE THE BOARD! + + #elif EITHER(MKS_MINI_12864, ENDER2_STOCKDISPLAY) + + #define BTN_EN1 EXPA1_08_PIN + #define BTN_EN2 EXPA1_06_PIN + #define BTN_ENC EXPA1_09_PIN + + #define DOGLCD_CS EXPA1_04_PIN + #define DOGLCD_A0 EXPA1_05_PIN + #define DOGLCD_SCK EXPA1_10_PIN + #define DOGLCD_MOSI EXPA1_03_PIN + #define FORCE_SOFT_SPI + #define LCD_BACKLIGHT_PIN -1 + + #else + + #error "Only ZONESTAR_LCD, MKS_MINI_12864, ENDER2_STOCKDISPLAY, and CR10_STOCKDISPLAY are currently supported on the BTT_SKR_E3_TURBO." + + #endif + +#endif // HAS_WIRED_LCD + +// +// SD Support +// +#ifndef SDCARD_CONNECTION + #define SDCARD_CONNECTION ONBOARD +#endif + +#if SD_CONNECTION_IS(ONBOARD) + #define SD_DETECT_PIN P2_00 + #define SCK_PIN P0_07 + #define MISO_PIN P0_08 + #define MOSI_PIN P0_09 + #define SS_PIN P0_06 +#elif SD_CONNECTION_IS(CUSTOM_CABLE) + #error "SD CUSTOM_CABLE is not compatible with SKR E3 Turbo." +#endif + +#define ON_BOARD_SPI_DEVICE 1 // SPI1 diff --git a/Marlin/src/pins/lpc1769/pins_COHESION3D_MINI.h b/Marlin/src/pins/lpc1769/pins_COHESION3D_MINI.h index d5c7d9868f..d66ffbe4e5 100644 --- a/Marlin/src/pins/lpc1769/pins_COHESION3D_MINI.h +++ b/Marlin/src/pins/lpc1769/pins_COHESION3D_MINI.h @@ -25,7 +25,7 @@ * Cohesion3D Mini pin assignments */ -#ifndef MCU_LPC1769 +#if NOT_TARGET(MCU_LPC1769) #error "Oops! Make sure you have the LPC1769 environment selected in your IDE." #endif @@ -141,7 +141,7 @@ // connector are shared with the onboard SD card, and Marlin does not support reading // G-code files from the onboard SD card. // -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #define BEEPER_PIN P0_27 // EXP2-7 - open drain @@ -160,7 +160,7 @@ #error "SDSUPPORT is not currently supported by the Cohesion3D boards" #endif -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD // // Ethernet pins diff --git a/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h b/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h index 3870902881..66604ef635 100644 --- a/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h +++ b/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h @@ -25,7 +25,7 @@ * Cohesion3D ReMix pin assignments */ -#ifndef MCU_LPC1769 +#if NOT_TARGET(MCU_LPC1769) #error "Oops! Make sure you have the LPC1769 environment selected in your IDE." #endif @@ -206,7 +206,7 @@ #define NEOPIXEL_PIN P1_16 // EXP1-6 => Ethernet pin 6 (top row, 3 from left) #endif -#elif HAS_SPI_LCD +#elif HAS_WIRED_LCD #define BEEPER_PIN P1_31 // EXP1-1 //#define SD_DETECT_PIN P0_27 // EXP2-7 @@ -222,7 +222,7 @@ #define KILL_PIN P2_11 // EXP2-10 -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD // // SD Support diff --git a/Marlin/src/pins/lpc1769/pins_MKS_SGEN.h b/Marlin/src/pins/lpc1769/pins_MKS_SGEN.h index c9f3ff7aae..d67549997b 100644 --- a/Marlin/src/pins/lpc1769/pins_MKS_SGEN.h +++ b/Marlin/src/pins/lpc1769/pins_MKS_SGEN.h @@ -26,10 +26,9 @@ * * The pins diagram can be found and the following URL: * https://github.com/makerbase-mks/MKS-SGen/blob/master/Hardware/MKS%20SGEN%20V1.0_001/MKS%20SGEN%20V1.0_001%20PIN.pdf - * */ -#ifndef MCU_LPC1769 +#if NOT_TARGET(MCU_LPC1769) #error "Oops! Make sure you have the LPC1769 environment selected in your IDE." #endif diff --git a/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h b/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h new file mode 100644 index 0000000000..cbbe8a9416 --- /dev/null +++ b/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h @@ -0,0 +1,367 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * MKS SGen pin assignments + */ + +#if NOT_TARGET(MCU_LPC1769) + #error "Oops! Make sure you have the LPC1769 environment selected in your IDE." +#endif + +#define BOARD_INFO_NAME "MKS SGEN_L V2" +#define BOARD_WEBSITE_URL "github.com/makerbase-mks" + +// +// EEPROM, MKS SGEN_L V2.0 hardware has 4K EEPROM on the board +// +#if NO_EEPROM_SELECTED + //#define SDCARD_EEPROM_EMULATION + //#define I2C_EEPROM // AT24C32 + #define FLASH_EEPROM_EMULATION + #define MARLIN_EEPROM_SIZE 0x1000 // 4KB +#endif + +// +// Servos +// +#define SERVO0_PIN P1_23 // SERVO P1.23 +#define SERVO1_PIN P2_00 // SERVO P2.0 + +// +// Trinamic Stallguard pins, can connect or disconnect by jumpers cap on the board +// +#define X_DIAG_PIN P1_29 // X- +#define Y_DIAG_PIN P1_27 // Y- +#define Z_DIAG_PIN P1_25 // Z- +#define E0_DIAG_PIN P1_28 // X+ +#define E1_DIAG_PIN P1_26 // Y+ + +// +// Limit Switches +// +#if X_STALL_SENSITIVITY + #define X_STOP_PIN X_DIAG_PIN + #if X_HOME_DIR < 0 + #define X_MAX_PIN P1_28 // X+ + #else + #define X_MIN_PIN P1_28 // X+ + #endif +#else + #define X_MIN_PIN P1_29 // X- + #define X_MAX_PIN P1_28 // X+ +#endif + +#if Y_STALL_SENSITIVITY + #define Y_STOP_PIN Y_DIAG_PIN + #if Y_HOME_DIR < 0 + #define Y_MAX_PIN P1_26 // Y+ + #else + #define Y_MIN_PIN P1_26 // Y+ + #endif +#else + #define Y_MIN_PIN P1_27 // Y- + #define Y_MAX_PIN P1_26 // Y+ +#endif + +#if Z_STALL_SENSITIVITY + #define Z_STOP_PIN Z_DIAG_PIN + #if Z_HOME_DIR < 0 + #define Z_MAX_PIN P1_24 // Z+ + #else + #define Z_MIN_PIN P1_24 // Z+ + #endif +#else + #define Z_MIN_PIN P1_25 // Z- + #define Z_MAX_PIN P1_24 // Z+ +#endif + +// +// Z Probe (when not Z_MIN_PIN) +// +#ifndef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN P1_24 +#endif + +// +// Steppers +// +#define X_STEP_PIN P2_02 +#define X_DIR_PIN P2_03 +#define X_ENABLE_PIN P2_01 +#ifndef X_CS_PIN + #define X_CS_PIN P1_01 +#endif + +#define Y_STEP_PIN P0_19 +#define Y_DIR_PIN P0_20 +#define Y_ENABLE_PIN P2_08 +#ifndef Y_CS_PIN + #define Y_CS_PIN P1_08 +#endif + +#define Z_STEP_PIN P0_22 +#define Z_DIR_PIN P2_11 +#define Z_ENABLE_PIN P0_21 +#ifndef Z_CS_PIN + #define Z_CS_PIN P1_10 +#endif + +#define E0_STEP_PIN P2_13 +#define E0_DIR_PIN P0_11 +#define E0_ENABLE_PIN P2_12 +#ifndef E0_CS_PIN + #define E0_CS_PIN P1_15 +#endif + +#define E1_STEP_PIN P1_09 +#define E1_DIR_PIN P1_14 +#define E1_ENABLE_PIN P0_10 +#ifndef E1_CS_PIN + #define E1_CS_PIN P1_17 +#endif + +// +// Software SPI pins for TMC2130 stepper drivers +// +#if ENABLED(TMC_USE_SW_SPI) + #ifndef TMC_SW_MOSI + #define TMC_SW_MOSI P1_16 + #endif + #ifndef TMC_SW_MISO + #define TMC_SW_MISO P0_05 + #endif + #ifndef TMC_SW_SCK + #define TMC_SW_SCK P0_04 + #endif +#endif + +#if HAS_TMC_UART + /** + * TMC2208/TMC2209 stepper drivers + * + * Hardware serial communication ports. + * If undefined software serial is used according to the pins below + */ + //#define X_HARDWARE_SERIAL Serial1 + //#define X2_HARDWARE_SERIAL Serial1 + //#define Y_HARDWARE_SERIAL Serial1 + //#define Y2_HARDWARE_SERIAL Serial1 + //#define Z_HARDWARE_SERIAL Serial1 + //#define Z2_HARDWARE_SERIAL Serial1 + //#define E0_HARDWARE_SERIAL Serial1 + //#define E1_HARDWARE_SERIAL Serial1 + //#define E2_HARDWARE_SERIAL Serial1 + //#define E3_HARDWARE_SERIAL Serial1 + //#define E4_HARDWARE_SERIAL Serial1 + + // + // Software serial + // + #define X_SERIAL_TX_PIN P1_01 + #define X_SERIAL_RX_PIN P1_01 + #define Y_SERIAL_TX_PIN P1_08 + #define Y_SERIAL_RX_PIN P1_08 + #define Z_SERIAL_TX_PIN P1_10 + #define Z_SERIAL_RX_PIN P1_10 + #define E0_SERIAL_TX_PIN P1_15 + #define E0_SERIAL_RX_PIN P1_15 + #define E1_SERIAL_TX_PIN P1_17 + #define E1_SERIAL_RX_PIN P1_17 + + // Reduce baud rate to improve software serial reliability + #define TMC_BAUD_RATE 19200 +#endif // HAS_TMC_UART + +// +// Temperature Sensors +// 3.3V max when defined as an analog input +// +#define TEMP_0_PIN P0_23_A0 // Analog Input A0 (TH1) +#define TEMP_BED_PIN P0_24_A1 // Analog Input A1 (TB) +#define TEMP_1_PIN P0_25_A2 // Analog Input A2 (TH2) +#define TEMP_2_PIN P0_26_A3 // Analog Input A3 (P0.26, No pull up) + +// +// Heaters / Fans +// +#define HEATER_BED_PIN P2_05 +#define HEATER_0_PIN P2_07 +#if HAS_MULTI_HOTEND + #ifndef HEATER_1_PIN + #define HEATER_1_PIN P2_06 + #endif +#else + #ifndef FAN2_PIN + #define FAN2_PIN P2_06 // HE1 for FAN3 + #endif +#endif +#ifndef FAN_PIN + #define FAN_PIN P2_04 // FAN1 +#endif +#ifndef FAN1_PIN + #define FAN1_PIN P1_04 // FAN2 +#endif + +// +// Misc. Functions +// +#define LED_PIN P1_18 // Used as a status indicator +#define LED2_PIN P1_19 +#define LED3_PIN P1_20 +#define LED4_PIN P1_21 + +/** + * _____ _____ + * (BEEPER) 1.31 | · · | 1.30 (BTN_ENC) (MISO) 0.8 | · · | 0.7 (SD_SCK) + * (LCD_EN) 0.18 | · · | 0.16 (LCD_RS) (BTN_EN1) 3.25 | · · | 0.28 (SD_CS2) + * (LCD_D4) 0.15 | · ·| 0.17 (LCD_D5) (BTN_EN2) 3.26 | · ·| 0.9 (SD_MOSI) + * (LCD_D6) 1.0 | · · | 1.22 (LCD_D7) (SD_DETECT) 0.27 | · · | RST + * GND | · · | 5V GND | · · | NC + * ----- ----- + * EXP1 EXP2 + */ +#if IS_TFTGLCD_PANEL + + #if ENABLED(TFTGLCD_PANEL_SPI) + #define TFTGLCD_CS P3_25 + #endif + + #define SD_DETECT_PIN P0_27 + +#elif HAS_WIRED_LCD + + #define BEEPER_PIN P1_31 + #define BTN_ENC P1_30 + + #if ENABLED(CR10_STOCKDISPLAY) + + #define LCD_PINS_RS P1_00 + + #define BTN_EN1 P0_18 + #define BTN_EN2 P0_15 + + #define LCD_PINS_ENABLE P1_22 + #define LCD_PINS_D4 P0_17 + + #else + + #define BTN_EN1 P3_25 + #define BTN_EN2 P3_26 + + #define LCD_SDSS P0_28 + + #if ENABLED(MKS_12864OLED_SSD1306) + + #define LCD_PINS_DC P0_17 + #define DOGLCD_CS P0_16 + #define DOGLCD_A0 LCD_PINS_DC + #define DOGLCD_SCK P0_15 + #define DOGLCD_MOSI P0_18 + + #define LCD_PINS_RS P1_00 + #define LCD_PINS_D7 P1_22 + #define KILL_PIN -1 // NC + + #else // !MKS_12864OLED_SSD1306 + + #define LCD_PINS_RS P0_16 + + #define LCD_PINS_ENABLE P0_18 + #define LCD_PINS_D4 P0_15 + + #if ENABLED(FYSETC_MINI_12864) + + #define DOGLCD_CS P0_18 + #define DOGLCD_A0 P0_16 + #define DOGLCD_SCK P0_07 + #define DOGLCD_MOSI P1_20 + + #define LCD_BACKLIGHT_PIN -1 + + #define FORCE_SOFT_SPI // Use this if default of hardware SPI causes display problems + // results in LCD soft SPI mode 3, SD soft SPI mode 0 + + #define LCD_RESET_PIN P0_15 // Must be high or open for LCD to operate normally. + + #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #ifndef RGB_LED_R_PIN + #define RGB_LED_R_PIN P0_17 + #endif + #ifndef RGB_LED_G_PIN + #define RGB_LED_G_PIN P1_00 + #endif + #ifndef RGB_LED_B_PIN + #define RGB_LED_B_PIN P1_22 + #endif + #elif ENABLED(FYSETC_MINI_12864_2_1) + #define NEOPIXEL_PIN P0_17 + #endif + + #else // !FYSETC_MINI_12864 + + #if ENABLED(MKS_MINI_12864) + #define DOGLCD_CS P0_17 + #define DOGLCD_A0 P1_00 + #endif + + #if ENABLED(ULTIPANEL) + #define LCD_PINS_D5 P0_17 + #define LCD_PINS_D6 P1_00 + #define LCD_PINS_D7 P1_22 + #endif + + #endif // !FYSETC_MINI_12864 + + #endif // !MKS_12864OLED_SSD1306 + + #endif // !CR10_STOCKDISPLAY + +#endif // HAS_WIRED_LCD + +#ifndef SDCARD_CONNECTION + #define SDCARD_CONNECTION ONBOARD +#endif + +#define ONBOARD_SD_CS_PIN P0_06 // Chip select for "System" SD card + +#if SD_CONNECTION_IS(LCD) || SD_CONNECTION_IS(ONBOARD) + #define SD_DETECT_PIN P0_27 + #define SCK_PIN P0_07 + #define MISO_PIN P0_08 + #define MOSI_PIN P0_09 + #if SD_CONNECTION_IS(ONBOARD) + #define SS_PIN ONBOARD_SD_CS_PIN + #else + #define SS_PIN P0_28 + #endif +#elif SD_CONNECTION_IS(CUSTOM_CABLE) + #error "No custom SD drive cable defined for this board." +#endif + +// +// Other Pins +// +//#define PIN_P0_02 P0_02 // AUX1 (Interrupt Capable/ADC/Serial Port 0) +//#define PIN_P0_03 P0_03 // AUX1 (Interrupt Capable/ADC/Serial Port 0) +//#define PS_ON_PIN P1_23 // SERVO P1.23 diff --git a/Marlin/src/pins/lpc1769/pins_SMOOTHIEBOARD.h b/Marlin/src/pins/lpc1769/pins_SMOOTHIEBOARD.h index c9bd9ec3ae..f2811b14ab 100644 --- a/Marlin/src/pins/lpc1769/pins_SMOOTHIEBOARD.h +++ b/Marlin/src/pins/lpc1769/pins_SMOOTHIEBOARD.h @@ -25,7 +25,7 @@ * Smoothieboard pin assignments */ -#ifndef MCU_LPC1769 +#if NOT_TARGET(MCU_LPC1769) #error "Oops! Make sure you have the LPC1769 environment selected in your IDE." #endif @@ -109,9 +109,57 @@ #define STAT_LED_RED_PIN P1_19 #define STAT_LED_BLUE_PIN P1_20 -#elif HAS_SPI_LCD - - #error "Marlin's Smoothieboard support cannot drive your LCD." +#elif HAS_WIRED_LCD + + /** + * SD Support + * + * For the RRD GLCD it CANNOT share the same SPI as the LCD so it must be + * hooked up to the onboard SDCard SPI and use a spare pin for the SDCS. + * Also note that an external SDCard sharing the SPI port with the + * onboard/internal SDCard must be ejected before rebooting as the bootloader + * does not like the external card. NOTE Smoothie will not boot if the external + * sdcard is inserted in the RRD LCD sdcard slot at boot time, it must be + * inserted after it has booted. + */ + #define SD_DETECT_PIN P0_27 // EXP2 Pin 7 (SD_CD, SD_DET) + + #define MISO_PIN P0_08 // EXP2 Pin 1 (PB3, SD_MISO) + #define SCK_PIN P0_07 // EXP2 Pin 2 (SD_SCK) + #define SS_PIN P0_28 // EXP2 Pin 4 (SD_CSEL, SD_CS) + #define MOSI_PIN P0_09 // EXP2 Pin 6 (PB2, SD_MOSI) + + /** + * The Smoothieboard supports the REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER with either + * a custom cable with breakouts to the pins indicated below or the RRD GLCD Adapter board + * found at http://smoothieware.org/rrdglcdadapter + * + * Other links to information about setting up a display panel with Smoothieboard + * http://chibidibidiwah.wdfiles.com/local--files/panel/smoothieboard2sd.jpg + * http://smoothieware.org/panel + */ + #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + // EXP1 Pins + #define BEEPER_PIN P1_31 // EXP1 Pin 1 + #define BTN_ENC P1_30 // EXP1 Pin 2 + #define LCD_PINS_ENABLE P0_18 // EXP1 Pin 3 (MOSI) + #define LCD_PINS_RS P0_16 // EXP1 Pin 4 (CS) + #define LCD_PINS_D4 P0_15 // EXP1 Pin 5 (SCK) + // EXP2 Pins + #define BTN_EN2 P3_26 // EXP2 Pin 3 + #define BTN_EN1 P3_25 // EXP2 Pin 5 + + #elif IS_TFTGLCD_PANEL + + #define SD_DETECT_PIN P0_27 // EXP2 Pin 7 (SD_CD, SD_DET) + + #if ENABLED(TFTGLCD_PANEL_SPI) + #define TFTGLCD_CS P3_26 // EXP2 Pin 3 + #endif + + #else + #error "Marlin's Smoothieboard support cannot drive your LCD." + #endif #endif diff --git a/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h b/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h index 81f5b75016..a0174f2602 100644 --- a/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h +++ b/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h @@ -25,7 +25,7 @@ * TH3D EZBoard pin assignments */ -#ifndef MCU_LPC1769 +#if NOT_TARGET(MCU_LPC1769) #error "Oops! Make sure you have the LPC1769 environment selected in your IDE." #endif @@ -166,7 +166,6 @@ * * A remote SD card is currently not supported because the pins routed to the EXP2 * connector are shared with the onboard SD card. - * */ #if ENABLED(CR10_STOCKDISPLAY) @@ -178,6 +177,6 @@ #define LCD_PINS_ENABLE P0_18 #define LCD_PINS_D4 P0_15 #define KILL_PIN P2_11 -#elif HAS_SPI_LCD +#elif HAS_WIRED_LCD #error "Only the CR10_STOCKDISPLAY is supported with TH3D EZBoard." #endif diff --git a/Marlin/src/pins/mega/pins_CHEAPTRONIC.h b/Marlin/src/pins/mega/pins_CHEAPTRONIC.h index 90d4340ba8..98427d9e59 100644 --- a/Marlin/src/pins/mega/pins_CHEAPTRONIC.h +++ b/Marlin/src/pins/mega/pins_CHEAPTRONIC.h @@ -25,7 +25,7 @@ * Cheaptronic v1.0 pin assignments */ -#ifndef __AVR_ATmega2560__ +#if NOT_TARGET(__AVR_ATmega2560__) #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" #endif diff --git a/Marlin/src/pins/mega/pins_CHEAPTRONICv2.h b/Marlin/src/pins/mega/pins_CHEAPTRONICv2.h index 18bcc9e407..3a84f4395f 100644 --- a/Marlin/src/pins/mega/pins_CHEAPTRONICv2.h +++ b/Marlin/src/pins/mega/pins_CHEAPTRONICv2.h @@ -27,7 +27,7 @@ * www.reprapobchod.cz */ -#ifndef __AVR_ATmega2560__ +#if NOT_TARGET(__AVR_ATmega2560__) #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" #endif diff --git a/Marlin/src/pins/mega/pins_CNCONTROLS_11.h b/Marlin/src/pins/mega/pins_CNCONTROLS_11.h index 6f792ad5fa..675d4b7262 100644 --- a/Marlin/src/pins/mega/pins_CNCONTROLS_11.h +++ b/Marlin/src/pins/mega/pins_CNCONTROLS_11.h @@ -25,7 +25,7 @@ * CartesioV11 pin assignments */ -#if !defined(__AVR_ATmega1280__) && !defined(__AVR_ATmega2560__) +#if NOT_TARGET(__AVR_ATmega1280__, __AVR_ATmega2560__) #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" #endif diff --git a/Marlin/src/pins/mega/pins_CNCONTROLS_12.h b/Marlin/src/pins/mega/pins_CNCONTROLS_12.h index 7040c2babb..35426a4531 100644 --- a/Marlin/src/pins/mega/pins_CNCONTROLS_12.h +++ b/Marlin/src/pins/mega/pins_CNCONTROLS_12.h @@ -25,7 +25,7 @@ * CartesioV12 pin assignments */ -#if !defined(__AVR_ATmega1280__) && !defined(__AVR_ATmega2560__) +#if NOT_TARGET(__AVR_ATmega1280__, __AVR_ATmega2560__) #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" #endif diff --git a/Marlin/src/pins/mega/pins_CNCONTROLS_15.h b/Marlin/src/pins/mega/pins_CNCONTROLS_15.h index 4af0d991e9..8bafbdf000 100644 --- a/Marlin/src/pins/mega/pins_CNCONTROLS_15.h +++ b/Marlin/src/pins/mega/pins_CNCONTROLS_15.h @@ -25,7 +25,7 @@ * CNControls V15 for HMS434 pin assignments */ -#if !defined(__AVR_ATmega1280__) && !defined(__AVR_ATmega2560__) +#if NOT_TARGET(__AVR_ATmega1280__, __AVR_ATmega2560__) #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" #endif diff --git a/Marlin/src/pins/mega/pins_EINSTART-S.h b/Marlin/src/pins/mega/pins_EINSTART-S.h index eeaf0c4197..40d65c353e 100644 --- a/Marlin/src/pins/mega/pins_EINSTART-S.h +++ b/Marlin/src/pins/mega/pins_EINSTART-S.h @@ -26,7 +26,7 @@ * PCB Silkscreen: 3DPrinterCon_v3.5 */ -#if !defined(__AVR_ATmega1280__) && !defined(__AVR_ATmega2560__) +#if NOT_TARGET(__AVR_ATmega1280__, __AVR_ATmega2560__) #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" #endif diff --git a/Marlin/src/pins/mega/pins_ELEFU_3.h b/Marlin/src/pins/mega/pins_ELEFU_3.h index 685611f78d..af93c408a2 100644 --- a/Marlin/src/pins/mega/pins_ELEFU_3.h +++ b/Marlin/src/pins/mega/pins_ELEFU_3.h @@ -25,7 +25,7 @@ * Elefu RA Board Pin Assignments */ -#ifndef __AVR_ATmega2560__ +#if NOT_TARGET(__AVR_ATmega2560__) #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" #endif diff --git a/Marlin/src/pins/mega/pins_GT2560_REV_A.h b/Marlin/src/pins/mega/pins_GT2560_REV_A.h index ebfdd24bb4..2fe9a43ba1 100644 --- a/Marlin/src/pins/mega/pins_GT2560_REV_A.h +++ b/Marlin/src/pins/mega/pins_GT2560_REV_A.h @@ -27,7 +27,7 @@ * Richard Smith */ -#if !defined(__AVR_ATmega1280__) && !defined(__AVR_ATmega2560__) +#if NOT_TARGET(__AVR_ATmega1280__, __AVR_ATmega2560__) #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" #endif @@ -105,7 +105,7 @@ #define SUICIDE_PIN 54 // Must be enabled at startup to keep power flowing #define KILL_PIN -1 -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #define BEEPER_PIN 18 @@ -148,4 +148,4 @@ #endif // !NEWPANEL -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/mega/pins_GT2560_V3.h b/Marlin/src/pins/mega/pins_GT2560_V3.h index 9b396d8db2..d71a195419 100644 --- a/Marlin/src/pins/mega/pins_GT2560_V3.h +++ b/Marlin/src/pins/mega/pins_GT2560_V3.h @@ -25,7 +25,7 @@ * GT2560 RevB + GT2560 V3.0 + GT2560 V3.1 + GT2560 V4.0 pin assignment */ -#if !defined(__AVR_ATmega1280__) && !defined(__AVR_ATmega2560__) +#if NOT_TARGET(__AVR_ATmega1280__, __AVR_ATmega2560__) #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" #endif diff --git a/Marlin/src/pins/mega/pins_HJC2560C_REV2.h b/Marlin/src/pins/mega/pins_HJC2560C_REV2.h index 2cbac0723c..e30a65b90e 100644 --- a/Marlin/src/pins/mega/pins_HJC2560C_REV2.h +++ b/Marlin/src/pins/mega/pins_HJC2560C_REV2.h @@ -25,7 +25,7 @@ * HJC2560-C Rev2.x pin assignments */ -#ifndef __AVR_ATmega2560__ +#if NOT_TARGET(__AVR_ATmega2560__) #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" #endif @@ -123,7 +123,7 @@ // // LCD / Controller // -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #define BEEPER_PIN 18 @@ -170,4 +170,4 @@ #endif // !NEWPANEL -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/mega/pins_INTAMSYS40.h b/Marlin/src/pins/mega/pins_INTAMSYS40.h index b6ff30a4fc..be5f461dda 100644 --- a/Marlin/src/pins/mega/pins_INTAMSYS40.h +++ b/Marlin/src/pins/mega/pins_INTAMSYS40.h @@ -27,7 +27,7 @@ * 2208 version exists and may or may not work */ -#ifndef __AVR_ATmega2560__ +#if NOT_TARGET(__AVR_ATmega2560__) #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" #endif @@ -122,7 +122,7 @@ #define BEEPER_PIN 18 -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #define LCD_PINS_RS 20 #define LCD_PINS_ENABLE 30 #define LCD_PINS_D4 14 @@ -137,7 +137,6 @@ ///////////////////// SPARE HEADERS ////////////// /** - * * J25 * 1 D54 * 2 D55 diff --git a/Marlin/src/pins/mega/pins_LEAPFROG.h b/Marlin/src/pins/mega/pins_LEAPFROG.h index 99872e1fb4..9e6802b24b 100644 --- a/Marlin/src/pins/mega/pins_LEAPFROG.h +++ b/Marlin/src/pins/mega/pins_LEAPFROG.h @@ -25,7 +25,7 @@ * Leapfrog Driver board pin assignments */ -#if !defined(__AVR_ATmega1280__) && !defined(__AVR_ATmega2560__) +#if NOT_TARGET(__AVR_ATmega1280__, __AVR_ATmega2560__) #error "Oops! Select 'Mega 1280' or 'Mega 2560' in 'Tools > Board.'" #endif diff --git a/Marlin/src/pins/mega/pins_LEAPFROG_XEED2015.h b/Marlin/src/pins/mega/pins_LEAPFROG_XEED2015.h index 61f5508cdc..9c316aa759 100644 --- a/Marlin/src/pins/mega/pins_LEAPFROG_XEED2015.h +++ b/Marlin/src/pins/mega/pins_LEAPFROG_XEED2015.h @@ -29,7 +29,7 @@ * printer models. As such this file is currently specific to the Xeed. */ -#ifndef __AVR_ATmega2560__ +#if NOT_TARGET(__AVR_ATmega2560__) #error "Oops! Select 'Mega 2560' in 'Tools > Board.'" #endif diff --git a/Marlin/src/pins/mega/pins_MEGACONTROLLER.h b/Marlin/src/pins/mega/pins_MEGACONTROLLER.h index 6b90b884c2..938ad82eff 100644 --- a/Marlin/src/pins/mega/pins_MEGACONTROLLER.h +++ b/Marlin/src/pins/mega/pins_MEGACONTROLLER.h @@ -25,7 +25,7 @@ * Mega controller pin assignments */ -#ifndef __AVR_ATmega2560__ +#if NOT_TARGET(__AVR_ATmega2560__) #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" #elif HOTENDS > 2 || E_STEPPERS > 2 #error "Mega Controller supports up to 2 hotends / E-steppers. Comment out this line to continue." diff --git a/Marlin/src/pins/mega/pins_MEGATRONICS.h b/Marlin/src/pins/mega/pins_MEGATRONICS.h index 84346e5f66..1c37b21ab7 100644 --- a/Marlin/src/pins/mega/pins_MEGATRONICS.h +++ b/Marlin/src/pins/mega/pins_MEGATRONICS.h @@ -25,7 +25,7 @@ * MegaTronics pin assignments */ -#ifndef __AVR_ATmega2560__ +#if NOT_TARGET(__AVR_ATmega2560__) #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" #endif @@ -124,7 +124,7 @@ #define SD_DETECT_PIN -1 // RAMPS doesn't use this -#endif // HAS_SPI_LCD && NEWPANEL +#endif // ULTRA_LCD && NEWPANEL // // M3/M4/M5 - Spindle/Laser Control diff --git a/Marlin/src/pins/mega/pins_MEGATRONICS_2.h b/Marlin/src/pins/mega/pins_MEGATRONICS_2.h index 481dc35fa3..ff7cf15714 100644 --- a/Marlin/src/pins/mega/pins_MEGATRONICS_2.h +++ b/Marlin/src/pins/mega/pins_MEGATRONICS_2.h @@ -25,7 +25,7 @@ * MegaTronics v2.0 pin assignments */ -#ifndef __AVR_ATmega2560__ +#if NOT_TARGET(__AVR_ATmega2560__) #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" #endif @@ -130,7 +130,7 @@ // #define BEEPER_PIN 64 -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #define LCD_PINS_RS 14 #define LCD_PINS_ENABLE 15 @@ -152,4 +152,4 @@ #define SHIFT_EN 17 #endif -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/mega/pins_MEGATRONICS_3.h b/Marlin/src/pins/mega/pins_MEGATRONICS_3.h index 0938896748..45ebd163a7 100644 --- a/Marlin/src/pins/mega/pins_MEGATRONICS_3.h +++ b/Marlin/src/pins/mega/pins_MEGATRONICS_3.h @@ -25,7 +25,7 @@ * MegaTronics v3.0 / v3.1 / v3.2 pin assignments */ -#ifndef __AVR_ATmega2560__ +#if NOT_TARGET(__AVR_ATmega2560__) #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" #endif diff --git a/Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h b/Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h index 526c9bfc68..963911ec5d 100644 --- a/Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h +++ b/Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h @@ -37,7 +37,7 @@ * number (B5) agrees with the schematic but B5 is assigned to logical pin 11. */ -#if !defined(__AVR_ATmega1280__) && !defined(__AVR_ATmega2560__) +#if NOT_TARGET(__AVR_ATmega1280__, __AVR_ATmega2560__) #error "Oops! Select 'Mega 1280' or 'Mega 2560' in 'Tools > Board.'" #endif @@ -212,7 +212,7 @@ // // LCD / Controller // -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) @@ -260,7 +260,7 @@ #define BTN_CENTER 15 // J0 #define BTN_ENC BTN_CENTER -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD // // SD Card diff --git a/Marlin/src/pins/mega/pins_MINITRONICS.h b/Marlin/src/pins/mega/pins_MINITRONICS.h index 138d4b4431..bbe746461e 100644 --- a/Marlin/src/pins/mega/pins_MINITRONICS.h +++ b/Marlin/src/pins/mega/pins_MINITRONICS.h @@ -29,10 +29,9 @@ * Rev B 2 JAN 2017 * * Added pin definitions for M3, M4 & M5 spindle control commands - * */ -#ifndef __AVR_ATmega1281__ +#if NOT_TARGET(__AVR_ATmega1281__) #error "Oops! Select 'Minitronics' in 'Tools > Board.'" #elif HOTENDS > 2 || E_STEPPERS > 2 #error "Minitronics supports up to 2 hotends / E-steppers. Comment out this line to continue." diff --git a/Marlin/src/pins/mega/pins_OVERLORD.h b/Marlin/src/pins/mega/pins_OVERLORD.h index bbccc93561..045c1bc0fa 100644 --- a/Marlin/src/pins/mega/pins_OVERLORD.h +++ b/Marlin/src/pins/mega/pins_OVERLORD.h @@ -25,7 +25,7 @@ * Dreammaker Overlord v1.1 pin assignments */ -#ifndef __AVR_ATmega2560__ +#if NOT_TARGET(__AVR_ATmega2560__) #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" #elif HOTENDS > 2 || E_STEPPERS > 2 #error "Overlord Controller supports up to 2 hotends / E-steppers. Comment out this line to continue." @@ -119,7 +119,7 @@ // // LCD / Controller // -#if HAS_GRAPHICAL_LCD +#if HAS_MARLINUI_U8GLIB // OVERLORD OLED pins #define LCD_PINS_RS 20 #define LCD_PINS_D5 21 diff --git a/Marlin/src/pins/mega/pins_PICA.h b/Marlin/src/pins/mega/pins_PICA.h index 40ef3a610f..ff4d3e834d 100644 --- a/Marlin/src/pins/mega/pins_PICA.h +++ b/Marlin/src/pins/mega/pins_PICA.h @@ -42,7 +42,7 @@ AD12 = 66; AD13 = 67; AD14 = 68; AD15 = 69; */ -#if !defined(__AVR_ATmega1280__) && !defined(__AVR_ATmega2560__) +#if NOT_TARGET(__AVR_ATmega1280__, __AVR_ATmega2560__) #error "Oops! Make sure you have 'Arduino Mega' selected from the 'Tools -> Boards' menu." #endif @@ -137,7 +137,7 @@ // #define BEEPER_PIN 29 -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #define LCD_PINS_RS 33 #define LCD_PINS_ENABLE 30 #define LCD_PINS_D4 35 diff --git a/Marlin/src/pins/mega/pins_SILVER_GATE.h b/Marlin/src/pins/mega/pins_SILVER_GATE.h index a67725d9bc..41cbe5e0e0 100644 --- a/Marlin/src/pins/mega/pins_SILVER_GATE.h +++ b/Marlin/src/pins/mega/pins_SILVER_GATE.h @@ -21,7 +21,7 @@ */ #pragma once -#if !defined(__AVR_ATmega1281__) && !defined(__AVR_ATmega2561__) +#if NOT_TARGET(__AVR_ATmega1281__, __AVR_ATmega2561__) #error "Oops! Select 'Silvergate' in 'Tools > Board.'" #endif @@ -72,7 +72,7 @@ #define HEATER_BED_PIN 8 #define TEMP_BED_PIN 6 -#if HAS_GRAPHICAL_LCD +#if HAS_MARLINUI_U8GLIB #if ENABLED(U8GLIB_ST7920) // SPI GLCD 12864 ST7920 #define LCD_PINS_RS 30 #define LCD_PINS_ENABLE 20 diff --git a/Marlin/src/pins/mega/pins_WANHAO_ONEPLUS.h b/Marlin/src/pins/mega/pins_WANHAO_ONEPLUS.h index ba7f64768b..52e757c534 100644 --- a/Marlin/src/pins/mega/pins_WANHAO_ONEPLUS.h +++ b/Marlin/src/pins/mega/pins_WANHAO_ONEPLUS.h @@ -25,7 +25,7 @@ * Wanhao 0ne+ pin assignments */ -#ifndef __AVR_ATmega2560__ +#if NOT_TARGET(__AVR_ATmega2560__) #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" #endif diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 22f6ea663c..3ec4e1a34b 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -51,6 +51,13 @@ #define HAS_FREE_AUX2_PINS !(BOTH(ULTRA_LCD, NEWPANEL) && ANY(PANEL_ONE, VIKI2, miniVIKI, MINIPANEL, REPRAPWORLD_KEYPAD)) +// Test the target within the included pins file +#ifdef __MARLIN_PREBUILD__ + #define NOT_TARGET(V...) 0 +#else + #define NOT_TARGET(V...) NONE(V) +#endif + // // RAMPS 1.3 / 1.4 - ATmega1280, ATmega2560 // @@ -196,6 +203,8 @@ #include "ramps/pins_ORTUR_4.h" // ATmega2560 env:mega2560 #elif MB(TENLOG_D3_HERO) #include "ramps/pins_TENLOG_D3_HERO.h" // ATmega2560 env:mega2560 +#elif MB(MKS_GEN_L_V21) + #include "ramps/pins_MKS_GEN_L_V21.h" // ATmega2560 env:mega2560 // // RAMBo and derivatives @@ -410,6 +419,10 @@ #include "lpc1769/pins_TH3D_EZBOARD.h" // LPC1769 env:LPC1769 #elif MB(BTT_SKR_V1_4_TURBO) #include "lpc1769/pins_BTT_SKR_V1_4_TURBO.h" // LPC1769 env:LPC1769 +#elif MB(MKS_SGEN_L_V2) + #include "lpc1769/pins_MKS_SGEN_L_V2.h" // LPC1769 env:LPC1769 +#elif MB(BTT_SKR_E3_TURBO) + #include "lpc1769/pins_BTT_SKR_E3_TURBO.h" // LPC1769 env:LPC1769 // // Due (ATSAM) boards @@ -478,7 +491,7 @@ // STM32 ARM Cortex-M0 // #elif MB(MALYAN_M200_V2) - #include "stm32f0/pins_MALYAN_M200_V2.h" // STM32F0 env:STM32F070RB_malyan + #include "stm32f0/pins_MALYAN_M200_V2.h" // STM32F0 env:STM32F070RB_malyan env:STM32F070CB_malyan #elif MB(MALYAN_M300) #include "stm32f0/pins_MALYAN_M300.h" // STM32F070 env:malyan_M300 @@ -494,10 +507,10 @@ #include "stm32f1/pins_STM3R_MINI.h" // STM32F1 env:STM32F103RE #elif MB(GTM32_PRO_VB) #include "stm32f1/pins_GTM32_PRO_VB.h" // STM32F1 env:STM32F103RE -#elif MB(GTM32_MINI_A30) - #include "stm32f1/pins_GTM32_MINI_A30.h" // STM32F1 env:STM32F103RE #elif MB(GTM32_MINI) #include "stm32f1/pins_GTM32_MINI.h" // STM32F1 env:STM32F103RE +#elif MB(GTM32_MINI_A30) + #include "stm32f1/pins_GTM32_MINI_A30.h" // STM32F1 env:STM32F103RE #elif MB(GTM32_REV_B) #include "stm32f1/pins_GTM32_REV_B.h" // STM32F1 env:STM32F103RE #elif MB(MORPHEUS) @@ -514,6 +527,16 @@ #include "stm32f1/pins_MKS_ROBIN_NANO_V2.h" // STM32F1 env:mks_robin_nano35 #elif MB(MKS_ROBIN_LITE) #include "stm32f1/pins_MKS_ROBIN_LITE.h" // STM32F1 env:mks_robin_lite +#elif MB(MKS_ROBIN_LITE3) + #include "stm32f1/pins_MKS_ROBIN_LITE3.h" // STM32F1 env:mks_robin_lite3 +#elif MB(MKS_ROBIN_PRO) + #include "stm32f1/pins_MKS_ROBIN_PRO.h" // STM32F1 env:mks_robin_pro +#elif MB(MKS_ROBIN_E3) + #include "stm32f1/pins_MKS_ROBIN_E3.h" // STM32F1 env:mks_robin_e3 +#elif MB(MKS_ROBIN_E3D) + #include "stm32f1/pins_MKS_ROBIN_E3D.h" // STM32F1 env:mks_robin_e3 +#elif MB(MKS_ROBIN_E3P) + #include "stm32f1/pins_MKS_ROBIN_E3P.h" // STM32F1 env:mks_robin_e3p #elif MB(BTT_SKR_MINI_V1_1) #include "stm32f1/pins_BTT_SKR_MINI_V1_1.h" // STM32F1 env:STM32F103RC_btt env:STM32F103RC_btt_512K env:STM32F103RC_btt_USB env:STM32F103RC_btt_512K_USB #elif MB(BTT_SKR_MINI_E3_V1_0) @@ -534,14 +557,6 @@ #include "stm32f1/pins_FYSETC_CHEETAH_V12.h" // STM32F1 env:STM32F103RC_fysetc #elif MB(LONGER3D_LK) #include "stm32f1/pins_LONGER3D_LK.h" // STM32F1 env:STM32F103VE_longer -#elif MB(MKS_ROBIN_LITE3) - #include "stm32f1/pins_MKS_ROBIN_LITE3.h" // STM32F1 env:mks_robin_lite3 -#elif MB(MKS_ROBIN_PRO) - #include "stm32f1/pins_MKS_ROBIN_PRO.h" // STM32F1 env:mks_robin_pro -#elif MB(MKS_ROBIN_E3D) - #include "stm32f1/pins_MKS_ROBIN_E3D.h" // STM32F1 env:mks_robin_e3 -#elif MB(MKS_ROBIN_E3) - #include "stm32f1/pins_MKS_ROBIN_E3.h" // STM32F1 env:mks_robin_e3 #elif MB(CCROBOT_MEEB_3DP) #include "stm32f1/pins_CCROBOT_MEEB_3DP.h" // STM32F1 env:STM32F103RC_meeb #elif MB(CHITU3D_V5) @@ -617,6 +632,10 @@ #include "stm32f7/pins_THE_BORG.h" // STM32F7 env:STM32F7 #elif MB(REMRAM_V1) #include "stm32f7/pins_REMRAM_V1.h" // STM32F7 env:STM32F7 +#elif MB(TEENSY41) + #include "teensy4/pins_TEENSY41.h" // Teensy-4.x env:teensy41 +#elif MB(T41U5XBB) + #include "teensy4/pins_T41U5XBB.h" // Teensy-4.x env:teensy41 // // Espressif ESP32 @@ -1208,7 +1227,7 @@ #define LCD_PINS_D4 -1 #endif -#if HAS_CHARACTER_LCD || TOUCH_UI_ULTIPANEL +#if HAS_MARLINUI_HD44780 || TOUCH_UI_ULTIPANEL #ifndef LCD_PINS_D5 #define LCD_PINS_D5 -1 #endif @@ -1578,7 +1597,7 @@ #define Z4_MS3_PIN -1 #endif -#if HAS_GRAPHICAL_LCD +#if HAS_MARLINUI_U8GLIB #if !defined(ST7920_DELAY_1) && defined(BOARD_ST7920_DELAY_1) #define ST7920_DELAY_1 BOARD_ST7920_DELAY_1 #endif diff --git a/Marlin/src/pins/pinsDebug.h b/Marlin/src/pins/pinsDebug.h index 0766d818e7..5f153cfa2b 100644 --- a/Marlin/src/pins/pinsDebug.h +++ b/Marlin/src/pins/pinsDebug.h @@ -31,7 +31,6 @@ * * Both passes use the same pin list. The list contains two macro names. The * actual macro definitions are changed depending on which pass is being done. - * */ // first pass - put the name strings into FLASH @@ -45,7 +44,7 @@ #line 46 // manually add pins that have names that are macros which don't play well with these macros -#if (AVR_ATmega2560_FAMILY || AVR_ATmega1284_FAMILY || defined(ARDUINO_ARCH_SAM) || defined(TARGET_LPC1768)) +#if ANY(AVR_ATmega2560_FAMILY, AVR_ATmega1284_FAMILY, ARDUINO_ARCH_SAM, TARGET_LPC1768) #if SERIAL_PORT == 0 static const char RXD_NAME_0[] PROGMEM = { "RXD0" }; static const char TXD_NAME_0[] PROGMEM = { "TXD0" }; @@ -110,83 +109,119 @@ const PinInfo pin_array[] PROGMEM = { // manually add pins ... #if SERIAL_PORT == 0 - #if (AVR_ATmega2560_FAMILY || defined(ARDUINO_ARCH_SAM)) + #if EITHER(AVR_ATmega2560_FAMILY, ARDUINO_ARCH_SAM) { RXD_NAME_0, 0, true }, { TXD_NAME_0, 1, true }, #elif AVR_ATmega1284_FAMILY { RXD_NAME_0, 8, true }, { TXD_NAME_0, 9, true }, - #elif defined(TARGET_LPC1768) + #elif defined(TARGET_LPC1768) // TX P0_02 RX P0_03 { RXD_NAME_0, 3, true }, { TXD_NAME_0, 2, true }, #endif #elif SERIAL_PORT == 1 - #if (AVR_ATmega2560_FAMILY || defined(ARDUINO_ARCH_SAM)) + #if EITHER(AVR_ATmega2560_FAMILY, ARDUINO_ARCH_SAM) { RXD_NAME_1, 19, true }, { TXD_NAME_1, 18, true }, #elif AVR_ATmega1284_FAMILY { RXD_NAME_1, 10, true }, { TXD_NAME_1, 11, true }, #elif defined(TARGET_LPC1768) - { RXD_NAME_1, 16, true }, - { TXD_NAME_1, 15, true }, + #ifdef LPC_PINCFG_UART1_P2_00 // TX P2_00 RX P2_01 + { RXD_NAME_1, 0x41, true }, + { TXD_NAME_1, 0x40, true }, + #else // TX P0_15 RX P0_16 + { RXD_NAME_1, 16, true }, + { TXD_NAME_1, 15, true }, + #endif #endif #elif SERIAL_PORT == 2 - #if (AVR_ATmega2560_FAMILY || defined(ARDUINO_ARCH_SAM)) + #if EITHER(AVR_ATmega2560_FAMILY, ARDUINO_ARCH_SAM) { RXD_NAME_2, 17, true }, { TXD_NAME_2, 16, true }, #elif defined(TARGET_LPC1768) - { RXD_NAME_2, 11, true }, - { TXD_NAME_2, 10, true }, + #ifdef LPC_PINCFG_UART2_P2_08 // TX P2_08 RX P2_09 + { RXD_NAME_2, 0x49, true }, + { TXD_NAME_2, 0x48, true }, + #else // TX P0_10 RX P0_11 + { RXD_NAME_2, 11, true }, + { TXD_NAME_2, 10, true }, + #endif #endif #elif SERIAL_PORT == 3 - #if (AVR_ATmega2560_FAMILY || defined(ARDUINO_ARCH_SAM)) + #if EITHER(AVR_ATmega2560_FAMILY, ARDUINO_ARCH_SAM) { RXD_NAME_3, 15, true }, { TXD_NAME_3, 14, true }, #elif defined(TARGET_LPC1768) - { RXD_NAME_3, 1, true }, - { TXD_NAME_3, 0, true }, + #ifdef LPC_PINCFG_UART3_P0_25 // TX P0_25 RX P0_26 + { RXD_NAME_3, 0x1A, true }, + { TXD_NAME_3, 0x19, true }, + #elif defined(LPC_PINCFG_UART3_P4_28) // TX P4_28 RX P4_29 + { RXD_NAME_3, 0x9D, true }, + { TXD_NAME_3, 0x9C, true }, + #else // TX P0_00 RX P0_01 + { RXD_NAME_3, 1, true }, + { TXD_NAME_3, 0, true }, + #endif #endif #endif #ifdef SERIAL_PORT_2 #if SERIAL_PORT_2 == 0 - #if (AVR_ATmega2560_FAMILY || defined(ARDUINO_ARCH_SAM)) + #if EITHER(AVR_ATmega2560_FAMILY, ARDUINO_ARCH_SAM) { RXD_NAME_0, 0, true }, { TXD_NAME_0, 1, true }, #elif AVR_ATmega1284_FAMILY { RXD_NAME_0, 8, true }, { TXD_NAME_0, 9, true }, - #elif defined(TARGET_LPC1768) + #elif defined(TARGET_LPC1768) // TX P0_02 RX P0_03 { RXD_NAME_0, 3, true }, { TXD_NAME_0, 2, true }, #endif #elif SERIAL_PORT_2 == 1 - #if (AVR_ATmega2560_FAMILY || defined(ARDUINO_ARCH_SAM)) + #if EITHER(AVR_ATmega2560_FAMILY, ARDUINO_ARCH_SAM) { RXD_NAME_1, 19, true }, { TXD_NAME_1, 18, true }, #elif AVR_ATmega1284_FAMILY { RXD_NAME_1, 10, true }, { TXD_NAME_1, 11, true }, #elif defined(TARGET_LPC1768) - { RXD_NAME_1, 16, true }, - { TXD_NAME_1, 15, true }, + #ifdef LPC_PINCFG_UART1_P2_00 // TX P2_00 RX P2_01 + { RXD_NAME_1, 0x41, true }, + { TXD_NAME_1, 0x40, true }, + #else // TX P0_15 RX P0_16 + { RXD_NAME_1, 16, true }, + { TXD_NAME_1, 15, true }, + #endif #endif #elif SERIAL_PORT_2 == 2 - #if (AVR_ATmega2560_FAMILY || defined(ARDUINO_ARCH_SAM)) + #if EITHER(AVR_ATmega2560_FAMILY, ARDUINO_ARCH_SAM) { RXD_NAME_2, 17, true }, { TXD_NAME_2, 16, true }, #elif defined(TARGET_LPC1768) - { RXD_NAME_2, 11, true }, - { TXD_NAME_2, 10, true }, + #ifdef LPC_PINCFG_UART2_P2_08 // TX P2_08 RX P2_09 + { RXD_NAME_2, 0x49, true }, + { TXD_NAME_2, 0x48, true }, + #else // TX P0_10 RX P0_11 + { RXD_NAME_2, 11, true }, + { TXD_NAME_2, 10, true }, + #endif #endif #elif SERIAL_PORT_2 == 3 - #if (AVR_ATmega2560_FAMILY || defined(ARDUINO_ARCH_SAM)) + #if EITHER(AVR_ATmega2560_FAMILY, ARDUINO_ARCH_SAM) { RXD_NAME_3, 15, true }, { TXD_NAME_3, 14, true }, #elif defined(TARGET_LPC1768) - { RXD_NAME_3, 1, true }, - { TXD_NAME_3, 0, true }, + #ifdef LPC_PINCFG_UART3_P0_25 // TX P0_25 RX P0_26 + { RXD_NAME_3, 0x1A, true }, + { TXD_NAME_3, 0x19, true }, + #elif defined(LPC_PINCFG_UART3_P4_28) // TX P4_28 RX P4_29 + { RXD_NAME_3, 0x9D, true }, + { TXD_NAME_3, 0x9C, true }, + #else // TX P0_00 RX P0_01 + { RXD_NAME_3, 1, true }, + { TXD_NAME_3, 0, true }, + #endif #endif #endif #endif diff --git a/Marlin/src/pins/pinsDebug_list.h b/Marlin/src/pins/pinsDebug_list.h index ac15a3c9ba..704f2a487f 100644 --- a/Marlin/src/pins/pinsDebug_list.h +++ b/Marlin/src/pins/pinsDebug_list.h @@ -261,6 +261,9 @@ #if defined(TMC_SW_SCK) && TMC_SW_SCK >= 0 REPORT_NAME_DIGITAL(__LINE__, TMC_SW_SCK) #endif +#if defined(TFTGLCD_CS) && TFTGLCD_CS >= 0 + REPORT_NAME_DIGITAL(__LINE__, TFTGLCD_CS) +#endif #if PIN_EXISTS(E_MUX0) REPORT_NAME_DIGITAL(__LINE__, E_MUX0_PIN) #endif diff --git a/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h b/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h index e2a4940e87..2ea15c97d3 100644 --- a/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h +++ b/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h @@ -25,7 +25,7 @@ * Einsy-Rambo pin assignments */ -#ifndef __AVR_ATmega2560__ +#if NOT_TARGET(__AVR_ATmega2560__) #error "Oops! Select 'Arduino Mega 2560 or Rambo' in 'Tools > Board.'" #endif @@ -160,7 +160,7 @@ // // LCD / Controller // -#if HAS_SPI_LCD || TOUCH_UI_ULTIPANEL +#if HAS_WIRED_LCD || TOUCH_UI_ULTIPANEL #define KILL_PIN 32 @@ -188,4 +188,4 @@ #define SD_DETECT_PIN 15 #endif // ULTIPANEL || TOUCH_UI_ULTIPANEL -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/rambo/pins_EINSY_RETRO.h b/Marlin/src/pins/rambo/pins_EINSY_RETRO.h index 0df977a05b..4a1bf70b6e 100644 --- a/Marlin/src/pins/rambo/pins_EINSY_RETRO.h +++ b/Marlin/src/pins/rambo/pins_EINSY_RETRO.h @@ -25,7 +25,7 @@ * Einsy-Retro pin assignments */ -#ifndef __AVR_ATmega2560__ +#if NOT_TARGET(__AVR_ATmega2560__) #error "Oops! Select 'Arduino Mega 2560 or Rambo' in 'Tools > Board.'" #endif @@ -166,11 +166,11 @@ // // LCD / Controller // -#if HAS_SPI_LCD || TOUCH_UI_ULTIPANEL || ENABLED(TOUCH_UI_FTDI_EVE) +#if ANY(HAS_WIRED_LCD, TOUCH_UI_ULTIPANEL, TOUCH_UI_FTDI_EVE) #define KILL_PIN 32 - #if ENABLED(ULTIPANEL) || TOUCH_UI_ULTIPANEL || ENABLED(TOUCH_UI_FTDI_EVE) + #if ANY(ULTIPANEL, TOUCH_UI_ULTIPANEL, TOUCH_UI_FTDI_EVE) #if ENABLED(CR10_STOCKDISPLAY) #define LCD_PINS_RS 85 @@ -194,5 +194,6 @@ #define SD_DETECT_PIN 15 - #endif // ULTIPANEL || TOUCH_UI_ULTIPANEL -#endif // HAS_SPI_LCD + #endif // ULTIPANEL || TOUCH_UI_ULTIPANEL || TOUCH_UI_FTDI_EVE + +#endif // HAS_WIRED_LCD || TOUCH_UI_ULTIPANEL || TOUCH_UI_FTDI_EVE diff --git a/Marlin/src/pins/rambo/pins_MINIRAMBO.h b/Marlin/src/pins/rambo/pins_MINIRAMBO.h index f89bba2d7f..6314bc07b8 100644 --- a/Marlin/src/pins/rambo/pins_MINIRAMBO.h +++ b/Marlin/src/pins/rambo/pins_MINIRAMBO.h @@ -25,7 +25,7 @@ * Mini-RAMBo pin assignments */ -#ifndef __AVR_ATmega2560__ +#if NOT_TARGET(__AVR_ATmega2560__) #error "Oops! Select 'RAMBo' in 'Tools > Board' or the Mega2560 environment in PlatformIO." #endif @@ -141,7 +141,7 @@ // // LCD / Controller // -#if HAS_SPI_LCD || TOUCH_UI_ULTIPANEL +#if HAS_WIRED_LCD || TOUCH_UI_ULTIPANEL #if !MB(MINIRAMBO_10A) #define KILL_PIN 32 @@ -189,4 +189,4 @@ #endif // ULTIPANEL || TOUCH_UI_ULTIPANEL -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD || TOUCH_UI_ULTIPANEL diff --git a/Marlin/src/pins/rambo/pins_RAMBO.h b/Marlin/src/pins/rambo/pins_RAMBO.h index 5abf1f2d90..735852b2ff 100644 --- a/Marlin/src/pins/rambo/pins_RAMBO.h +++ b/Marlin/src/pins/rambo/pins_RAMBO.h @@ -41,7 +41,7 @@ * Rambo pin assignments */ -#ifndef __AVR_ATmega2560__ +#if NOT_TARGET(__AVR_ATmega2560__) #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" #endif @@ -183,7 +183,7 @@ // // LCD / Controller // -#if HAS_SPI_LCD || TOUCH_UI_ULTIPANEL +#if HAS_WIRED_LCD || TOUCH_UI_ULTIPANEL #define KILL_PIN 80 @@ -249,4 +249,4 @@ #endif // !NEWPANEL -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/rambo/pins_SCOOVO_X9H.h b/Marlin/src/pins/rambo/pins_SCOOVO_X9H.h index bba628f307..4af38e1de3 100644 --- a/Marlin/src/pins/rambo/pins_SCOOVO_X9H.h +++ b/Marlin/src/pins/rambo/pins_SCOOVO_X9H.h @@ -25,7 +25,7 @@ * Rambo pin assignments MODIFIED FOR Scoovo X9H ************************************************/ -#ifndef __AVR_ATmega2560__ +#if NOT_TARGET(__AVR_ATmega2560__) #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" #endif diff --git a/Marlin/src/pins/ramps/pins_3DRAG.h b/Marlin/src/pins/ramps/pins_3DRAG.h index 1989a1657f..f0057e1fc9 100644 --- a/Marlin/src/pins/ramps/pins_3DRAG.h +++ b/Marlin/src/pins/ramps/pins_3DRAG.h @@ -106,7 +106,7 @@ #define BEEPER_PIN 33 -#endif // HAS_SPI_LCD && NEWPANEL +#endif // ULTRA_LCD && NEWPANEL /** * M3/M4/M5 - Spindle/Laser Control diff --git a/Marlin/src/pins/ramps/pins_AZTEEG_X3.h b/Marlin/src/pins/ramps/pins_AZTEEG_X3.h index d142fb903e..e919b30cf9 100644 --- a/Marlin/src/pins/ramps/pins_AZTEEG_X3.h +++ b/Marlin/src/pins/ramps/pins_AZTEEG_X3.h @@ -25,7 +25,7 @@ * AZTEEG_X3 Arduino Mega with RAMPS v1.4 pin assignments */ -#ifndef __AVR_ATmega2560__ +#if NOT_TARGET(__AVR_ATmega2560__) #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" #elif HOTENDS > 2 || E_STEPPERS > 2 #error "Azteeg X3 supports up to 2 hotends / E-steppers. Comment out this line to continue." diff --git a/Marlin/src/pins/ramps/pins_AZTEEG_X3_PRO.h b/Marlin/src/pins/ramps/pins_AZTEEG_X3_PRO.h index 5eee450fc5..9ba6a0c1ac 100644 --- a/Marlin/src/pins/ramps/pins_AZTEEG_X3_PRO.h +++ b/Marlin/src/pins/ramps/pins_AZTEEG_X3_PRO.h @@ -25,7 +25,7 @@ * AZTEEG_X3_PRO (Arduino Mega) pin assignments */ -#ifndef __AVR_ATmega2560__ +#if NOT_TARGET(__AVR_ATmega2560__) #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" #elif HOTENDS > 5 || E_STEPPERS > 5 #error "Azteeg X3 Pro supports up to 5 hotends / E-steppers. Comment out this line to continue." diff --git a/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h b/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h index 1420aaaa56..967fec7b47 100644 --- a/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h +++ b/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h @@ -25,7 +25,7 @@ * bq ZUM Mega 3D board definition */ -#ifndef __AVR_ATmega2560__ +#if NOT_TARGET(__AVR_ATmega2560__) #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" #endif diff --git a/Marlin/src/pins/ramps/pins_DUPLICATOR_I3_PLUS.h b/Marlin/src/pins/ramps/pins_DUPLICATOR_I3_PLUS.h index de80851df0..87d24890c9 100644 --- a/Marlin/src/pins/ramps/pins_DUPLICATOR_I3_PLUS.h +++ b/Marlin/src/pins/ramps/pins_DUPLICATOR_I3_PLUS.h @@ -25,7 +25,7 @@ * Wanhao Duplicator i3 Plus pin assignments */ -#ifndef __AVR_ATmega2560__ +#if NOT_TARGET(__AVR_ATmega2560__) #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" #endif @@ -87,7 +87,7 @@ // // LCDs and Controllers // -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #if ENABLED(ZONESTAR_LCD) #define LCD_PINS_RS 2 #define LCD_PINS_ENABLE 36 diff --git a/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR.h b/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR.h index f1e6e6727c..0877d168d6 100644 --- a/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR.h +++ b/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR.h @@ -25,7 +25,7 @@ * Formbot Raptor pin assignments */ -#ifndef __AVR_ATmega2560__ +#if NOT_TARGET(__AVR_ATmega2560__) #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" #elif HOTENDS > 3 || E_STEPPERS > 3 #error "Formbot supports up to 3 hotends / E-steppers. Comment out this line to continue." diff --git a/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h b/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h index 4a9b9e1d59..75a219c177 100644 --- a/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h +++ b/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h @@ -25,7 +25,7 @@ * Formbot pin assignments */ -#ifndef __AVR_ATmega2560__ +#if NOT_TARGET(__AVR_ATmega2560__) #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" #elif HOTENDS > 2 || E_STEPPERS > 2 #error "Formbot supports up to 2 hotends / E-steppers. Comment out this line to continue." @@ -197,7 +197,7 @@ #define LCD_PINS_D7 29 #endif -#if HAS_GRAPHICAL_LCD +#if HAS_MARLINUI_U8GLIB #ifndef BOARD_ST7920_DELAY_1 #define BOARD_ST7920_DELAY_1 DELAY_NS(200) #endif diff --git a/Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h b/Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h index a804df4ed3..0470fc47e9 100644 --- a/Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h +++ b/Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h @@ -25,7 +25,7 @@ * Formbot pin assignments */ -#ifndef __AVR_ATmega2560__ +#if NOT_TARGET(__AVR_ATmega2560__) #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" #elif HOTENDS > 2 || E_STEPPERS > 2 #error "Formbot supports up to 2 hotends / E-steppers. Comment out this line to continue." diff --git a/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h b/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h index ffaa72d988..3fa3cc9e8c 100644 --- a/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h +++ b/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h @@ -25,7 +25,7 @@ // FYSETC F6 1.3 (and 1.4) pin assignments // -#ifndef __AVR_ATmega2560__ +#if NOT_TARGET(__AVR_ATmega2560__) #error "Oops! Select 'FYSETC F6' in 'Tools > Board.'" #endif @@ -261,7 +261,7 @@ #define NEOPIXEL_PIN 25 #endif - #elif HAS_GRAPHICAL_LCD + #elif HAS_MARLINUI_U8GLIB #define LCD_PINS_RS 16 #define LCD_PINS_ENABLE 17 diff --git a/Marlin/src/pins/ramps/pins_K8800.h b/Marlin/src/pins/ramps/pins_K8800.h index 2783f69896..7e8c245a41 100644 --- a/Marlin/src/pins/ramps/pins_K8800.h +++ b/Marlin/src/pins/ramps/pins_K8800.h @@ -25,7 +25,7 @@ * Velleman K8800 (Vertex) */ -#if !defined(__AVR_ATmega1280__) && !defined(__AVR_ATmega2560__) +#if NOT_TARGET(__AVR_ATmega1280__, __AVR_ATmega2560__) #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" #endif @@ -39,8 +39,13 @@ // #define X_STOP_PIN 3 #define Y_STOP_PIN 14 -#define Z_MIN_PIN 68 // Used for bed leveling -#define Z_MAX_PIN 66 +#define Z_STOP_PIN 66 + +#ifndef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN 68 +#endif + +#define FIL_RUNOUT_PIN 69 // PK7 // // Steppers @@ -61,10 +66,6 @@ #define E0_DIR_PIN 28 #define E0_ENABLE_PIN 24 -#define E1_STEP_PIN 32 -#define E1_DIR_PIN 34 -#define E1_ENABLE_PIN 30 - // // Temperature Sensors // @@ -80,30 +81,42 @@ // // Misc. Functions // -#define SDSS 25 - -#define FIL_RUNOUT_PIN 69 // PK7 #define KILL_PIN 20 // PD1 +#define CASE_LIGHT_PIN 7 // -// LCD / Controller +// SD Card // +#define SDSS 25 #define SD_DETECT_PIN 21 // PD0 -#define LCD_SDSS 53 + +// +// LCD / Controller +// #define BEEPER_PIN 6 -#define DOGLCD_CS 29 -#define DOGLCD_A0 27 +#if HAS_WIRED_LCD -#define LCD_PINS_RS 27 -#define LCD_PINS_ENABLE 29 -#define LCD_PINS_D4 37 -#define LCD_PINS_D5 35 -#define LCD_PINS_D6 33 -#define LCD_PINS_D7 31 + #define LCD_SDSS 53 -#if ENABLED(NEWPANEL) - #define BTN_EN1 17 - #define BTN_EN2 16 - #define BTN_ENC 23 -#endif + #define DOGLCD_CS 29 + #define DOGLCD_A0 27 + + #define LCD_PINS_RS 27 + #define LCD_PINS_ENABLE 29 + #define LCD_PINS_D4 37 + #define LCD_PINS_D5 35 + #define LCD_PINS_D6 33 + #define LCD_PINS_D7 31 + + #define LCD_CONTRAST_MIN 0 + #define LCD_CONTRAST_MAX 100 + #define DEFAULT_LCD_CONTRAST 30 + + #if ENABLED(NEWPANEL) + #define BTN_EN1 17 + #define BTN_EN2 16 + #define BTN_ENC 23 + #endif + +#endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/ramps/pins_MKS_GEN_L_V21.h b/Marlin/src/pins/ramps/pins_MKS_GEN_L_V21.h new file mode 100644 index 0000000000..24e04a39ff --- /dev/null +++ b/Marlin/src/pins/ramps/pins_MKS_GEN_L_V21.h @@ -0,0 +1,85 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * MKS GEN L V2 – Arduino Mega2560 with RAMPS v1.4 pin assignments + */ + +#if HOTENDS > 2 || E_STEPPERS > 2 + #error "MKS GEN L V2.1 supports up to 2 hotends / E-steppers. Comment out this line to continue." +#endif + +#define BOARD_INFO_NAME "MKS GEN L V2.1" + +// +// Heaters / Fans +// +// Power outputs EFBF or EFBE +#define MOSFET_D_PIN 7 + +// +// CS Pins wired to avoid conflict with the LCD +// See https://www.thingiverse.com/asset:66604 +// + +#ifndef X_CS_PIN + #define X_CS_PIN 63 +#endif +#ifndef Y_CS_PIN + #define Y_CS_PIN 64 +#endif +#ifndef Z_CS_PIN + #define Z_CS_PIN 65 +#endif +#ifndef E0_CS_PIN + #define E0_CS_PIN 66 +#endif +#ifndef E1_CS_PIN + #define E1_CS_PIN 12 +#endif + +// TMC2130 Diag Pins (currently just for reference) +#define X_DIAG_PIN 3 +#define Y_DIAG_PIN 14 +#define Z_DIAG_PIN 18 +#define E0_DIAG_PIN 2 +#define E1_DIAG_PIN 15 + +#ifndef SERVO1_PIN + #define SERVO1_PIN 21 +#endif +#ifndef SERVO2_PIN + #define SERVO2_PIN 39 +#endif +#ifndef SERVO3_PIN + #define SERVO3_PIN 32 +#endif + +#ifndef E1_SERIAL_TX_PIN + #define E1_SERIAL_TX_PIN 20 +#endif +#ifndef E1_SERIAL_RX_PIN + #define E1_SERIAL_RX_PIN 12 +#endif + +#include "pins_RAMPS.h" diff --git a/Marlin/src/pins/ramps/pins_RAMPS.h b/Marlin/src/pins/ramps/pins_RAMPS.h index e32c79afa9..de56d2b59d 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS.h +++ b/Marlin/src/pins/ramps/pins_RAMPS.h @@ -51,12 +51,13 @@ #error "Oops! Set MOTHERBOARD to an STM32F1-based board when building for STM32F1." #endif -#if NONE(IS_RAMPS_SMART, IS_RAMPS_DUO, IS_RAMPS4DUE, TARGET_LPC1768) - #if !defined(__AVR_ATmega1280__) && !defined(__AVR_ATmega2560__) - #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" - #endif +#if NOT_TARGET(IS_RAMPS_SMART, IS_RAMPS_DUO, IS_RAMPS4DUE, TARGET_LPC1768, __AVR_ATmega1280__, __AVR_ATmega2560__) + #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" #endif +// Custom flags and defines for the build +//#define BOARD_CUSTOM_BUILD_FLAGS -D__FOO__ + #ifndef BOARD_INFO_NAME #define BOARD_INFO_NAME "RAMPS 1.4" #endif @@ -429,7 +430,7 @@ // LCDs and Controllers // ////////////////////////// -#if HAS_SPI_LCD +#if HAS_WIRED_LCD // // LCD Display output pins @@ -449,6 +450,10 @@ #define LCD_PINS_D6 44 #define LCD_PINS_D7 64 + #elif ENABLED(TFTGLCD_PANEL_SPI) + + #define TFTGLCD_CS 33 + #else #if ENABLED(CR10_STOCKDISPLAY) @@ -681,6 +686,10 @@ // Pins only defined for RAMPS_SMART currently + #elif IS_TFTGLCD_PANEL + + #define SD_DETECT_PIN 49 + #else // Beeper on AUX-4 @@ -705,7 +714,7 @@ #endif #endif // NEWPANEL -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD #if ENABLED(REPRAPWORLD_KEYPAD) && DISABLED(ADC_KEYPAD) #define SHIFT_OUT 40 diff --git a/Marlin/src/pins/ramps/pins_RAMPS_13.h b/Marlin/src/pins/ramps/pins_RAMPS_13.h index 032dd79c23..6e7c8cbab5 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS_13.h +++ b/Marlin/src/pins/ramps/pins_RAMPS_13.h @@ -31,7 +31,6 @@ * RAMPS_13_EFF (Extruder, Fan, Fan) * RAMPS_13_EEF (Extruder, Extruder, Fan) * RAMPS_13_SF (Spindle, Controller Fan) - * */ #ifndef BOARD_INFO_NAME diff --git a/Marlin/src/pins/ramps/pins_RAMPS_OLD.h b/Marlin/src/pins/ramps/pins_RAMPS_OLD.h index d154b2fdd0..6d2dad2314 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS_OLD.h +++ b/Marlin/src/pins/ramps/pins_RAMPS_OLD.h @@ -25,7 +25,7 @@ * Arduino Mega with RAMPS v1.0, v1.1, v1.2 pin assignments */ -#if !defined(__AVR_ATmega1280__) && !defined(__AVR_ATmega2560__) +#if NOT_TARGET(__AVR_ATmega1280__, __AVR_ATmega2560__) #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" #endif diff --git a/Marlin/src/pins/ramps/pins_RAMPS_PLUS.h b/Marlin/src/pins/ramps/pins_RAMPS_PLUS.h index bdd53abbc0..9908d9494f 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS_PLUS.h +++ b/Marlin/src/pins/ramps/pins_RAMPS_PLUS.h @@ -35,10 +35,9 @@ * RAMPS_PLUS_EFF (Extruder, Fan, Fan) * RAMPS_PLUS_EEF (Extruder, Extruder, Fan) * RAMPS_PLUS_SF (Spindle, Controller Fan) - * */ -#if !defined(__AVR_ATmega1280__) && !defined(__AVR_ATmega2560__) +#if NOT_TARGET(__AVR_ATmega1280__, __AVR_ATmega2560__) #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" #endif diff --git a/Marlin/src/pins/ramps/pins_RUMBA.h b/Marlin/src/pins/ramps/pins_RUMBA.h index 5b4f830328..5be2896e18 100644 --- a/Marlin/src/pins/ramps/pins_RUMBA.h +++ b/Marlin/src/pins/ramps/pins_RUMBA.h @@ -25,7 +25,7 @@ * RUMBA pin assignments */ -#ifndef __AVR_ATmega2560__ +#if NOT_TARGET(__AVR_ATmega2560__) #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" #elif HOTENDS > 3 || E_STEPPERS > 3 #error "RUMBA supports up to 3 hotends / E-steppers. Comment out this line to continue." diff --git a/Marlin/src/pins/ramps/pins_TENLOG_D3_HERO.h b/Marlin/src/pins/ramps/pins_TENLOG_D3_HERO.h index 98a20fb3fd..e7a59a69df 100644 --- a/Marlin/src/pins/ramps/pins_TENLOG_D3_HERO.h +++ b/Marlin/src/pins/ramps/pins_TENLOG_D3_HERO.h @@ -25,7 +25,7 @@ * Tenlog pin assignments */ -#ifndef __AVR_ATmega2560__ +#if NOT_TARGET(__AVR_ATmega2560__) #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" #elif HOTENDS > 2 || E_STEPPERS > 2 #error "Tenlog supports up to 2 hotends / E-steppers. Comment out this line to continue." diff --git a/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h b/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h index 708f8fa26c..1c2cb60957 100644 --- a/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h +++ b/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h @@ -64,7 +64,7 @@ #elif TEMP_SENSOR_BED // EFB (Anycubic Kossel default) #define RAMPS_D9_PIN TG_FAN0_PIN - #if ENABLED(ANYCUBIC_CHIRON) + #if ENABLED(ANYCUBIC_LCD_CHIRON) #define RAMPS_D8_PIN TG_HEATER_1_PIN // Heated bed is connected to HEATER1 output #else #define RAMPS_D8_PIN TG_HEATER_BED_PIN @@ -84,7 +84,7 @@ #define E0_AUTO_FAN_PIN TG_FAN2_PIN // Used in Anycubic Kossel example config #endif -#if ENABLED(ANYCUBIC_I3MEGA) +#if ENABLED(ANYCUBIC_LCD_I3MEGA) #define CONTROLLER_FAN_PIN TG_FAN1_PIN #endif @@ -105,14 +105,14 @@ #if ENABLED(ANYCUBIC_4_MAX_PRO_ENDSTOPS) #define X_MAX_PIN 43 #define Y_STOP_PIN 19 -#elif EITHER(ANYCUBIC_CHIRON, ANYCUBIC_I3MEGA) +#elif EITHER(ANYCUBIC_LCD_CHIRON, ANYCUBIC_LCD_I3MEGA) #define Y_STOP_PIN 42 #define Z2_MIN_PIN 43 #ifndef Z_MIN_PROBE_PIN #define Z_MIN_PROBE_PIN 2 #endif #ifndef FIL_RUNOUT_PIN - #if ENABLED(ANYCUBIC_CHIRON) + #if ENABLED(ANYCUBIC_LCD_CHIRON) #define FIL_RUNOUT_PIN 33 #else #define FIL_RUNOUT_PIN 19 @@ -128,7 +128,7 @@ // AnyCubic made the following changes to 1.1.0-RC8 // If these are appropriate for your LCD let us know. // -#if 0 && HAS_SPI_LCD +#if 0 && HAS_WIRED_LCD // LCD Display output pins #if BOTH(NEWPANEL, PANEL_ONE) @@ -154,4 +154,4 @@ #define DOGLCD_A0 42 #endif -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/ramps/pins_TRONXY_V3_1_0.h b/Marlin/src/pins/ramps/pins_TRONXY_V3_1_0.h index d02a063e80..f342eff8aa 100644 --- a/Marlin/src/pins/ramps/pins_TRONXY_V3_1_0.h +++ b/Marlin/src/pins/ramps/pins_TRONXY_V3_1_0.h @@ -25,7 +25,7 @@ * Arduino Mega for Tronxy X5S-2E, etc. */ -#ifndef __AVR_ATmega2560__ +#if NOT_TARGET(__AVR_ATmega2560__) #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" #elif HOTENDS > 2 || E_STEPPERS > 2 #error "TRONXY-V3-1.0 supports only 2 hotends/E-steppers. Comment out this line to continue." diff --git a/Marlin/src/pins/ramps/pins_TT_OSCAR.h b/Marlin/src/pins/ramps/pins_TT_OSCAR.h index ab3dc1a32b..1568288e69 100644 --- a/Marlin/src/pins/ramps/pins_TT_OSCAR.h +++ b/Marlin/src/pins/ramps/pins_TT_OSCAR.h @@ -20,7 +20,7 @@ * */ -#if !defined(__AVR_ATmega1280__) && !defined(__AVR_ATmega2560__) +#if NOT_TARGET(__AVR_ATmega1280__, __AVR_ATmega2560__) #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" #endif @@ -271,7 +271,7 @@ // LCDs and Controllers // ////////////////////////// -#if HAS_SPI_LCD +#if HAS_WIRED_LCD // // LCD Display output pins diff --git a/Marlin/src/pins/ramps/pins_ULTIMAIN_2.h b/Marlin/src/pins/ramps/pins_ULTIMAIN_2.h index cbf9523eac..c6251ae817 100644 --- a/Marlin/src/pins/ramps/pins_ULTIMAIN_2.h +++ b/Marlin/src/pins/ramps/pins_ULTIMAIN_2.h @@ -33,7 +33,7 @@ * case light */ -#ifndef __AVR_ATmega2560__ +#if NOT_TARGET(__AVR_ATmega2560__) #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" #endif diff --git a/Marlin/src/pins/ramps/pins_ULTIMAKER.h b/Marlin/src/pins/ramps/pins_ULTIMAKER.h index f316fad778..597a37bdbc 100644 --- a/Marlin/src/pins/ramps/pins_ULTIMAKER.h +++ b/Marlin/src/pins/ramps/pins_ULTIMAKER.h @@ -33,7 +33,7 @@ * case light */ -#if !defined(__AVR_ATmega1280__) && !defined(__AVR_ATmega2560__) +#if NOT_TARGET(__AVR_ATmega1280__, __AVR_ATmega2560__) #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" #endif @@ -119,7 +119,7 @@ // // LCD / Controller // -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #define BEEPER_PIN 18 @@ -158,7 +158,7 @@ #endif // !NEWPANEL -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD // // M3/M4/M5 - Spindle/Laser Control diff --git a/Marlin/src/pins/ramps/pins_ULTIMAKER_OLD.h b/Marlin/src/pins/ramps/pins_ULTIMAKER_OLD.h index a44baf26e4..c5bbd02bf5 100644 --- a/Marlin/src/pins/ramps/pins_ULTIMAKER_OLD.h +++ b/Marlin/src/pins/ramps/pins_ULTIMAKER_OLD.h @@ -60,7 +60,7 @@ //#define BOARD_REV_1_0 //#define BOARD_REV_1_5 -#if !defined(__AVR_ATmega1280__) && !defined(__AVR_ATmega2560__) +#if NOT_TARGET(__AVR_ATmega1280__, __AVR_ATmega2560__) #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" #endif diff --git a/Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h b/Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h index 4bf63f348f..096d970871 100644 --- a/Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h +++ b/Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h @@ -25,7 +25,7 @@ * Z-Bolt X Series board – based on Arduino Mega2560 */ -#ifndef __AVR_ATmega2560__ +#if NOT_TARGET(__AVR_ATmega2560__) #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" #elif HOTENDS > 4 || E_STEPPERS > 4 #error "Z-Bolt X Series board supports up to 4 hotends / E-steppers." diff --git a/Marlin/src/pins/sam/pins_ADSK.h b/Marlin/src/pins/sam/pins_ADSK.h index 289fa462cc..b0e171cf17 100644 --- a/Marlin/src/pins/sam/pins_ADSK.h +++ b/Marlin/src/pins/sam/pins_ADSK.h @@ -27,7 +27,7 @@ #define BOARD_INFO_NAME "ADSK" -#if !defined(__SAM3X8E__) && !defined(__AVR_ATmega1280__) && !defined(__AVR_ATmega2560__) +#if NOT_TARGET(__SAM3X8E__, __AVR_ATmega1280__, __AVR_ATmega2560__) #error "Oops! Select 'Arduino Due or Mega' in 'Tools > Board.'" #endif @@ -204,5 +204,4 @@ A stepper for E0 extruder * * Standard ethernet pairs: 1&2, 3&6, 4&5, 7&8 * Use CAT7 cable to have all pairs shielded - * */ diff --git a/Marlin/src/pins/sam/pins_ALLIGATOR_R2.h b/Marlin/src/pins/sam/pins_ALLIGATOR_R2.h index 7cd81456b1..8d6906117d 100644 --- a/Marlin/src/pins/sam/pins_ALLIGATOR_R2.h +++ b/Marlin/src/pins/sam/pins_ALLIGATOR_R2.h @@ -26,7 +26,7 @@ * https://reprap.org/wiki/Alligator_Board */ -#ifndef __SAM3X8E__ +#if NOT_TARGET(__SAM3X8E__) #error "Oops! Select 'Arduino Due' in 'Tools > Board.'" #endif @@ -144,17 +144,16 @@ // LCD / Controller // #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) - #define LCD_PINS_RS 18 #define LCD_PINS_ENABLE 15 #define LCD_PINS_D4 19 #define BEEPER_PIN 64 + #undef UI_VOLTAGE_LEVEL + #define UI_VOLTAGE_LEVEL 1 +#endif +#if ENABLED(NEWPANEL) #define BTN_EN1 14 #define BTN_EN2 16 #define BTN_ENC 17 - - #undef UI_VOLTAGE_LEVEL - #define UI_VOLTAGE_LEVEL 1 - -#endif // REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER +#endif diff --git a/Marlin/src/pins/sam/pins_ARCHIM1.h b/Marlin/src/pins/sam/pins_ARCHIM1.h index 134049781a..6e3768c663 100644 --- a/Marlin/src/pins/sam/pins_ARCHIM1.h +++ b/Marlin/src/pins/sam/pins_ARCHIM1.h @@ -37,7 +37,7 @@ * https://github.com/ultimachine/Archim/wiki */ -#ifndef __SAM3X8E__ +#if NOT_TARGET(__SAM3X8E__) #error "Oops! Select 'Archim' in 'Tools > Board.'" #endif @@ -181,7 +181,7 @@ // // LCD / Controller // -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #define BEEPER_PIN 23 // D24 PA15_CTS1 #define LCD_PINS_RS 17 // D17 PA12_RXD1 #define LCD_PINS_ENABLE 24 // D23 PA14_RTS1 @@ -198,4 +198,4 @@ #define BTN_EN2 13 // D13 PB27_TIOB0 #define BTN_ENC 16 // D16 PA13_TXD1 #endif // NEWPANEL -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/sam/pins_ARCHIM2.h b/Marlin/src/pins/sam/pins_ARCHIM2.h index bbd4804dbd..5a3fe0e4d5 100644 --- a/Marlin/src/pins/sam/pins_ARCHIM2.h +++ b/Marlin/src/pins/sam/pins_ARCHIM2.h @@ -37,7 +37,7 @@ * https://github.com/ultimachine/Archim/wiki */ -#ifndef __SAM3X8E__ +#if NOT_TARGET(__SAM3X8E__) #error "Oops! Select 'Archim' in 'Tools > Board.'" #elif DISABLED(TMC_USE_SW_SPI) #error "Archim2 requires Software SPI. Enable TMC_USE_SW_SPI in Configuration_adv.h." @@ -237,7 +237,7 @@ // // LCD / Controller // -#if HAS_SPI_LCD || TOUCH_UI_ULTIPANEL || ENABLED(TOUCH_UI_FTDI_EVE) +#if ANY(HAS_WIRED_LCD, TOUCH_UI_ULTIPANEL, TOUCH_UI_FTDI_EVE) #define BEEPER_PIN 23 // D24 PA15_CTS1 #define LCD_PINS_RS 17 // D17 PA12_RXD1 #define LCD_PINS_ENABLE 24 // D23 PA14_RTS1 @@ -248,10 +248,10 @@ #define SD_DETECT_PIN 2 // D2 PB25_TIOA0 - #if ENABLED(ULTIPANEL) || TOUCH_UI_ULTIPANEL || ENABLED(TOUCH_UI_FTDI_EVE) + #if ANY(ULTIPANEL, TOUCH_UI_ULTIPANEL, TOUCH_UI_FTDI_EVE) // Buttons on AUX-2 #define BTN_EN1 60 // D60 PA3_TIOB1 #define BTN_EN2 13 // D13 PB27_TIOB0 #define BTN_ENC 16 // D16 PA13_TXD1 // the click - #endif // ULTIPANEL || TOUCH_UI_ULTIPANEL -#endif // HAS_SPI_LCD + #endif +#endif diff --git a/Marlin/src/pins/sam/pins_CNCONTROLS_15D.h b/Marlin/src/pins/sam/pins_CNCONTROLS_15D.h index a2094bee4d..fcd2bb4c67 100644 --- a/Marlin/src/pins/sam/pins_CNCONTROLS_15D.h +++ b/Marlin/src/pins/sam/pins_CNCONTROLS_15D.h @@ -24,7 +24,7 @@ * CNControls V15 for HMS434 with DUE pin assignments */ -#ifndef __SAM3X8E__ +#if NOT_TARGET(__SAM3X8E__) #error "Oops! Select 'Arduino Due' in 'Tools > Board.'" #endif diff --git a/Marlin/src/pins/sam/pins_DUE3DOM.h b/Marlin/src/pins/sam/pins_DUE3DOM.h index e0a56137f7..cd4033aa6f 100644 --- a/Marlin/src/pins/sam/pins_DUE3DOM.h +++ b/Marlin/src/pins/sam/pins_DUE3DOM.h @@ -25,7 +25,7 @@ * DUE3DOM pin assignments */ -#ifndef __SAM3X8E__ +#if NOT_TARGET(__SAM3X8E__) #error "Oops! Select 'Arduino Due' in 'Tools > Board.'" #endif @@ -113,7 +113,7 @@ // // LCD / Controller // -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #define LCD_PINS_RS 42 #define LCD_PINS_ENABLE 43 @@ -147,7 +147,7 @@ #define SDSS 4 #define SD_DETECT_PIN 14 - #elif HAS_SSD1306_OLED_I2C + #elif HAS_U8GLIB_I2C_OLED #define BTN_EN1 50 #define BTN_EN2 52 @@ -168,4 +168,4 @@ #define BEEPER_PIN -1 #endif // SPARK_FULL_GRAPHICS -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/sam/pins_DUE3DOM_MINI.h b/Marlin/src/pins/sam/pins_DUE3DOM_MINI.h index 9a488e3126..5f9ad48a08 100644 --- a/Marlin/src/pins/sam/pins_DUE3DOM_MINI.h +++ b/Marlin/src/pins/sam/pins_DUE3DOM_MINI.h @@ -25,7 +25,7 @@ * DUE3DOM MINI pin assignments */ -#ifndef __SAM3X8E__ +#if NOT_TARGET(__SAM3X8E__) #error "Oops! Select 'Arduino Due' in 'Tools > Board.'" #endif @@ -105,7 +105,7 @@ // // LCD / Controller // -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #define LCD_PINS_RS 42 #define LCD_PINS_ENABLE 43 @@ -139,7 +139,7 @@ #define SDSS 4 #define SD_DETECT_PIN 14 - #elif HAS_SSD1306_OLED_I2C + #elif HAS_U8GLIB_I2C_OLED #define BTN_EN1 50 #define BTN_EN2 52 @@ -171,4 +171,4 @@ #define DOGLCD_CS 45 #endif // SPARK_FULL_GRAPHICS -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/sam/pins_PRINTRBOARD_G2.h b/Marlin/src/pins/sam/pins_PRINTRBOARD_G2.h index be6b0fb2ed..22edb70213 100644 --- a/Marlin/src/pins/sam/pins_PRINTRBOARD_G2.h +++ b/Marlin/src/pins/sam/pins_PRINTRBOARD_G2.h @@ -25,7 +25,7 @@ * PRINTRBOARD_G2 */ -#ifndef __SAM3X8E__ +#if NOT_TARGET(__SAM3X8E__) #error "Oops! Select 'Arduino Due' in 'Tools > Board.'" #endif @@ -170,5 +170,4 @@ * None of these are in the arduino_due_x variant so digitalWrite and digitalRead can't be used on them. * * They can be accessed via FASTIO functions WRITE, READ, OUT_WRITE, OUTPUT, ... - * */ diff --git a/Marlin/src/pins/sam/pins_RADDS.h b/Marlin/src/pins/sam/pins_RADDS.h index a0192aadb6..60fe351237 100644 --- a/Marlin/src/pins/sam/pins_RADDS.h +++ b/Marlin/src/pins/sam/pins_RADDS.h @@ -25,7 +25,7 @@ * RADDS */ -#ifndef __SAM3X8E__ +#if NOT_TARGET(__SAM3X8E__) #error "Oops! Select 'Arduino Due' in 'Tools > Board.'" #endif @@ -226,7 +226,7 @@ // // LCD / Controller // -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #if ENABLED(RADDS_DISPLAY) @@ -266,7 +266,7 @@ #define SDSS 10 #define SD_DETECT_PIN 14 - #elif HAS_SSD1306_OLED_I2C + #elif HAS_U8GLIB_I2C_OLED #define BTN_EN1 50 #define BTN_EN2 52 @@ -287,7 +287,7 @@ #endif // SPARK_FULL_GRAPHICS -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD #ifndef SDSS #define SDSS 4 diff --git a/Marlin/src/pins/sam/pins_RAMPS4DUE.h b/Marlin/src/pins/sam/pins_RAMPS4DUE.h index 2bd894f9ae..54548333b5 100644 --- a/Marlin/src/pins/sam/pins_RAMPS4DUE.h +++ b/Marlin/src/pins/sam/pins_RAMPS4DUE.h @@ -39,7 +39,7 @@ * A15 | NC */ -#if !defined(__SAM3X8E__) && !defined(__AVR_ATmega2560__) +#if NOT_TARGET(__SAM3X8E__, __AVR_ATmega2560__) #error "Oops! Select 'Arduino Due' or 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" #endif diff --git a/Marlin/src/pins/sam/pins_RAMPS_DUO.h b/Marlin/src/pins/sam/pins_RAMPS_DUO.h index 5f8864ab14..bfc3968ffa 100644 --- a/Marlin/src/pins/sam/pins_RAMPS_DUO.h +++ b/Marlin/src/pins/sam/pins_RAMPS_DUO.h @@ -43,7 +43,7 @@ * A15 | A11 */ -#if !defined(__SAM3X8E__) && !defined(__AVR_ATmega2560__) +#if NOT_TARGET(__SAM3X8E__, __AVR_ATmega2560__) #error "Oops! Select 'Arduino Due' or 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" #endif @@ -76,7 +76,7 @@ // // LCD / Controller // -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #if BOTH(NEWPANEL, PANEL_ONE) #undef LCD_PINS_D4 @@ -129,4 +129,4 @@ #endif // NEWPANEL -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/sam/pins_RAMPS_FD_V1.h b/Marlin/src/pins/sam/pins_RAMPS_FD_V1.h index eb9889607d..ee525eefaa 100644 --- a/Marlin/src/pins/sam/pins_RAMPS_FD_V1.h +++ b/Marlin/src/pins/sam/pins_RAMPS_FD_V1.h @@ -28,7 +28,7 @@ * Use 4k7 thermistor tables */ -#ifndef __SAM3X8E__ +#if NOT_TARGET(__SAM3X8E__) #error "Oops! Select 'Arduino Due' in 'Tools > Board.'" #endif @@ -139,7 +139,7 @@ // // LCD / Controller // -#if HAS_SPI_LCD +#if HAS_WIRED_LCD // ramps-fd lcd adaptor #define BEEPER_PIN 37 @@ -203,7 +203,7 @@ #define DOGLCD_MISO 74 // MISO_PIN #endif -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD #if HAS_TMC_UART /** diff --git a/Marlin/src/pins/sam/pins_RAMPS_SMART.h b/Marlin/src/pins/sam/pins_RAMPS_SMART.h index 06eee2d970..9b76ee290b 100644 --- a/Marlin/src/pins/sam/pins_RAMPS_SMART.h +++ b/Marlin/src/pins/sam/pins_RAMPS_SMART.h @@ -60,7 +60,7 @@ * (Search the web for "Arduino DUE Board Pinout" to see the correct header.) */ -#ifndef __SAM3X8E__ +#if NOT_TARGET(__SAM3X8E__) #error "Oops! Select 'Arduino Due' in 'Tools > Board.'" #endif diff --git a/Marlin/src/pins/sam/pins_RURAMPS4D_11.h b/Marlin/src/pins/sam/pins_RURAMPS4D_11.h index dd490e3893..b9e61fb27c 100644 --- a/Marlin/src/pins/sam/pins_RURAMPS4D_11.h +++ b/Marlin/src/pins/sam/pins_RURAMPS4D_11.h @@ -32,7 +32,7 @@ * | */ -#ifndef __SAM3X8E__ +#if NOT_TARGET(__SAM3X8E__) #error "Oops! Select 'Arduino Due' in 'Tools > Board.'" #endif @@ -200,7 +200,7 @@ // // LCD / Controller // -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #if ANY(RADDS_DISPLAY, REPRAP_DISCOUNT_SMART_CONTROLLER, REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define BEEPER_PIN 62 @@ -221,7 +221,7 @@ #define LCD_PINS_RS 52 #define LCD_PINS_ENABLE 53 - #elif HAS_SSD1306_OLED_I2C + #elif HAS_U8GLIB_I2C_OLED #define BEEPER_PIN 62 #define LCD_SDSS 10 @@ -271,4 +271,4 @@ #define BTN_ENC 40 #endif -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/sam/pins_RURAMPS4D_13.h b/Marlin/src/pins/sam/pins_RURAMPS4D_13.h index 8a6287fb65..dc0c127995 100644 --- a/Marlin/src/pins/sam/pins_RURAMPS4D_13.h +++ b/Marlin/src/pins/sam/pins_RURAMPS4D_13.h @@ -32,7 +32,7 @@ * | */ -#ifndef __SAM3X8E__ +#if NOT_TARGET(__SAM3X8E__) #error "Oops! Select 'Arduino Due' in 'Tools > Board.'" #endif @@ -186,7 +186,7 @@ // // LCD / Controller // -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #if ANY(RADDS_DISPLAY, REPRAP_DISCOUNT_SMART_CONTROLLER, REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define BEEPER_PIN 62 @@ -207,7 +207,7 @@ #define LCD_PINS_RS 52 #define LCD_PINS_ENABLE 53 - #elif HAS_SSD1306_OLED_I2C + #elif HAS_U8GLIB_I2C_OLED #define BEEPER_PIN 62 #define LCD_SDSS 10 @@ -253,4 +253,4 @@ #define BTN_ENC 40 #endif -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/sam/pins_ULTRATRONICS_PRO.h b/Marlin/src/pins/sam/pins_ULTRATRONICS_PRO.h index 671307bc00..0b91ba61d6 100644 --- a/Marlin/src/pins/sam/pins_ULTRATRONICS_PRO.h +++ b/Marlin/src/pins/sam/pins_ULTRATRONICS_PRO.h @@ -23,9 +23,10 @@ /** * ReprapWorld ULTRATRONICS v1.0 + * https://reprapworld.com/documentation/datasheet_ultratronics10_05.pdf */ -#ifndef ARDUINO_ARCH_SAM +#if NOT_TARGET(ARDUINO_ARCH_SAM) #error "Oops! Select 'Arduino Due' in 'Tools > Board.'" #endif @@ -146,6 +147,10 @@ #define SPI_EEPROM2_CS -1 #define SPI_FLASH_CS -1 +#define SCK_PIN 76 +#define MISO_PIN 74 +#define MOSI_PIN 75 + // SPI for Max6675 or Max31855 Thermocouple #define MAX6675_SS_PIN 65 #define MAX31855_SS0 65 diff --git a/Marlin/src/pins/samd/pins_RAMPS_144.h b/Marlin/src/pins/samd/pins_RAMPS_144.h index 93e758b3ae..6076be07e9 100644 --- a/Marlin/src/pins/samd/pins_RAMPS_144.h +++ b/Marlin/src/pins/samd/pins_RAMPS_144.h @@ -25,7 +25,7 @@ * AGCM4 with RAMPS v1.4.4 pin assignments */ -#ifndef ARDUINO_GRAND_CENTRAL_M4 +#if NOT_TARGET(ARDUINO_GRAND_CENTRAL_M4) #error "Oops! Select 'Adafruit Grand Central M4' in 'Tools > Board.'" #endif @@ -287,7 +287,7 @@ // LCDs and Controllers // ////////////////////////// -#if HAS_SPI_LCD +#if HAS_WIRED_LCD // // LCD Display output pins @@ -594,7 +594,7 @@ #endif #endif // NEWPANEL -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD // // SD Support diff --git a/Marlin/src/pins/sanguino/pins_ANET_10.h b/Marlin/src/pins/sanguino/pins_ANET_10.h index a2ef1e2c17..74692a21a3 100644 --- a/Marlin/src/pins/sanguino/pins_ANET_10.h +++ b/Marlin/src/pins/sanguino/pins_ANET_10.h @@ -30,7 +30,6 @@ * * 1) no longer uses Sanguino files to define some of the pins * 2) added pointers to useable Arduino IDE extensions - * */ /** @@ -48,7 +47,6 @@ * "Anet V1.0 (Optiboot)" frees up another 3K of FLASH. You'll need to burn * a new bootloader to the board to be able to automatically download a * compiled image. - * */ /** @@ -66,7 +64,6 @@ * Just use the above JSON URL instead of Sparkfun's JSON. * * Once installed select the Sanguino board and then select the CPU. - * */ /** @@ -89,7 +86,7 @@ * Many thanks to Hans Raaf (@oderwat) for developing the Anet-specific software and supporting the Anet community. */ -#ifndef __AVR_ATmega1284P__ +#if NOT_TARGET(__AVR_ATmega1284P__) #error "Oops! Select 'Sanguino' in 'Tools > Board' and 'ATmega1284P' in 'Tools > Processor.' (For PlatformIO, use 'melzi' or 'melzi_optiboot.')" #endif @@ -152,7 +149,7 @@ * REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER */ -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #define LCD_SDSS 28 #if ENABLED(ADC_KEYPAD) #define SERVO0_PIN 27 // free for BLTouch/3D-Touch @@ -163,7 +160,7 @@ #define LCD_PINS_D6 16 #define LCD_PINS_D7 17 #define ADC_KEYPAD_PIN 1 - #elif EITHER(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER, ANET_FULL_GRAPHICS_LCD) + #elif ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) // Pin definitions for the Anet A6 Full Graphics display and the RepRapDiscount Full Graphics // display using an adapter board // https://go.aisler.net/benlye/anet-lcd-adapter/pcb // See below for alternative pin definitions for use with https://www.thingiverse.com/thing:2103748 diff --git a/Marlin/src/pins/sanguino/pins_GEN3_MONOLITHIC.h b/Marlin/src/pins/sanguino/pins_GEN3_MONOLITHIC.h index 901e326742..29905c1089 100644 --- a/Marlin/src/pins/sanguino/pins_GEN3_MONOLITHIC.h +++ b/Marlin/src/pins/sanguino/pins_GEN3_MONOLITHIC.h @@ -29,7 +29,6 @@ * Rev B 26 DEC 2016 * * added pointer to a current Arduino IDE extension - * */ /** @@ -47,10 +46,9 @@ * Just use the above JSON URL instead of Sparkfun's JSON. * * Once installed select the Sanguino board and then select the CPU. - * */ -#ifndef __AVR_ATmega644P__ +#if NOT_TARGET(__AVR_ATmega644P__) #error "Oops! Select 'Sanguino' in 'Tools > Board.'" #endif diff --git a/Marlin/src/pins/sanguino/pins_GEN3_PLUS.h b/Marlin/src/pins/sanguino/pins_GEN3_PLUS.h index a28b4c039c..33fc233f7a 100644 --- a/Marlin/src/pins/sanguino/pins_GEN3_PLUS.h +++ b/Marlin/src/pins/sanguino/pins_GEN3_PLUS.h @@ -29,7 +29,6 @@ * Rev B 26 DEC 2016 * * added pointer to a current Arduino IDE extension - * */ /** @@ -47,10 +46,9 @@ * Just use the above JSON URL instead of Sparkfun's JSON. * * Once installed select the SANGUINO board and then select the CPU. - * */ -#if !defined(__AVR_ATmega644P__) && !defined(__AVR_ATmega1284P__) +#if NOT_TARGET(__AVR_ATmega644P__, __AVR_ATmega1284P__) #error "Oops! Select 'Sanguino' in 'Tools > Boards' and 'ATmega644P' or 'ATmega1284P' in 'Tools > Processor.'" #endif diff --git a/Marlin/src/pins/sanguino/pins_GEN6.h b/Marlin/src/pins/sanguino/pins_GEN6.h index ad54f3cd76..bfca8e90d9 100644 --- a/Marlin/src/pins/sanguino/pins_GEN6.h +++ b/Marlin/src/pins/sanguino/pins_GEN6.h @@ -31,7 +31,6 @@ * 1) added pointer to a current Arduino IDE extension * 2) added support for M3, M4 & M5 spindle control commands * 3) added case light pin definition - * */ /** @@ -49,10 +48,9 @@ * Just use the above JSON URL instead of Sparkfun's JSON. * * Once installed select the Sanguino board and then select the CPU. - * */ -#if !defined(__AVR_ATmega644P__) && !defined(__AVR_ATmega1284P__) +#if NOT_TARGET(__AVR_ATmega644P__, __AVR_ATmega1284P__) #error "Oops! Select 'Sanguino' in 'Tools > Boards' and 'ATmega644P' or 'ATmega1284P' in 'Tools > Processor.'" #endif diff --git a/Marlin/src/pins/sanguino/pins_GEN6_DELUXE.h b/Marlin/src/pins/sanguino/pins_GEN6_DELUXE.h index a40c2ec15f..9c63570620 100644 --- a/Marlin/src/pins/sanguino/pins_GEN6_DELUXE.h +++ b/Marlin/src/pins/sanguino/pins_GEN6_DELUXE.h @@ -29,7 +29,6 @@ * Rev B 26 DEC 2016 * * added pointer to a current Arduino IDE extension - * */ /** @@ -47,7 +46,6 @@ * Just use the above JSON URL instead of Sparkfun's JSON. * * Once installed select the SANGUINO board and then select the CPU. - * */ diff --git a/Marlin/src/pins/sanguino/pins_GEN7_12.h b/Marlin/src/pins/sanguino/pins_GEN7_12.h index 75b75cdc6f..9db7d7214a 100644 --- a/Marlin/src/pins/sanguino/pins_GEN7_12.h +++ b/Marlin/src/pins/sanguino/pins_GEN7_12.h @@ -31,7 +31,6 @@ * 1) added pointer to a current Arduino IDE extension * 2) added support for M3, M4 & M5 spindle control commands * 3) added case light pin definition - * */ /** @@ -49,10 +48,9 @@ * Just use the above JSON URL instead of Sparkfun's JSON. * * Once installed select the Sanguino board and then select the CPU. - * */ -#if !defined(__AVR_ATmega644P__) && !defined(__AVR_ATmega644__) && !defined(__AVR_ATmega1284P__) +#if NOT_TARGET(__AVR_ATmega644P__, __AVR_ATmega644__, __AVR_ATmega1284P__) #error "Oops! Select 'Sanguino' in 'Tools > Boards' and 'ATmega644', 'ATmega644P', or 'ATmega1284P' in 'Tools > Processor.'" #endif diff --git a/Marlin/src/pins/sanguino/pins_GEN7_13.h b/Marlin/src/pins/sanguino/pins_GEN7_13.h index 6743c8cf75..55881aaff5 100644 --- a/Marlin/src/pins/sanguino/pins_GEN7_13.h +++ b/Marlin/src/pins/sanguino/pins_GEN7_13.h @@ -29,7 +29,6 @@ * Rev B 26 DEC 2016 * * added pointer to a current Arduino IDE extension - * */ /** @@ -47,7 +46,6 @@ * Just use the above JSON URL instead of Sparkfun's JSON. * * Once installed select the Sanguino board and then select the CPU. - * */ #define BOARD_INFO_NAME "Gen7 v1.3" diff --git a/Marlin/src/pins/sanguino/pins_GEN7_14.h b/Marlin/src/pins/sanguino/pins_GEN7_14.h index af0d824151..66dba533e9 100644 --- a/Marlin/src/pins/sanguino/pins_GEN7_14.h +++ b/Marlin/src/pins/sanguino/pins_GEN7_14.h @@ -31,7 +31,6 @@ * 1) added pointer to a current Arduino IDE extension * 2) added support for M3, M4 & M5 spindle control commands * 3) added case light pin definition - * */ /** @@ -49,10 +48,9 @@ * Just use the above JSON URL instead of Sparkfun's JSON. * * Once installed select the Sanguino board and then select the CPU. - * */ -#if !defined(__AVR_ATmega644P__) && !defined(__AVR_ATmega644__) && !defined(__AVR_ATmega1284P__) +#if NOT_TARGET(__AVR_ATmega644P__, __AVR_ATmega644__, __AVR_ATmega1284P__) #error "Oops! Select 'Sanguino' in 'Tools > Boards' and 'ATmega644', 'ATmega644P', or 'ATmega1284P' in 'Tools > Processor.'" #endif diff --git a/Marlin/src/pins/sanguino/pins_GEN7_CUSTOM.h b/Marlin/src/pins/sanguino/pins_GEN7_CUSTOM.h index 27ec622fce..0c4871fb27 100644 --- a/Marlin/src/pins/sanguino/pins_GEN7_CUSTOM.h +++ b/Marlin/src/pins/sanguino/pins_GEN7_CUSTOM.h @@ -34,7 +34,6 @@ * 1) added pointer to a current Arduino IDE extension * 2) added support for M3, M4 & M5 spindle control commands * 3) added case light pin definition - * */ /** @@ -52,10 +51,9 @@ * Just use the above JSON URL instead of Sparkfun's JSON. * * Once installed select the Sanguino board and then select the CPU. - * */ -#if !defined(__AVR_ATmega644P__) && !defined(__AVR_ATmega644__) && !defined(__AVR_ATmega1284P__) +#if NOT_TARGET(__AVR_ATmega644P__, __AVR_ATmega644__, __AVR_ATmega1284P__) #error "Oops! Select 'Sanguino' in 'Tools > Boards' and 'ATmega644', 'ATmega644P', or 'ATmega1284P' in 'Tools > Processor.'" #endif diff --git a/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h b/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h index 4817ce8043..9f406c1f78 100644 --- a/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h +++ b/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h @@ -36,7 +36,7 @@ #define BOARD_INFO_NAME "Melzi (Creality)" // Alter timing for graphical display -#if HAS_GRAPHICAL_LCD +#if HAS_MARLINUI_U8GLIB #ifndef BOARD_ST7920_DELAY_1 #define BOARD_ST7920_DELAY_1 DELAY_NS(125) #endif diff --git a/Marlin/src/pins/sanguino/pins_MELZI_MALYAN.h b/Marlin/src/pins/sanguino/pins_MELZI_MALYAN.h index 8128fb86e6..5014620c6b 100644 --- a/Marlin/src/pins/sanguino/pins_MELZI_MALYAN.h +++ b/Marlin/src/pins/sanguino/pins_MELZI_MALYAN.h @@ -28,7 +28,7 @@ #define BOARD_INFO_NAME "Melzi (Malyan)" // Alter timing for graphical display -#if HAS_GRAPHICAL_LCD +#if HAS_MARLINUI_U8GLIB #ifndef BOARD_ST7920_DELAY_1 #define BOARD_ST7920_DELAY_1 DELAY_NS(125) #endif diff --git a/Marlin/src/pins/sanguino/pins_MELZI_TRONXY.h b/Marlin/src/pins/sanguino/pins_MELZI_TRONXY.h index 9e433f19c4..f878941037 100644 --- a/Marlin/src/pins/sanguino/pins_MELZI_TRONXY.h +++ b/Marlin/src/pins/sanguino/pins_MELZI_TRONXY.h @@ -27,7 +27,7 @@ #define BOARD_INFO_NAME "Melzi (Tronxy)" -#if HAS_GRAPHICAL_LCD +#if HAS_MARLINUI_U8GLIB #ifndef BOARD_ST7920_DELAY_1 #define BOARD_ST7920_DELAY_1 DELAY_NS(0) #endif diff --git a/Marlin/src/pins/sanguino/pins_MELZI_V2.h b/Marlin/src/pins/sanguino/pins_MELZI_V2.h index 1cdf51117f..275498d558 100644 --- a/Marlin/src/pins/sanguino/pins_MELZI_V2.h +++ b/Marlin/src/pins/sanguino/pins_MELZI_V2.h @@ -24,7 +24,7 @@ #define BOARD_INFO_NAME "Melzi V2" -#if HAS_GRAPHICAL_LCD +#if HAS_MARLINUI_U8GLIB #ifndef BOARD_ST7920_DELAY_1 #define BOARD_ST7920_DELAY_1 DELAY_NS(0) #endif diff --git a/Marlin/src/pins/sanguino/pins_OMCA.h b/Marlin/src/pins/sanguino/pins_OMCA.h index 8e4c6d2b64..7f18283d1c 100644 --- a/Marlin/src/pins/sanguino/pins_OMCA.h +++ b/Marlin/src/pins/sanguino/pins_OMCA.h @@ -56,7 +56,6 @@ * Rev B 26 DEC 2016 * * added pointer to a current Arduino IDE extension - * */ /** @@ -74,10 +73,9 @@ * Just use the above JSON URL instead of Sparkfun's JSON. * * Once installed select the Sanguino board and then select the CPU. - * */ -#if !defined(__AVR_ATmega644P__) && !defined(__AVR_ATmega644__) +#if NOT_TARGET(__AVR_ATmega644P__, __AVR_ATmega644__) #error "Oops! Select 'Sanguino' in 'Tools > Board' and 'ATmega644' or 'ATmega644P' in 'Tools > Processor.'" #endif diff --git a/Marlin/src/pins/sanguino/pins_OMCA_A.h b/Marlin/src/pins/sanguino/pins_OMCA_A.h index 922ef69b5e..7707320519 100644 --- a/Marlin/src/pins/sanguino/pins_OMCA_A.h +++ b/Marlin/src/pins/sanguino/pins_OMCA_A.h @@ -48,14 +48,12 @@ * PWM (D 13) PD5 19| |22 PC0 (D 16) SCL * PWM (D 14) PD6 20| |21 PD7 (D 15) PWM * +--------+ - * */ /** * Rev B 26 DEC 2016 * * added pointer to a current Arduino IDE extension - * */ /** @@ -73,10 +71,9 @@ * Just use the above JSON URL instead of Sparkfun's JSON. * * Once installed select the Sanguino board and then select the CPU. - * */ -#ifndef __AVR_ATmega644__ +#if NOT_TARGET(__AVR_ATmega644__) #error "Oops! Select 'Sanguino' in 'Tools > Board' and ATmega644 in 'Tools > Processor.'" #endif diff --git a/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h b/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h index 83c2d56d2b..438d49d615 100644 --- a/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h +++ b/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h @@ -31,7 +31,6 @@ * 1) added pointer to a current Arduino IDE extension * 2) added support for M3, M4 & M5 spindle control commands * 3) added case light pin definition - * */ /** @@ -49,10 +48,9 @@ * Just use the above JSON URL instead of Sparkfun's JSON. * * Once installed select the Sanguino board and then select the CPU. - * */ -#if !defined(__AVR_ATmega644P__) && !defined(__AVR_ATmega1284P__) +#if NOT_TARGET(__AVR_ATmega644P__, __AVR_ATmega1284P__) #error "Oops! Select 'Sanguino' in 'Tools > Boards' and 'ATmega644P' or 'ATmega1284P' in 'Tools > Processor.'" #endif @@ -154,11 +152,11 @@ // // LCD / Controller // -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #define SD_DETECT_PIN -1 - #if HAS_GRAPHICAL_LCD + #if HAS_MARLINUI_U8GLIB #if ENABLED(LCD_FOR_MELZI) @@ -290,7 +288,7 @@ #define BTN_EN2 10 #endif -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD // // M3/M4/M5 - Spindle/Laser Control diff --git a/Marlin/src/pins/sanguino/pins_SETHI.h b/Marlin/src/pins/sanguino/pins_SETHI.h index 19fea9ff53..dc2133e441 100644 --- a/Marlin/src/pins/sanguino/pins_SETHI.h +++ b/Marlin/src/pins/sanguino/pins_SETHI.h @@ -47,10 +47,9 @@ * Just use the above JSON URL instead of Sparkfun's JSON. * * Once installed select the Sanguino board and then select the CPU. - * */ -#if !defined(__AVR_ATmega644P__) && !defined(__AVR_ATmega644__) && !defined(__AVR_ATmega1284P__) +#if NOT_TARGET(__AVR_ATmega644P__, __AVR_ATmega644__, __AVR_ATmega1284P__) #error "Oops! Select 'Sanguino' in 'Tools > Boards' and 'ATmega644', 'ATmega644P', or 'ATmega1284P' in 'Tools > Processor.'" #endif diff --git a/Marlin/src/pins/sanguino/pins_ZMIB_V2.h b/Marlin/src/pins/sanguino/pins_ZMIB_V2.h index 262199e310..838ffe38aa 100644 --- a/Marlin/src/pins/sanguino/pins_ZMIB_V2.h +++ b/Marlin/src/pins/sanguino/pins_ZMIB_V2.h @@ -21,7 +21,7 @@ */ #pragma once -#if !defined(__AVR_ATmega644P__) && !defined(__AVR_ATmega1284P__) +#if NOT_TARGET(__AVR_ATmega644P__, __AVR_ATmega1284P__) #error "Oops! Select 'Sanguino' in 'Tools > Boards' and 'ATmega644P' or 'ATmega1284P' in 'Tools > Processor.'" #endif diff --git a/Marlin/src/pins/sensitive_pins.h b/Marlin/src/pins/sensitive_pins.h index 5f61389cf9..169f74b437 100644 --- a/Marlin/src/pins/sensitive_pins.h +++ b/Marlin/src/pins/sensitive_pins.h @@ -354,7 +354,7 @@ #endif #endif -#elif EXTRUDERS > 1 || ENABLED(MIXING_EXTRUDER) +#elif EITHER(HAS_MULTI_EXTRUDER, MIXING_EXTRUDER) #undef _E1_PINS #define _E1_PINS E1_STEP_PIN, E1_DIR_PIN, E1_ENABLE_PIN, _E1_CS _E1_MS1 _E1_MS2 _E1_MS3 @@ -383,7 +383,7 @@ #endif // EXTRUDERS > 3 || MIXING_EXTRUDER > 3 #endif // EXTRUDERS > 2 || MIXING_EXTRUDER > 2 -#endif // EXTRUDERS > 1 || MIXING_EXTRUDER +#endif // HAS_MULTI_EXTRUDER || MIXING_EXTRUDER // // Heaters, Fans, Temp Sensors diff --git a/Marlin/src/pins/stm32f0/pins_MALYAN_M200_V2.h b/Marlin/src/pins/stm32f0/pins_MALYAN_M200_V2.h index 0e5bd58987..abdd088f9b 100644 --- a/Marlin/src/pins/stm32f0/pins_MALYAN_M200_V2.h +++ b/Marlin/src/pins/stm32f0/pins_MALYAN_M200_V2.h @@ -22,7 +22,7 @@ #pragma once -#ifndef STM32F0xx +#if NOT_TARGET(STM32F0xx) #error "Oops! Select an STM32F0 board in your IDE." #endif diff --git a/Marlin/src/pins/stm32f0/pins_MALYAN_M300.h b/Marlin/src/pins/stm32f0/pins_MALYAN_M300.h index d6a83aca1a..dfa413b63f 100644 --- a/Marlin/src/pins/stm32f0/pins_MALYAN_M300.h +++ b/Marlin/src/pins/stm32f0/pins_MALYAN_M300.h @@ -22,7 +22,7 @@ #pragma once -#if NONE(__STM32F1__, STM32F1xx, STM32F0xx) +#if NOT_TARGET(__STM32F1__, STM32F1xx, STM32F0xx) #error "Oops! Select a 'Malyan M300' board in 'Tools > Board.'" #endif diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h index cff34daf2f..63b97b666f 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h @@ -21,7 +21,7 @@ */ #pragma once -#ifndef TARGET_STM32F1 +#if NOT_TARGET(TARGET_STM32F1) #error "Oops! Select an STM32F1 board in 'Tools > Board.'" #endif @@ -117,10 +117,10 @@ * Hardware serial communication ports. * If undefined software serial is used according to the pins below */ - //#define X_HARDWARE_SERIAL Serial1 - //#define Y_HARDWARE_SERIAL Serial1 - //#define Z_HARDWARE_SERIAL Serial1 - //#define E0_HARDWARE_SERIAL Serial1 + //#define X_HARDWARE_SERIAL MSerial1 + //#define Y_HARDWARE_SERIAL MSerial1 + //#define Z_HARDWARE_SERIAL MSerial1 + //#define E0_HARDWARE_SERIAL MSerial1 // // Software serial @@ -171,7 +171,7 @@ * EXP1 */ -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #if ENABLED(CR10_STOCKDISPLAY) @@ -225,7 +225,7 @@ #error "Only CR10_STOCKDISPLAY, ZONESTAR_LCD, ENDER2_STOCKDISPLAY, MKS_MINI_12864, and MKS_LCD12864 are currently supported on the BIGTREE_SKR_E3_DIP." #endif -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD #if BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) @@ -257,7 +257,6 @@ * EXP1-8 ----------- EXP1-3 * SPI1-1 ----------- EXP1-1 * EXP1-10 ----------- EXP1-7 - * */ #define CLCD_SPI_BUS 1 // SPI1 connector @@ -279,14 +278,12 @@ #if SD_CONNECTION_IS(ONBOARD) #define SD_DETECT_PIN PC4 -#endif - -#if BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) && SD_CONNECTION_IS(LCD) +#elif SD_CONNECTION_IS(LCD) && BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) #define SD_DETECT_PIN PA15 #define SS_PIN PA10 #elif SD_CONNECTION_IS(CUSTOM_CABLE) #error "SD CUSTOM_CABLE is not compatible with SKR E3 DIP." #endif -#define ON_BOARD_SPI_DEVICE 1 // SPI1 +#define ONBOARD_SPI_DEVICE 1 // SPI1 #define ONBOARD_SD_CS_PIN PA4 // Chip select for "System" SD card diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V1_0.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V1_0.h index b658f3d714..78751a6bac 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V1_0.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V1_0.h @@ -30,8 +30,8 @@ * Hardware serial communication ports. */ #if HAS_TMC_UART - #define X_HARDWARE_SERIAL Serial4 - #define Y_HARDWARE_SERIAL Serial4 - #define Z_HARDWARE_SERIAL Serial4 - #define E0_HARDWARE_SERIAL Serial4 + #define X_HARDWARE_SERIAL MSerial4 + #define Y_HARDWARE_SERIAL MSerial4 + #define Z_HARDWARE_SERIAL MSerial4 + #define E0_HARDWARE_SERIAL MSerial4 #endif diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V2_0.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V2_0.h index cb94f0bdca..0a0d857db3 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V2_0.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_V2_0.h @@ -52,8 +52,8 @@ * Hardware serial communication ports. */ #if HAS_TMC_UART - #define X_HARDWARE_SERIAL Serial4 - #define Y_HARDWARE_SERIAL Serial4 - #define Z_HARDWARE_SERIAL Serial4 - #define E0_HARDWARE_SERIAL Serial4 + #define X_HARDWARE_SERIAL MSerial4 + #define Y_HARDWARE_SERIAL MSerial4 + #define Z_HARDWARE_SERIAL MSerial4 + #define E0_HARDWARE_SERIAL MSerial4 #endif diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h index 923b0fa4c1..50257f4f46 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h @@ -21,7 +21,7 @@ */ #pragma once -#ifndef TARGET_STM32F1 +#if NOT_TARGET(TARGET_STM32F1) #error "Oops! Select an STM32F1 board in 'Tools > Board.'" #endif @@ -129,7 +129,7 @@ #define EXP1_3 PB7 #endif -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #if ENABLED(CR10_STOCKDISPLAY) @@ -169,11 +169,50 @@ #define FORCE_SOFT_SPI #define LCD_BACKLIGHT_PIN -1 + #elif IS_TFTGLCD_PANEL + + #if ENABLED(TFTGLCD_PANEL_SPI) + + #error "CAUTION! TFTGLCD_PANEL_SPI requires wiring modifications. See 'pins_BTT_SKR_MINI_E3_common.h' for details. Comment out this line to continue." + + /** + * TFTGLCD_PANEL_SPI display pinout + * + * Board Display + * _____ _____ + * 5V | 1 2 | GND (SPI1-MISO) MISO | 1 2 | SCK (SPI1-SCK) + * (FREE) PB7 | 3 4 | PB8 (LCD_CS) (PA9) GLCD_CS | 3 4 | SD_CS (PA10) + * (FREE) PB9 | 5 6 | PA10 (SD_CS) (FREE) | 5 6 | MOSI (SPI1-MOSI) + * RESET | 7 8 | PA9 (MOD_RESET) (PB5) SD_DET | 7 8 | (FREE) + * (BEEPER) PB6 | 9 10| PB5 (SD_DET) GND | 9 10| 5V + * ----- ----- + * EXP1 EXP1 + * + * Needs custom cable: + * + * Board Adapter Display + * _________ + * EXP1-1 ----------- EXP1-10 + * EXP1-2 ----------- EXP1-9 + * SPI1-4 ----------- EXP1-6 + * EXP1-4 ----------- FREE + * SPI1-3 ----------- EXP1-2 + * EXP1-6 ----------- EXP1-4 + * EXP1-7 ----------- FREE + * EXP1-8 ----------- EXP1-3 + * SPI1-1 ----------- EXP1-1 + * EXP1-10 ----------- EXP1-7 + */ + + #define TFTGLCD_CS PA9 + + #endif + #else - #error "Only CR10_STOCKDISPLAY, ZONESTAR_LCD, ENDER2_STOCKDISPLAY, and MKS_MINI_12864 are currently supported on the BIGTREE_SKR_MINI_E3." + #error "Only CR10_STOCKDISPLAY, ZONESTAR_LCD, ENDER2_STOCKDISPLAY, MKS_MINI_12864, and TFTGLCD_PANEL_(SPI|I2C) are currently supported on the BIGTREE_SKR_MINI_E3." #endif -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD #if BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) @@ -185,7 +224,7 @@ * _____ _____ * 5V | 1 2 | GND (SPI1-MISO) MISO | 1 2 | SCK (SPI1-SCK) * (FREE) PB7 | 3 4 | PB8 (LCD_CS) (PA9) MOD_RESET | 3 4 | SD_CS (PA10) - * (FREE) PB9 | 5 6 PA10 (SD_CS) (PB8) LCD_CS | 5 6 MOSI (SPI1-MOSI) + * (FREE) PB9 | 5 6 | PA10 (SD_CS) (PB8) LCD_CS | 5 6 | MOSI (SPI1-MOSI) * RESET | 7 8 | PA9 (MOD_RESET) (PB5) SD_DET | 7 8 | RESET * (BEEPER) PB6 | 9 10| PB5 (SD_DET) GND | 9 10| 5V * ----- ----- @@ -205,7 +244,6 @@ * EXP1-8 ----------- EXP1-3 * SPI1-1 ----------- EXP1-1 * EXP1-10 ----------- EXP1-7 - * */ #define CLCD_SPI_BUS 1 // SPI1 connector @@ -227,14 +265,12 @@ #if SD_CONNECTION_IS(ONBOARD) #define SD_DETECT_PIN PC4 -#endif - -#if BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) && SD_CONNECTION_IS(LCD) +#elif SD_CONNECTION_IS(LCD) && (BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) || IS_TFTGLCD_PANEL) #define SD_DETECT_PIN PB5 #define SS_PIN PA10 #elif SD_CONNECTION_IS(CUSTOM_CABLE) #error "SD CUSTOM_CABLE is not compatible with SKR Mini E3." #endif -#define ON_BOARD_SPI_DEVICE 1 // SPI1 +#define ONBOARD_SPI_DEVICE 1 // SPI1 #define ONBOARD_SD_CS_PIN PA4 // Chip select for "System" SD card diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h index 4a12d5d32d..47fff4467c 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h @@ -21,7 +21,7 @@ */ #pragma once -#ifndef TARGET_STM32F1 +#if NOT_TARGET(TARGET_STM32F1) #error "Oops! Select an STM32F1 board in 'Tools > Board.'" #endif @@ -110,7 +110,7 @@ * EXP2 EXP1 */ -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #define BEEPER_PIN PC10 #define BTN_ENC PC11 @@ -123,6 +123,17 @@ #define LCD_PINS_ENABLE PC14 #define LCD_PINS_D4 PB7 + #elif IS_TFTGLCD_PANEL + + #undef BEEPER_PIN + #undef BTN_ENC + + #if ENABLED(TFTGLCD_PANEL_SPI) + #define TFTGLCD_CS PD2 + #endif + + #define SD_DETECT_PIN PB9 + #else #define LCD_PINS_RS PC12 @@ -172,7 +183,7 @@ #endif // !FYSETC_MINI_12864 - #if HAS_GRAPHICAL_LCD + #if HAS_MARLINUI_U8GLIB #ifndef BOARD_ST7920_DELAY_1 #define BOARD_ST7920_DELAY_1 DELAY_NS(125) #endif @@ -186,7 +197,7 @@ #endif -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD // // SD Card @@ -213,5 +224,5 @@ #define MOSI_PIN PA7 #define SS_PIN PA4 #endif -#define ON_BOARD_SPI_DEVICE 1 // SPI1 +#define ONBOARD_SPI_DEVICE 1 // SPI1 #define ONBOARD_SD_CS_PIN PA4 // Chip select for "System" SD card diff --git a/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h b/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h index 5254166fa5..66930a2ea5 100644 --- a/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h +++ b/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h @@ -21,7 +21,7 @@ */ #pragma once -#ifndef TARGET_STM32F1 +#if NOT_TARGET(TARGET_STM32F1) #error "Oops! Select an STM32F1 board in 'Tools > Board.'" #elif HOTENDS > 1 || E_STEPPERS > 1 #error "CCROBOT-ONLINE MEEB_3DP only supports 1 hotend / E-stepper. Comment out this line to continue." @@ -142,7 +142,7 @@ #endif // Alter timing for graphical display -#if HAS_GRAPHICAL_LCD +#if HAS_MARLINUI_U8GLIB #ifndef BOARD_ST7920_DELAY_1 #define BOARD_ST7920_DELAY_1 DELAY_NS(125) #endif @@ -173,7 +173,7 @@ #define SS_PIN PA4 #endif -#define ON_BOARD_SPI_DEVICE 1 // SPI1 +#define ONBOARD_SPI_DEVICE 1 // SPI1 #define ONBOARD_SD_CS_PIN PA4 // Chip select for SD-NAND #endif diff --git a/Marlin/src/pins/stm32f1/pins_CHITU3D.h b/Marlin/src/pins/stm32f1/pins_CHITU3D.h index bf9a7d8e05..3a872db025 100644 --- a/Marlin/src/pins/stm32f1/pins_CHITU3D.h +++ b/Marlin/src/pins/stm32f1/pins_CHITU3D.h @@ -21,7 +21,7 @@ */ #pragma once -#if !defined(__STM32F1__) && !defined(__STM32F4__) +#if NOT_TARGET(__STM32F1__, __STM32F4__) #error "Oops! Select an STM32F1/4 board in 'Tools > Board.'" #endif @@ -120,7 +120,7 @@ // // LCD Pins // -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #if ENABLED(REPRAPWORLD_GRAPHICAL_LCD) #define LCD_PINS_RS PD1 // 49 // CS chip select /SS chip slave select @@ -281,4 +281,4 @@ #endif #endif // NEWPANEL -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/stm32f1/pins_CHITU3D_V5.h b/Marlin/src/pins/stm32f1/pins_CHITU3D_V5.h index 54ff9a779a..10c615e524 100644 --- a/Marlin/src/pins/stm32f1/pins_CHITU3D_V5.h +++ b/Marlin/src/pins/stm32f1/pins_CHITU3D_V5.h @@ -21,7 +21,7 @@ */ #pragma once -#if !defined(__STM32F1__) && !defined(__STM32F4__) +#if NOT_TARGET(__STM32F1__, __STM32F4__) #error "Oops! Select an STM32F1/4 board in 'Tools > Board.'" #endif diff --git a/Marlin/src/pins/stm32f1/pins_CHITU3D_V6.h b/Marlin/src/pins/stm32f1/pins_CHITU3D_V6.h index a825db275c..f8f3225f3c 100644 --- a/Marlin/src/pins/stm32f1/pins_CHITU3D_V6.h +++ b/Marlin/src/pins/stm32f1/pins_CHITU3D_V6.h @@ -21,7 +21,7 @@ */ #pragma once -#if !defined(__STM32F1__) && !defined(__STM32F4__) +#if NOT_TARGET(__STM32F1__, __STM32F4__) #error "Oops! Select an STM32F1/4 board in 'Tools > Board.'" #endif diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h index ded0ba405b..eb910dd846 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h @@ -24,7 +24,7 @@ * CREALITY (STM32F103) board pin assignments */ -#ifndef __STM32F1__ +#if NOT_TARGET(__STM32F1__) #error "Oops! Select an STM32F1 board in 'Tools > Board.'" #endif @@ -150,9 +150,10 @@ // #define SD_DETECT_PIN PC7 #define SDCARD_CONNECTION ONBOARD -#define ON_BOARD_SPI_DEVICE 1 +#define ONBOARD_SPI_DEVICE 1 #define ONBOARD_SD_CS_PIN PA4 // SDSS #define SDIO_SUPPORT +#define NO_SD_HOST_DRIVE // This board's SD is only seen by the printer #if ENABLED(CR10_STOCKDISPLAY) && NONE(RET6_12864_LCD, VET6_12864_LCD) #error "Define RET6_12864_LCD or VET6_12864_LCD to select pins for CR10_STOCKDISPLAY with the Creality V4 controller." @@ -160,7 +161,7 @@ #if ENABLED(RET6_12864_LCD) - /* RET6 12864 LCD */ + // RET6 12864 LCD #define LCD_PINS_RS PB12 #define LCD_PINS_ENABLE PB15 #define LCD_PINS_D4 PB13 @@ -173,7 +174,7 @@ #elif ENABLED(VET6_12864_LCD) - /* VET6 12864 LCD */ + // VET6 12864 LCD #define LCD_PINS_RS PA4 #define LCD_PINS_ENABLE PA7 #define LCD_PINS_D4 PA5 @@ -184,7 +185,7 @@ #elif ENABLED(DWIN_CREALITY_LCD) - /* RET6 DWIN ENCODER LCD */ + // RET6 DWIN ENCODER LCD #define BTN_ENC PB14 #define BTN_EN1 PB15 #define BTN_EN2 PB12 @@ -197,7 +198,7 @@ #elif ENABLED(DWIN_VET6_CREALITY_LCD) - /* VET6 DWIN ENCODER LCD */ + // VET6 DWIN ENCODER LCD #define BTN_ENC PA6 #define BTN_EN1 PA7 #define BTN_EN2 PA4 diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V427.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V427.h index 9453a6d515..5b51ece07f 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V427.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V427.h @@ -24,7 +24,7 @@ * CREALITY v4.2.7 (STM32F103) board pin assignments */ -#ifndef __STM32F1__ +#if NOT_TARGET(__STM32F1__) #error "Oops! Select an STM32F1 board in 'Tools > Board.'" #endif diff --git a/Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h b/Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h index ca9364a570..ebe5964d05 100644 --- a/Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h +++ b/Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h @@ -21,7 +21,7 @@ */ #pragma once -#ifndef __STM32F1__ +#if NOT_TARGET(__STM32F1__) #error "Oops! Select an STM32F1 board in 'Tools > Board.'" #endif @@ -93,10 +93,10 @@ // // Hardware serial with switch // - #define X_HARDWARE_SERIAL Serial1 - #define Y_HARDWARE_SERIAL Serial1 - #define Z_HARDWARE_SERIAL Serial1 - #define E0_HARDWARE_SERIAL Serial1 + #define X_HARDWARE_SERIAL MSerial1 + #define Y_HARDWARE_SERIAL MSerial1 + #define Z_HARDWARE_SERIAL MSerial1 + #define E0_HARDWARE_SERIAL MSerial1 // The 4xTMC2209 module doesn't have a serial multiplexer and // needs to set *_SLAVE_ADDRESS in Configuration_adv.h for X,Y,Z,E0 @@ -139,11 +139,11 @@ // // LCD Pins // -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #define BEEPER_PIN PC9 - #if HAS_GRAPHICAL_LCD + #if HAS_MARLINUI_U8GLIB #define DOGLCD_A0 PA15 #ifdef pins_v2_20190128 diff --git a/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h b/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h index 1f5e70a15a..de5ea45d44 100644 --- a/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h +++ b/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h @@ -21,7 +21,7 @@ */ #pragma once -#ifndef __STM32F1__ +#if NOT_TARGET(__STM32F1__) #error "Oops! Select an STM32F1 board in 'Tools > Board.'" #endif @@ -130,10 +130,10 @@ * Note: Pin 4 on the Cheetah board is assigned to an I/O, it is assigned to RESET on the Ender-3 board. */ -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #define BEEPER_PIN PC9 - #if HAS_GRAPHICAL_LCD + #if HAS_MARLINUI_U8GLIB #define DOGLCD_A0 PB14 #define DOGLCD_CS PB12 #define DOGLCD_SCK PB13 diff --git a/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH_V12.h b/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH_V12.h index f07320db40..5e8bd11b4b 100644 --- a/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH_V12.h +++ b/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH_V12.h @@ -21,7 +21,7 @@ */ #pragma once -#ifndef __STM32F1__ +#if NOT_TARGET(__STM32F1__) #error "Oops! Select an STM32F1 board in 'Tools > Board.'" #endif diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_MINI.h b/Marlin/src/pins/stm32f1/pins_GTM32_MINI.h index fe6c0b1325..ca25c45a7b 100644 --- a/Marlin/src/pins/stm32f1/pins_GTM32_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_GTM32_MINI.h @@ -26,7 +26,7 @@ * Schematic: https://github.com/chepo92/Smartto/blob/master/circuit_diagram/Rostock301/Hardware_GTM32_PRO_VB.pdf */ -#ifndef __STM32F1__ +#if NOT_TARGET(__STM32F1__) #error "Oops! Select an STM32F1 board in 'Tools > Board.'" #endif @@ -135,7 +135,7 @@ // // LCD / Controller // -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) // @@ -158,7 +158,7 @@ //#define LCD_UART_RX PD9 #endif - #if HAS_GRAPHICAL_LCD + #if HAS_MARLINUI_U8GLIB #ifndef BOARD_ST7920_DELAY_1 #define BOARD_ST7920_DELAY_1 DELAY_NS(96) #endif @@ -170,7 +170,7 @@ #endif #endif -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) // diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h b/Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h index 716de610a7..02fd3bcae7 100644 --- a/Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h +++ b/Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h @@ -26,7 +26,7 @@ * Schematic: https://github.com/chepo92/Smartto/blob/master/circuit_diagram/Rostock301/Hardware_GTM32_PRO_VB.pdf */ -#ifndef __STM32F1__ +#if NOT_TARGET(__STM32F1__) #error "Oops! Select an STM32F1 board in 'Tools > Board.'" #endif @@ -135,7 +135,7 @@ // // LCD / Controller // -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) // @@ -166,7 +166,7 @@ //#define LCD_UART_RX PD9 #endif - #if HAS_GRAPHICAL_LCD + #if HAS_MARLINUI_U8GLIB #ifndef BOARD_ST7920_DELAY_1 #define BOARD_ST7920_DELAY_1 DELAY_NS(96) #endif @@ -178,7 +178,7 @@ #endif #endif -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD // // Beeper diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h b/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h index fe6c0b1325..ca25c45a7b 100644 --- a/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h +++ b/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h @@ -26,7 +26,7 @@ * Schematic: https://github.com/chepo92/Smartto/blob/master/circuit_diagram/Rostock301/Hardware_GTM32_PRO_VB.pdf */ -#ifndef __STM32F1__ +#if NOT_TARGET(__STM32F1__) #error "Oops! Select an STM32F1 board in 'Tools > Board.'" #endif @@ -135,7 +135,7 @@ // // LCD / Controller // -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) // @@ -158,7 +158,7 @@ //#define LCD_UART_RX PD9 #endif - #if HAS_GRAPHICAL_LCD + #if HAS_MARLINUI_U8GLIB #ifndef BOARD_ST7920_DELAY_1 #define BOARD_ST7920_DELAY_1 DELAY_NS(96) #endif @@ -170,7 +170,7 @@ #endif #endif -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) // diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h b/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h index 1fc4fa9424..fc18263fdd 100644 --- a/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h +++ b/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h @@ -26,7 +26,7 @@ * Schematic: https://github.com/chepo92/Smartto/blob/master/circuit_diagram/Rostock301/Hardware_GTM32_PRO_VB.pdf */ -#ifndef __STM32F1__ +#if NOT_TARGET(__STM32F1__) #error "Oops! Select an STM32F1 board in 'Tools > Board.'" #endif @@ -135,7 +135,7 @@ // // LCD / Controller // -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) @@ -168,7 +168,7 @@ //#define LCD_UART_RX PD9 #endif - #if HAS_GRAPHICAL_LCD + #if HAS_MARLINUI_U8GLIB #ifndef BOARD_ST7920_DELAY_1 #define BOARD_ST7920_DELAY_1 DELAY_NS(96) #endif @@ -180,7 +180,7 @@ #endif #endif -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD // // Beeper diff --git a/Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h b/Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h index d474eb25f6..64948039ba 100644 --- a/Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h +++ b/Marlin/src/pins/stm32f1/pins_JGAURORA_A5S_A1.h @@ -28,7 +28,7 @@ * Pin assignments for 32-bit JGAurora A5S & A1 */ -#ifndef __STM32F1__ +#if NOT_TARGET(__STM32F1__) #error "Oops! Select an STM32F1 board in 'Tools > Board.'" #elif HOTENDS > 1 || E_STEPPERS > 1 #error "JGAurora 32-bit board only supports 1 hotend / E-stepper. Comment out this line to continue." diff --git a/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h b/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h index cbc43a7ac8..47d7118b53 100644 --- a/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h +++ b/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h @@ -22,7 +22,7 @@ * Longer3D LK1/LK2 & Alfawise U20/U30 (STM32F103VET6) board pin assignments */ -#if !defined(__STM32F1__) && !defined(STM32F1xx) +#if NOT_TARGET(__STM32F1__, STM32F1xx) #error "Oops! Select a STM32F1 board in 'Tools > Board.'" #elif HOTENDS > 1 || E_STEPPERS > 1 #error "Longer3D board only supports 1 hotend / E-stepper. Comment out this line to continue." @@ -119,7 +119,8 @@ */ #define LCD_RESET_PIN PC4 // pin 33 -#define LCD_BACKLIGHT_PIN PD12 // pin 59 +#define TFT_RESET_PIN PC4 // pin 33 +#define TFT_BACKLIGHT_PIN PD12 // pin 59 #define FSMC_CS_PIN PD7 // pin 88 = FSMC_NE1 #define FSMC_RS_PIN PD11 // pin 58 A16 Register. Only one address needed @@ -136,6 +137,8 @@ #define TFT_PIXEL_OFFSET_X 32 #define TFT_PIXEL_OFFSET_Y 32 +//#define TFT_DRIVER ILI9341 + /** * Note: Alfawise U20/U30 boards DON'T use SPI2, as the hardware designer * mixed up MOSI and MISO pins. SPI is managed in SW, and needs pins diff --git a/Marlin/src/pins/stm32f1/pins_MALYAN_M200.h b/Marlin/src/pins/stm32f1/pins_MALYAN_M200.h index 39c52ab0d3..d3c26c497d 100644 --- a/Marlin/src/pins/stm32f1/pins_MALYAN_M200.h +++ b/Marlin/src/pins/stm32f1/pins_MALYAN_M200.h @@ -25,7 +25,7 @@ * MALYAN M200 pin assignments */ -#if NONE(__STM32F1__, STM32F1xx, STM32F0xx) +#if NOT_TARGET(__STM32F1__, STM32F1xx, STM32F0xx) #error "Oops! Select an STM32 board in your IDE." #endif diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h index 1ab9165830..26a0c9260e 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h @@ -27,7 +27,7 @@ * https://github.com/makerbase-mks/MKS-Robin/tree/master/MKS%20Robin/Hardware */ -#if !defined(STM32F1) && !defined(STM32F1xx) +#if NOT_TARGET(STM32F1, STM32F1xx) #error "Oops! Select an STM32F1 board in 'Tools > Board.'" #elif HOTENDS > 2 || E_STEPPERS > 2 #error "MKS Robin supports up to 2 hotends / E-steppers. Comment out this line to continue." @@ -126,12 +126,7 @@ #endif #define LED_PIN PB2 -#ifdef HAS_GRAPHICAL_TFT - #define TFT_RESET_PIN PF6 - #define TFT_BACKLIGHT_PIN PG11 - #define TFT_CS_PIN PG12 // NE4 - #define TFT_RS_PIN PF0 // A0 -#else +#if HAS_FSMC_TFT /** * Note: MKS Robin TFT screens use various TFT controllers * Supported screens are based on the ILI9341, ST7789V and ILI9328 (320x240) @@ -148,10 +143,17 @@ #define LCD_BACKLIGHT_PIN PG11 #define FSMC_CS_PIN PG12 // NE4 #define FSMC_RS_PIN PF0 // A0 + #define TFT_CS_PIN FSMC_CS_PIN + #define TFT_RS_PIN FSMC_RS_PIN #define LCD_USE_DMA_FSMC // Use DMA transfers to send data to the TFT #define FSMC_DMA_DEV DMA2 #define FSMC_DMA_CHANNEL DMA_CH5 +#elif HAS_GRAPHICAL_TFT + #define TFT_RESET_PIN PF6 + #define TFT_BACKLIGHT_PIN PG11 + #define TFT_CS_PIN PG12 // NE4 + #define TFT_RS_PIN PF0 // A0 #endif #if NEED_TOUCH_PINS @@ -188,17 +190,11 @@ * Hardware serial communication ports. * If undefined software serial is used according to the pins below */ - //#define X_HARDWARE_SERIAL Serial1 - //#define X2_HARDWARE_SERIAL Serial1 - //#define Y_HARDWARE_SERIAL Serial1 - //#define Y2_HARDWARE_SERIAL Serial1 - //#define Z_HARDWARE_SERIAL Serial1 - //#define Z2_HARDWARE_SERIAL Serial1 - //#define E0_HARDWARE_SERIAL Serial1 - //#define E1_HARDWARE_SERIAL Serial1 - //#define E2_HARDWARE_SERIAL Serial1 - //#define E3_HARDWARE_SERIAL Serial1 - //#define E4_HARDWARE_SERIAL Serial1 + //#define X_HARDWARE_SERIAL MSerial1 + //#define Y_HARDWARE_SERIAL MSerial1 + //#define Z_HARDWARE_SERIAL MSerial1 + //#define E0_HARDWARE_SERIAL MSerial1 + //#define E1_HARDWARE_SERIAL MSerial1 // Unused servo pins may be repurposed with SoftwareSerialM //#define X_SERIAL_TX_PIN PF8 // SERVO3_PIN -- XS2 - 6 diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h new file mode 100644 index 0000000000..a530c89d2c --- /dev/null +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h @@ -0,0 +1,377 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * MKS Robin nano (STM32F130VET6) board pin assignments + */ + +#if NOT_TARGET(__STM32F1__) + #error "Oops! Select an STM32F1 board in 'Tools > Board.'" +#elif HOTENDS > 1 || E_STEPPERS > 1 + #error "MKS Robin e3p supports up to 1 hotends / E-steppers. Comment out this line to continue." +#elif HAS_FSMC_TFT + #error "MKS Robin e3p doesn't support FSMC-based TFT displays." +#endif + +#define BOARD_INFO_NAME "MKS Robin e3p" + +// +// Release PB4 (Y_ENABLE_PIN) from JTAG NRST role +// + +#define DISABLE_DEBUG + +// +// EEPROM +// +//#define FLASH_EEPROM_EMULATION +//#define SDCARD_EEPROM_EMULATION + +#if EITHER(NO_EEPROM_SELECTED, I2C_EEPROM) + #define I2C_EEPROM // EEPROM on I2C-0 + #define MARLIN_EEPROM_SIZE 0x1000 // 4KB +#endif + +// +// Note: MKS Robin board is using SPI2 interface. +// +//#define SPI_MODULE 2 +#define ENABLE_SPI2 + +// +// Limit Switches +// +#define X_DIAG_PIN PA15 +#define Y_DIAG_PIN PA12 +#define Z_DIAG_PIN PA11 +#define E0_DIAG_PIN PC4 + +#define X_STOP_PIN PA15 +#define Y_STOP_PIN PA12 +#define Z_MIN_PIN PA11 +#define Z_MAX_PIN PC4 + +// +// Steppers +// +#define X_ENABLE_PIN PE4 +#define X_STEP_PIN PE3 +#define X_DIR_PIN PE2 +#ifndef X_CS_PIN + #define X_CS_PIN PD5 +#endif + +#define Y_ENABLE_PIN PE1 +#define Y_STEP_PIN PE0 +#define Y_DIR_PIN PB9 +#ifndef Y_CS_PIN + #define Y_CS_PIN PD7 +#endif + +#define Z_ENABLE_PIN PB8 +#define Z_STEP_PIN PB5 +#define Z_DIR_PIN PB4 +#ifndef Z_CS_PIN + #define Z_CS_PIN PD4 +#endif + +#define E0_ENABLE_PIN PB3 +#define E0_STEP_PIN PD6 +#define E0_DIR_PIN PD3 +#ifndef E0_CS_PIN + #define E0_CS_PIN PD9 +#endif + +// +// Software SPI pins for TMC2130 stepper drivers +// +#if ENABLED(TMC_USE_SW_SPI) + #ifndef TMC_SW_MOSI + #define TMC_SW_MOSI PD14 + #endif + #ifndef TMC_SW_MISO + #define TMC_SW_MISO PD1 + #endif + #ifndef TMC_SW_SCK + #define TMC_SW_SCK PD0 + #endif +#endif + +#if HAS_TMC_UART + /** + * TMC2208/TMC2209 stepper drivers + * + * Hardware serial communication ports. + * If undefined software serial is used according to the pins below + */ + //#define X_HARDWARE_SERIAL Serial + //#define X2_HARDWARE_SERIAL Serial1 + //#define Y_HARDWARE_SERIAL Serial1 + //#define Y2_HARDWARE_SERIAL Serial1 + //#define Z_HARDWARE_SERIAL Serial1 + //#define Z2_HARDWARE_SERIAL Serial1 + //#define E0_HARDWARE_SERIAL Serial1 + //#define E1_HARDWARE_SERIAL Serial1 + //#define E2_HARDWARE_SERIAL Serial1 + //#define E3_HARDWARE_SERIAL Serial1 + //#define E4_HARDWARE_SERIAL Serial1 + + // + // Software serial + // + + #define X_SERIAL_TX_PIN PD5 + #define X_SERIAL_RX_PIN PD5 + + #define Y_SERIAL_TX_PIN PD7 + #define Y_SERIAL_RX_PIN PD7 + + #define Z_SERIAL_TX_PIN PD4 + #define Z_SERIAL_RX_PIN PD4 + + #define E0_SERIAL_TX_PIN PD9 + #define E0_SERIAL_RX_PIN PD9 + + // Reduce baud rate to improve software serial reliability + #define TMC_BAUD_RATE 19200 +#endif // TMC2208 || TMC2209 + +// +// Temperature Sensors +// +#define TEMP_0_PIN PC1 // TH1 +#define TEMP_BED_PIN PC0 // TB1 + +// +// Heaters / Fans +// +#define HEATER_0_PIN PC3 // HEATER1 +#define HEATER_BED_PIN PA0 // HOT BED + +#define FAN_PIN PB1 // FAN + +// +// Misc. Functions +// +#if HAS_TFT_LVGL_UI + //#define MKSPWC + #ifdef MKSPWC + #define SUICIDE_PIN PB2 // Enable MKSPWC SUICIDE PIN + #define SUICIDE_PIN_INVERTING false // Enable MKSPWC PIN STATE + #define KILL_PIN PA2 // Enable MKSPWC DET PIN + #define KILL_PIN_STATE true // Enable MKSPWC PIN STATE + #endif + + #define MT_DET_1_PIN PA4 // LVGL UI FILAMENT RUNOUT1 PIN + #define MT_DET_PIN_INVERTING false // LVGL UI filament RUNOUT PIN STATE + + #define WIFI_IO0_PIN PC13 // MKS ESP WIFI IO0 PIN + #define WIFI_IO1_PIN PC7 // MKS ESP WIFI IO1 PIN + #define WIFI_RESET_PIN PE9 // MKS ESP WIFI RESET PIN + + #if ENABLED(MKS_TEST) + #define MKS_TEST_POWER_LOSS_PIN PA2 // PW_DET + #define MKS_TEST_PS_ON_PIN PB0 // PW_OFF + #endif +#else + //#define POWER_LOSS_PIN PA2 // PW_DET + //#define PS_ON_PIN PB2 // PW_OFF + #define FIL_RUNOUT_PIN PA4 +#endif + +#define SERVO0_PIN PA8 // Enable BLTOUCH + +//#define LED_PIN PB2 + +// +// SD Card +// +#ifndef SDCARD_CONNECTION + #define SDCARD_CONNECTION ONBOARD +#endif + +#define SDIO_SUPPORT +#define SDIO_CLOCK 4500000 // 4.5 MHz +#define SD_DETECT_PIN PD12 +#define ONBOARD_SD_CS_PIN PC11 + +// +// LCD / Controller +// +#ifndef BEEPER_PIN + #define BEEPER_PIN PC5 +#endif + +/** + * Note: MKS Robin TFT screens use various TFT controllers. + * If the screen stays white, disable 'LCD_RESET_PIN' + * to let the bootloader init the screen. + */ + +#if HAS_SPI_TFT + + // Shared SPI TFT + + #define LCD_BACKLIGHT_PIN PD13 + + #define TOUCH_CS_PIN PE14 // SPI1_NSS + #define TOUCH_SCK_PIN PA5 // SPI1_SCK + #define TOUCH_MISO_PIN PA6 // SPI1_MISO + #define TOUCH_MOSI_PIN PA7 // SPI1_MOSI + + #define BTN_EN1 PE8 + #define BTN_EN2 PE11 + #define BTN_ENC PE13 + + #define TFT_CS_PIN PD11 + #define TFT_SCK_PIN PA5 + #define TFT_MISO_PIN PA6 + #define TFT_MOSI_PIN PA7 + #define TFT_DC_PIN PD10 + #define TFT_RST_PIN PC6 + #define TFT_A0_PIN TFT_DC_PIN + + #define TFT_RESET_PIN PC6 + #define TFT_BACKLIGHT_PIN PD13 + + #define TOUCH_BUTTONS_HW_SPI + #define TOUCH_BUTTONS_HW_SPI_DEVICE 1 + + #ifndef TFT_WIDTH + #define TFT_WIDTH 480 + #endif + #ifndef TFT_HEIGHT + #define TFT_HEIGHT 320 + #endif + + #define LCD_READ_ID 0xD3 + #define LCD_USE_DMA_SPI + +#endif + +#if ENABLED(TFT_LVGL_UI_SPI) + + // LVGL + + #define XPT2046_X_CALIBRATION -17253 + #define XPT2046_Y_CALIBRATION 11579 + #define XPT2046_X_OFFSET 514 + #define XPT2046_Y_OFFSET -24 + +#elif ENABLED(SPI_GRAPHICAL_TFT) + + // Emulated DOGM SPI + + #ifndef XPT2046_X_CALIBRATION + #define XPT2046_X_CALIBRATION -11386 + #endif + #ifndef XPT2046_Y_CALIBRATION + #define XPT2046_Y_CALIBRATION 8684 + #endif + #ifndef XPT2046_X_OFFSET + #define XPT2046_X_OFFSET 339 + #endif + #ifndef XPT2046_Y_OFFSET + #define XPT2046_Y_OFFSET -18 + #endif + + #ifndef GRAPHICAL_TFT_UPSCALE + #define GRAPHICAL_TFT_UPSCALE 3 + #endif + #ifndef TFT_PIXEL_OFFSET_Y + #define TFT_PIXEL_OFFSET_Y 32 + #endif + + #define BTN_ENC PE13 + #define BTN_EN1 PE8 + #define BTN_EN2 PE11 + + #define LCD_PINS_ENABLE PD13 + #define LCD_PINS_RS PC6 + +#elif ENABLED(TFT_480x320_SPI) + #define XPT2046_X_CALIBRATION -17253 + #define XPT2046_Y_CALIBRATION 11579 + #define XPT2046_X_OFFSET 514 + #define XPT2046_Y_OFFSET -24 + + #define TFT_DRIVER ST7796 + #define TFT_BUFFER_SIZE 14400 + +#endif + +#if HAS_WIRED_LCD && !HAS_SPI_TFT + + // NON TFT Displays + + #if ENABLED(MKS_MINI_12864) + + // MKS MINI12864 and MKS LCD12864B + // If using MKS LCD12864A (Need to remove RPK2 resistor) + + #define LCD_BACKLIGHT_PIN -1 + #define LCD_RESET_PIN -1 + #define DOGLCD_A0 PD11 + #define DOGLCD_CS PE15 + #define DOGLCD_SCK PA5 + #define DOGLCD_MOSI PA7 + + // Required for MKS_MINI_12864 with this board + #define MKS_LCD12864B + #undef SHOW_BOOTSCREEN + + #else // !MKS_MINI_12864 + + #define LCD_PINS_D4 PE14 + #if ENABLED(ULTIPANEL) + #define LCD_PINS_D5 PE15 + #define LCD_PINS_D6 PD11 + #define LCD_PINS_D7 PD10 + #endif + + #ifndef BOARD_ST7920_DELAY_1 + #define BOARD_ST7920_DELAY_1 DELAY_NS(125) + #endif + #ifndef BOARD_ST7920_DELAY_2 + #define BOARD_ST7920_DELAY_2 DELAY_NS(125) + #endif + #ifndef BOARD_ST7920_DELAY_3 + #define BOARD_ST7920_DELAY_3 DELAY_NS(125) + #endif + + #endif // !MKS_MINI_12864 + +#endif // HAS_WIRED_LCD && !HAS_SPI_TFT + +#define HAS_SPI_FLASH 1 +#define SPI_FLASH_SIZE 0x1000000 // 16MB +#if HAS_SPI_FLASH + #define W25QXX_CS_PIN PB12 + #define W25QXX_MOSI_PIN PB15 + #define W25QXX_MISO_PIN PB14 + #define W25QXX_SCK_PIN PB13 +#endif + +#if ENABLED(SPEAKER) && BEEPER_PIN == PC5 + #error "MKS Robin nano default BEEPER_PIN is not a SPEAKER." +#endif diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h index 1346e8099a..015e29bdbe 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h @@ -25,7 +25,7 @@ * MKS Robin E3 & E3D (STM32F103RCT6) common board pin assignments */ -#ifndef __STM32F1__ +#if NOT_TARGET(__STM32F1__) #error "Oops! Select an STM32F1 board in 'Tools > Board.'" #endif @@ -33,7 +33,6 @@ //#define DISABLE_DEBUG #define DISABLE_JTAG -#define ENABLE_SPI2 // // EEPROM @@ -84,10 +83,10 @@ * Hardware serial communication ports. * If undefined software serial is used according to the pins below */ - //#define X_HARDWARE_SERIAL Serial1 - //#define Y_HARDWARE_SERIAL Serial1 - //#define Z_HARDWARE_SERIAL Serial1 - //#define E0_HARDWARE_SERIAL Serial1 + //#define X_HARDWARE_SERIAL MSerial1 + //#define Y_HARDWARE_SERIAL MSerial1 + //#define Z_HARDWARE_SERIAL MSerial1 + //#define E0_HARDWARE_SERIAL MSerial1 // // Software serial @@ -133,7 +132,7 @@ * ----- ----- ----- * EXP1 EXP2 EXP3 */ -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #define BEEPER_PIN PC1 #define BTN_ENC PC3 @@ -152,8 +151,6 @@ #define DOGLCD_SCK PB13 #define DOGLCD_MOSI PB15 - #undef SHOW_BOOTSCREEN - #else #define LCD_PINS_D4 PA6 @@ -165,7 +162,7 @@ #endif // !MKS_MINI_12864 -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD // // SD Card diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h index 3cf0bce06d..aa1ccedb35 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h @@ -21,7 +21,7 @@ */ #pragma once -#ifndef __STM32F1__ +#if NOT_TARGET(__STM32F1__) #error "Oops! Select an STM32F1 board in 'Tools > Board.'" #elif HOTENDS > 1 || E_STEPPERS > 1 #error "MKS Robin Lite supports only 1 hotend / E-stepper. Comment out this line to continue." @@ -81,7 +81,7 @@ // // LCD Pins // -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #define BEEPER_PIN PD2 #define BTN_ENC PB3 #define LCD_PINS_RS PC3 @@ -111,7 +111,7 @@ #endif // !MKS_MINI_12864 - #if HAS_GRAPHICAL_LCD + #if HAS_MARLINUI_U8GLIB #ifndef BOARD_ST7920_DELAY_1 #define BOARD_ST7920_DELAY_1 DELAY_NS(125) #endif @@ -123,7 +123,7 @@ #endif #endif -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD // Motor current PWM pins #define MOTOR_CURRENT_PWM_XY_PIN PB0 diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE3.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE3.h index 9cf8685dfa..d5318b8e87 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE3.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE3.h @@ -25,7 +25,7 @@ * MKS Robin Lite 3 (STM32F103RCT6) board pin assignments */ -#ifndef __STM32F1__ +#if NOT_TARGET(__STM32F1__) #error "Oops! Select an STM32F1 board in 'Tools > Board.'" #elif HOTENDS > 2 || E_STEPPERS > 2 #error "MKS Robin Lite3 supports up to 2 hotends / E-steppers. Comment out this line to continue." @@ -96,7 +96,7 @@ // // LCD Pins // -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #define BEEPER_PIN PC1 #define BTN_ENC PC3 @@ -115,7 +115,11 @@ #define DOGLCD_SCK PB13 #define DOGLCD_MOSI PB15 - #undef SHOW_BOOTSCREEN + #elif IS_TFTGLCD_PANEL + + #if ENABLED(TFTGLCD_PANEL_SPI) + #define TFTGLCD_CS PB11 + #endif #else // !MKS_MINI_12864 @@ -128,7 +132,7 @@ #endif // !MKS_MINI_12864 -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD // // SD Card diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h index cb3ab62cc2..b159ae3f4c 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h @@ -25,7 +25,7 @@ * MKS Robin mini (STM32F130VET6) board pin assignments */ -#ifndef __STM32F1__ +#if NOT_TARGET(__STM32F1__) #error "Oops! Select an STM32F1 board in 'Tools > Board.'" #elif HOTENDS > 1 || E_STEPPERS > 1 #error "MKS Robin mini only supports 1 hotend / E-stepper. Comment out this line to continue." @@ -87,7 +87,7 @@ #define MOTOR_CURRENT_PWM_E_PIN PB0 #define MOTOR_CURRENT_PWM_RANGE 1500 // (255 * (1000mA / 65535)) * 257 = 1000 is equal 1.6v Vref in turn equal 1Amp #ifndef DEFAULT_PWM_MOTOR_CURRENT - #define DEFAULT_PWM_MOTOR_CURRENT { 800, 800, 800 } + #define DEFAULT_PWM_MOTOR_CURRENT { 800, 800, 800 } #endif // // Temperature Sensors @@ -126,6 +126,7 @@ #define SDIO_SUPPORT #define SDIO_CLOCK 4500000 // 4.5 MHz #define SD_DETECT_PIN PD12 +#define ONBOARD_SPI_DEVICE 1 // SPI1 #define ONBOARD_SD_CS_PIN PC11 // @@ -180,7 +181,7 @@ #define TFT_DRIVER ILI9341 #define TFT_BUFFER_SIZE 14400 - + // YV for normal screen mounting #define ILI9341_ORIENTATION ILI9341_MADCTL_MY | ILI9341_MADCTL_MV // XV for 180° rotated screen mounting diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h index d2cbaa682b..ac1f1e770d 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO.h @@ -1,6 +1,10 @@ #pragma once -#ifndef __STM32F1__ +/** + * MKS Robin nano (STM32F130VET6) board pin assignments + */ + +#if NOT_TARGET(STM32F1, STM32F1xx) #error "Oops! Select an STM32F1 board in 'Tools > Board.'" #elif HOTENDS > 2 || E_STEPPERS > 2 #error "MKS Robin nano supports up to 2 hotends / E-steppers. Comment out this line to continue." @@ -8,8 +12,10 @@ #define BOARD_INFO_NAME "MKS Robin Nano" -#define DISABLE_DEBUG -#undef JTAGSWD_DISABLE +// +// Release PB4 (Y_ENABLE_PIN) from JTAG NRST role +// +#define DISABLE_JTAG /* Управление подсветкой платой в разъеме второго экструдера @@ -87,7 +93,6 @@ BlTouch #ifndef HEATER_0_PIN #define HEATER_0_PIN PC3 #endif - #if HOTENDS == 1 #ifndef FAN1_PIN #define FAN1_PIN PB0 @@ -97,11 +102,9 @@ BlTouch #define HEATER_1_PIN PB0 #endif #endif - #ifndef FAN_PIN #define FAN_PIN PB1 // FAN #endif - #ifndef HEATER_BED_PIN #define HEATER_BED_PIN PA0 #endif @@ -131,6 +134,8 @@ BlTouch #define WIFI_IO0_PIN PC13 +//#define LED_PIN PB2 + // // SD Card // @@ -183,10 +188,18 @@ BlTouch // LVGL Configs #if ENABLED(TFT_LVGL_UI_FSMC) - #define XPT2046_X_CALIBRATION 17880 - #define XPT2046_Y_CALIBRATION -12234 - #define XPT2046_X_OFFSET -45 - #define XPT2046_Y_OFFSET 349 + #ifndef XPT2046_X_CALIBRATION + #define XPT2046_X_CALIBRATION 17880 + #endif + #ifndef XPT2046_Y_CALIBRATION + #define XPT2046_Y_CALIBRATION -12234 + #endif + #ifndef XPT2046_X_OFFSET + #define XPT2046_X_OFFSET -45 + #endif + #ifndef XPT2046_Y_OFFSET + #define XPT2046_Y_OFFSET 349 + #endif // Emulated DOGM Configs #elif ENABLED(FSMC_GRAPHICAL_TFT) @@ -233,10 +246,18 @@ BlTouch #define FSMC_DMA_DEV DMA2 #define FSMC_DMA_CHANNEL DMA_CH5 - #define XPT2046_X_CALIBRATION -12246 - #define XPT2046_Y_CALIBRATION 9453 - #define XPT2046_X_OFFSET 360 - #define XPT2046_Y_OFFSET -22 + #ifndef XPT2046_X_CALIBRATION + #define XPT2046_X_CALIBRATION -12246 + #endif + #ifndef XPT2046_Y_CALIBRATION + #define XPT2046_Y_CALIBRATION 9453 + #endif + #ifndef XPT2046_X_OFFSET + #define XPT2046_X_OFFSET 360 + #endif + #ifndef XPT2046_Y_OFFSET + #define XPT2046_Y_OFFSET -22 + #endif #define TOUCH_CS_PIN PA7 // SPI2_NSS #define TOUCH_SCK_PIN PB13 // SPI2_SCK @@ -251,11 +272,21 @@ BlTouch // XV for 180° rotated screen mounting #define ILI9341_ORIENTATION ILI9341_MADCTL_MX | ILI9341_MADCTL_MV + #define ILI9341_COLOR_RGB + #elif ENABLED(TFT_480x320) - #define XPT2046_X_CALIBRATION 17880 - #define XPT2046_Y_CALIBRATION -12234 - #define XPT2046_X_OFFSET -45 - #define XPT2046_Y_OFFSET 349 + #ifndef XPT2046_X_CALIBRATION + #define XPT2046_X_CALIBRATION 17880 + #endif + #ifndef XPT2046_Y_CALIBRATION + #define XPT2046_Y_CALIBRATION -12234 + #endif + #ifndef XPT2046_X_OFFSET + #define XPT2046_X_OFFSET -45 + #endif + #ifndef XPT2046_Y_OFFSET + #define XPT2046_Y_OFFSET 349 + #endif #define TFT_DRIVER ILI9488 #define TFT_BUFFER_SIZE 320*15 diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h index 518c140092..65abb7a998 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h @@ -25,7 +25,7 @@ * MKS Robin nano (STM32F130VET6) board pin assignments */ -#ifndef __STM32F1__ +#if NOT_TARGET(__STM32F1__) #error "Oops! Select an STM32F1 board in 'Tools > Board.'" #elif HOTENDS > 2 || E_STEPPERS > 2 #error "MKS Robin nano supports up to 2 hotends / E-steppers. Comment out this line to continue." @@ -144,17 +144,11 @@ https://easyeda.com/sst78rust/fb4s-led-control * Hardware serial communication ports. * If undefined software serial is used according to the pins below */ - //#define X_HARDWARE_SERIAL Serial - //#define X2_HARDWARE_SERIAL Serial1 - //#define Y_HARDWARE_SERIAL Serial1 - //#define Y2_HARDWARE_SERIAL Serial1 - //#define Z_HARDWARE_SERIAL Serial1 - //#define Z2_HARDWARE_SERIAL Serial1 - //#define E0_HARDWARE_SERIAL Serial1 - //#define E1_HARDWARE_SERIAL Serial1 - //#define E2_HARDWARE_SERIAL Serial1 - //#define E3_HARDWARE_SERIAL Serial1 - //#define E4_HARDWARE_SERIAL Serial1 + //#define X_HARDWARE_SERIAL MSerial1 + //#define Y_HARDWARE_SERIAL MSerial1 + //#define Z_HARDWARE_SERIAL MSerial1 + //#define E0_HARDWARE_SERIAL MSerial1 + //#define E1_HARDWARE_SERIAL MSerial1 // // Software serial @@ -194,6 +188,7 @@ https://easyeda.com/sst78rust/fb4s-led-control // Heaters / Fans // #define HEATER_0_PIN PC3 // HEATER1 +#define HEATER_1_PIN PB0 // HEATER2 #define HEATER_BED_PIN PA0 // HOT BED #if HOTENDS == 1 @@ -217,29 +212,37 @@ https://easyeda.com/sst78rust/fb4s-led-control // // Misc. Functions // -#define POWER_LOSS_PIN PA2 // PW_DET -#define PS_ON_PIN PA3 // PW_OFF - -//#define SUICIDE_PIN PB2 // Enable MKSPWC support ROBIN NANO v1.2 ONLY -//#define SUICIDE_PIN_INVERTING false +#if HAS_TFT_LVGL_UI + //#define MKSPWC + #ifdef MKSPWC + #define SUICIDE_PIN PB2 // Enable MKSPWC SUICIDE PIN + #define SUICIDE_PIN_INVERTING false // Enable MKSPWC PIN STATE + #define KILL_PIN PA2 // Enable MKSPWC DET PIN + #define KILL_PIN_STATE true // Enable MKSPWC PIN STATE + #endif -//#define KILL_PIN PA2 // Enable MKSPWC support ROBIN NANO v1.2 ONLY -//#define KILL_PIN_INVERTING true // Enable MKSPWC support ROBIN NANO v1.2 ONLY + #define MT_DET_1_PIN PA4 // LVGL UI FILAMENT RUNOUT1 PIN + #define MT_DET_2_PIN PE6 // LVGL UI FILAMENT RUNOUT2 PIN + #define MT_DET_PIN_INVERTING false // LVGL UI filament RUNOUT PIN STATE -#define SERVO0_PIN PA8 // Enable BLTOUCH support ROBIN NANO v1.2 ONLY + #define WIFI_IO0_PIN PC13 // MKS ESP WIFI IO0 PIN + #define WIFI_IO1_PIN PC7 // MKS ESP WIFI IO1 PIN + #define WIFI_RESET_PIN PE9 // MKS ESP WIFI RESET PIN -//#define LED_PIN PB2 + #if ENABLED(MKS_TEST) + #define MKS_TEST_POWER_LOSS_PIN PA2 // PW_DET + #define MKS_TEST_PS_ON_PIN PB2 // PW_OFF + #endif +#else + //#define POWER_LOSS_PIN PA2 // PW_DET + //#define PS_ON_PIN PB2 // PW_OFF + #define FIL_RUNOUT_PIN PA4 + #define FIL_RUNOUT2_PIN PE6 +#endif -#define MT_DET_1_PIN PA4 -#define MT_DET_2_PIN PE6 -#define MT_DET_PIN_INVERTING false +#define SERVO0_PIN PA8 // Enable BLTOUCH -#ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN MT_DET_1_PIN -#endif -#ifndef FIL_RUNOUT2_PIN - #define FIL_RUNOUT2_PIN MT_DET_2_PIN -#endif +//#define LED_PIN PB2 // // SD Card @@ -256,9 +259,6 @@ https://easyeda.com/sst78rust/fb4s-led-control // // LCD / Controller // -#ifndef BEEPER_PIN - #define BEEPER_PIN PC5 -#endif /** * Note: MKS Robin TFT screens use various TFT controllers. @@ -348,17 +348,25 @@ https://easyeda.com/sst78rust/fb4s-led-control #define LCD_PINS_RS PC6 #elif ENABLED(TFT_480x320_SPI) + #ifndef XPT2046_X_CALIBRATION #define XPT2046_X_CALIBRATION -17253 + #endif + #ifndef XPT2046_Y_CALIBRATION #define XPT2046_Y_CALIBRATION 11579 + #endif + #ifndef XPT2046_X_OFFSET #define XPT2046_X_OFFSET 514 + #endif + #ifndef XPT2046_Y_OFFSET #define XPT2046_Y_OFFSET -24 + #endif #define TFT_DRIVER ST7796 - #define TFT_BUFFER_SIZE 512*15 + #define TFT_BUFFER_SIZE 320*15 #endif -#if HAS_SPI_LCD && !HAS_SPI_TFT +#if HAS_WIRED_LCD && !HAS_SPI_TFT // NON TFT Displays @@ -374,9 +382,18 @@ https://easyeda.com/sst78rust/fb4s-led-control #define DOGLCD_SCK PA5 #define DOGLCD_MOSI PA7 - // Required for MKS_MINI_12864 with this board - #define MKS_LCD12864B - #undef SHOW_BOOTSCREEN + #elif IS_TFTGLCD_PANEL + + #if ENABLED(TFTGLCD_PANEL_SPI) + #define PIN_SPI_SCK PA5 + #define PIN_TFT_MISO PA6 + #define PIN_TFT_MOSI PA7 + #define TFTGLCD_CS PE8 + #endif + + #ifndef BEEPER_PIN + #define BEEPER_PIN -1 + #endif #else // !MKS_MINI_12864 @@ -399,7 +416,7 @@ https://easyeda.com/sst78rust/fb4s-led-control #endif // !MKS_MINI_12864 -#endif // HAS_SPI_LCD && !HAS_SPI_TFT +#endif // HAS_WIRED_LCD && !HAS_SPI_TFT #define HAS_SPI_FLASH 1 #define SPI_FLASH_SIZE 0x1000000 // 16MB @@ -410,6 +427,10 @@ https://easyeda.com/sst78rust/fb4s-led-control #define W25QXX_SCK_PIN PB13 #endif +#ifndef BEEPER_PIN + #define BEEPER_PIN PC5 +#endif + #if ENABLED(SPEAKER) && BEEPER_PIN == PC5 #error "MKS Robin nano default BEEPER_PIN is not a SPEAKER." #endif diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h index c00466677a..12c40b31b3 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h @@ -25,7 +25,7 @@ * MKS Robin pro (STM32F103ZET6) board pin assignments */ -#ifndef __STM32F1__ +#if NOT_TARGET(__STM32F1__) #error "Oops! Select an STM32F1 board in 'Tools > Board.'" #elif HOTENDS > 3 || E_STEPPERS > 3 #error "MKS Robin pro supports up to 3 hotends / E-steppers. Comment out this line to continue." @@ -125,17 +125,12 @@ * Hardware serial communication ports. * If undefined software serial is used according to the pins below */ - //#define X_HARDWARE_SERIAL Serial - //#define X2_HARDWARE_SERIAL Serial1 - //#define Y_HARDWARE_SERIAL Serial1 - //#define Y2_HARDWARE_SERIAL Serial1 - //#define Z_HARDWARE_SERIAL Serial1 - //#define Z2_HARDWARE_SERIAL Serial1 - //#define E0_HARDWARE_SERIAL Serial1 - //#define E1_HARDWARE_SERIAL Serial1 - //#define E2_HARDWARE_SERIAL Serial1 - //#define E3_HARDWARE_SERIAL Serial1 - //#define E4_HARDWARE_SERIAL Serial1 + //#define X_HARDWARE_SERIAL MSerial1 + //#define Y_HARDWARE_SERIAL MSerial1 + //#define Z_HARDWARE_SERIAL MSerial1 + //#define E0_HARDWARE_SERIAL MSerial1 + //#define E1_HARDWARE_SERIAL MSerial1 + //#define E2_HARDWARE_SERIAL MSerial1 // // Software serial @@ -230,7 +225,13 @@ #define BTN_EN2 PG4 #endif -#elif HAS_SPI_LCD +#elif IS_TFTGLCD_PANEL + + #if ENABLED(TFTGLCD_PANEL_SPI) + #define TFTGLCD_CS PG5 + #endif + +#elif HAS_WIRED_LCD #define BEEPER_PIN PC5 #define BTN_ENC PG2 @@ -259,6 +260,7 @@ #endif #endif // !MKS_MINI_12864 && !ENDER2_STOCKDISPLAY + #endif #ifndef BOARD_ST7920_DELAY_1 diff --git a/Marlin/src/pins/stm32f1/pins_MORPHEUS.h b/Marlin/src/pins/stm32f1/pins_MORPHEUS.h index 1cd3780ec5..28262eaa82 100644 --- a/Marlin/src/pins/stm32f1/pins_MORPHEUS.h +++ b/Marlin/src/pins/stm32f1/pins_MORPHEUS.h @@ -30,7 +30,7 @@ * MORPHEUS Board pin assignments */ -#ifndef __STM32F1__ +#if NOT_TARGET(__STM32F1__) #error "Oops! Select an STM32F1 board in 'Tools > Board.'" #endif diff --git a/Marlin/src/pins/stm32f1/pins_STM32F1R.h b/Marlin/src/pins/stm32f1/pins_STM32F1R.h index 63fb383c9b..cf2ba2c5fa 100644 --- a/Marlin/src/pins/stm32f1/pins_STM32F1R.h +++ b/Marlin/src/pins/stm32f1/pins_STM32F1R.h @@ -21,7 +21,7 @@ */ #pragma once -#ifndef __STM32F1__ +#if NOT_TARGET(__STM32F1__) #error "Oops! Select an STM32F1 board in 'Tools > Board.'" #endif @@ -97,7 +97,7 @@ // // LCD Pins // -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #if ENABLED(REPRAPWORLD_GRAPHICAL_LCD) #define LCD_PINS_RS 49 // CS chip select /SS chip slave select @@ -258,4 +258,4 @@ #endif #endif // NEWPANEL -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/stm32f1/pins_STM3R_MINI.h b/Marlin/src/pins/stm32f1/pins_STM3R_MINI.h index c18642fb1d..e74698f89e 100644 --- a/Marlin/src/pins/stm32f1/pins_STM3R_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_STM3R_MINI.h @@ -21,7 +21,7 @@ */ #pragma once -#if !defined(__STM32F1__) && !defined(__STM32F4__) +#if NOT_TARGET(__STM32F1__, __STM32F4__) #error "Oops! Select an STM32F1/4 board in 'Tools > Board.'" #endif @@ -112,7 +112,7 @@ // // LCD Pins // -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #if ENABLED(REPRAPWORLD_GRAPHICAL_LCD) #define LCD_PINS_RS 49 // CS chip select /SS chip slave select @@ -282,4 +282,4 @@ #endif #endif // NEWPANEL -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/stm32f1/pins_TRIGORILLA_PRO.h b/Marlin/src/pins/stm32f1/pins_TRIGORILLA_PRO.h index 598db026fd..4745641ea9 100644 --- a/Marlin/src/pins/stm32f1/pins_TRIGORILLA_PRO.h +++ b/Marlin/src/pins/stm32f1/pins_TRIGORILLA_PRO.h @@ -28,7 +28,7 @@ * https://github.com/MarlinFirmware/Marlin/files/3401484/x5sa-main_board-2.pdf */ -#ifndef __STM32F1__ +#if NOT_TARGET(__STM32F1__) #error "Oops! Select an STM32F1 board in 'Tools > Board.'" #elif HOTENDS > 2 || E_STEPPERS > 2 #error "Trigorilla Pro supports up to 2 hotends / E-steppers. Comment out this line to continue." diff --git a/Marlin/src/pins/stm32f4/pins_ARMED.h b/Marlin/src/pins/stm32f4/pins_ARMED.h index 6962416936..db57db14d5 100644 --- a/Marlin/src/pins/stm32f4/pins_ARMED.h +++ b/Marlin/src/pins/stm32f4/pins_ARMED.h @@ -24,7 +24,7 @@ #pragma once -#ifndef STM32F4 +#if NOT_TARGET(STM32F4) #error "Oops! Select an STM32F4 board in 'Tools > Board.'" #elif HOTENDS > 2 || E_STEPPERS > 2 #error "Arm'ed supports up to 2 hotends / E-steppers." diff --git a/Marlin/src/pins/stm32f4/pins_BEAST.h b/Marlin/src/pins/stm32f4/pins_BEAST.h index 691b468c34..268b7b59cd 100644 --- a/Marlin/src/pins/stm32f4/pins_BEAST.h +++ b/Marlin/src/pins/stm32f4/pins_BEAST.h @@ -21,7 +21,7 @@ */ #pragma once -#if !defined(__STM32F1__) && !defined(__STM32F4__) +#if NOT_TARGET(__STM32F1__, __STM32F4__) #error "Oops! Select an STM32F1/4 board in 'Tools > Board.'" #endif @@ -120,7 +120,7 @@ // // LCD Pins // -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #if ENABLED(REPRAPWORLD_GRAPHICAL_LCD) #define LCD_PINS_RS 49 // CS chip select /SS chip slave select @@ -282,4 +282,4 @@ #endif #endif // NEWPANEL -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/stm32f4/pins_BLACK_STM32F407VE.h b/Marlin/src/pins/stm32f4/pins_BLACK_STM32F407VE.h index dc0dab1cd1..b13d495542 100644 --- a/Marlin/src/pins/stm32f4/pins_BLACK_STM32F407VE.h +++ b/Marlin/src/pins/stm32f4/pins_BLACK_STM32F407VE.h @@ -27,7 +27,7 @@ * Shield - https://github.com/jmz52/Hardware */ -#if !defined(STM32F4) && !defined(STM32F4xx) +#if NOT_TARGET(STM32F4, STM32F4xx) #error "Oops! Select an STM32F4 board in 'Tools > Board.'" #elif HOTENDS > 2 || E_STEPPERS > 2 #error "Black STM32F4VET6 supports up to 2 hotends / E-steppers." diff --git a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h index d3510b1ff8..c37f6cce04 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h @@ -21,7 +21,7 @@ */ #pragma once -#ifndef TARGET_STM32F4 +#if NOT_TARGET(STM32F4) #error "Oops! Select an STM32F4 board in 'Tools > Board.'" #elif HOTENDS > 1 || E_STEPPERS > 1 #error "BIGTREE BTT002 V1.0 supports up to 1 hotends / E-steppers." @@ -187,21 +187,22 @@ #define SDSS PA4 /** - * -------------------------------------BTT002 V1.0----------------------------------------------- - * _____ _____ | + * -------------------------------------BTT002 V1.0-------------------------------------------- + * ----- ----- | * PA3 | · · | GND 5V | · · | GND | * NRESET | · · | PC4(SD_DET) (LCD_D7) PE13 | · · | PE12 (LCD_D6) | * (MOSI)PA7 | · · | PB0(BTN_EN2) (LCD_D5) PE11 | · · | PE10 (LCD_D4) | * (SD_SS)PA4 | · · | PC5(BTN_EN1) (LCD_RS) PE8 | · · | PE9 (LCD_EN) | * (SCK)PA5 | · · | PA6(MISO) (BTN_ENC) PB1 | · · | PE7 (BEEPER) | - *  ̄ ̄  ̄ ̄ | + * ----- ----- | * EXP2 EXP1 | - * --------------------------------------------------------------------------------------------- + * -------------------------------------------------------------------------------------------- */ + // // LCDs and Controllers // -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #define BEEPER_PIN PE7 #define BTN_ENC PB1 @@ -236,7 +237,7 @@ #endif // Alter timing for graphical display - #if HAS_GRAPHICAL_LCD + #if HAS_MARLINUI_U8GLIB #ifndef BOARD_ST7920_DELAY_1 #define BOARD_ST7920_DELAY_1 DELAY_NS(96) #endif @@ -248,7 +249,7 @@ #endif #endif -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD // // RGB LEDs diff --git a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h index ea643322b6..dc8ce9f2d1 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h @@ -21,7 +21,7 @@ */ #pragma once -#ifndef TARGET_STM32F4 +#if NOT_TARGET(STM32F4) #error "Oops! Select an STM32F4 board in 'Tools > Board.'" #elif HOTENDS > 8 || E_STEPPERS > 8 #error "BIGTREE GTR V1.0 supports up to 8 hotends / E-steppers." @@ -171,7 +171,7 @@ * Hardware serial communication ports. * If undefined software serial is used according to the pins below */ - //#define X_HARDWARE_SERIAL Serial + //#define X_HARDWARE_SERIAL Serial1 //#define X2_HARDWARE_SERIAL Serial1 //#define Y_HARDWARE_SERIAL Serial1 //#define Y2_HARDWARE_SERIAL Serial1 @@ -290,9 +290,12 @@ // overriding pins to access. // #if SD_CONNECTION_IS(LCD) + #define SD_DETECT_PIN PB10 #define SDSS PB12 + #elif SD_CONNECTION_IS(ONBOARD) + // Instruct the STM32 HAL to override the default SPI pins from the variant.h file #define CUSTOM_SPI_PINS #define SDSS PA4 @@ -301,25 +304,26 @@ #define MISO_PIN PA6 #define MOSI_PIN PA7 #define SD_DETECT_PIN PC4 + #elif SD_CONNECTION_IS(CUSTOM_CABLE) - #define "CUSTOM_CABLE is not a supported SDCARD_CONNECTION for this board" + #error "CUSTOM_CABLE is not a supported SDCARD_CONNECTION for this board" #endif /** - * _____ _____ + * ----- ----- * NC | · · | GND 5V | · · | GND * RESET | · · | PB10(SD_DETECT) (LCD_D7) PG5 | · · | PG6 (LCD_D6) * (MOSI)PB15 | · · | PH10(BTN_EN2) (LCD_D5) PG7 | · · | PG8 (LCD_D4) * (SD_SS)PB12 | · · | PD10(BTN_EN1) (LCD_RS) PA8 | · · | PC10 (LCD_EN) * (SCK)PB13 | · · | PB14(MISO) (BTN_ENC) PA15 | · · | PC11 (BEEPER) - *  ̄ ̄  ̄ ̄ + * ----- ----- * EXP2 EXP1 */ // // LCDs and Controllers // -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #define BEEPER_PIN PC11 #define BTN_ENC PA15 @@ -390,7 +394,7 @@ #endif // Alter timing for graphical display - #if HAS_GRAPHICAL_LCD + #if HAS_MARLINUI_U8GLIB #ifndef BOARD_ST7920_DELAY_1 #define BOARD_ST7920_DELAY_1 DELAY_NS(96) #endif @@ -402,6 +406,6 @@ #endif #endif -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD #undef TP diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h index 56c509562f..1cd7e9dd89 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h @@ -21,7 +21,7 @@ */ #pragma once -#ifndef TARGET_STM32F4 +#if NOT_TARGET(STM32F4) #error "Oops! Select an STM32F4 board in 'Tools > Board.'" #endif @@ -178,7 +178,7 @@ * Hardware serial communication ports. * If undefined software serial is used according to the pins below */ - //#define X_HARDWARE_SERIAL Serial + //#define X_HARDWARE_SERIAL Serial1 //#define X2_HARDWARE_SERIAL Serial1 //#define Y_HARDWARE_SERIAL Serial1 //#define Y2_HARDWARE_SERIAL Serial1 @@ -251,9 +251,12 @@ // Must use soft SPI because Marlin's default hardware SPI is tied to LCD's EXP2 // #if SD_CONNECTION_IS(LCD) + #define SD_DETECT_PIN PF12 #define SDSS PB12 + #elif SD_CONNECTION_IS(ONBOARD) + // The SKR Pro's ONBOARD SD interface is on SPI1. // Due to a pull resistor on the clock line, it needs to use SPI Data Mode 3 to // function with Hardware SPI. This is not currently configurable in the HAL, @@ -264,29 +267,38 @@ #define MISO_PIN PA6 #define MOSI_PIN PB5 #define SD_DETECT_PIN PB11 + #elif SD_CONNECTION_IS(CUSTOM_CABLE) - #define "CUSTOM_CABLE is not a supported SDCARD_CONNECTION for this board" + #error "CUSTOM_CABLE is not a supported SDCARD_CONNECTION for this board" #endif /** - * _____ _____ + * ----- ----- * NC | · · | GND 5V | · · | GND * RESET | · · | PF12(SD_DETECT) (LCD_D7) PG7 | · · | PG6 (LCD_D6) * (MOSI)PB15 | · · | PF11(BTN_EN2) (LCD_D5) PG3 | · · | PG2 (LCD_D4) * (SD_SS)PB12 | · · | PG10(BTN_EN1) (LCD_RS) PD10 | · · | PD11 (LCD_EN) * (SCK)PB13 | · · | PB14(MISO) (BTN_ENC) PA8 | · · | PG4 (BEEPER) - *  ̄ ̄  ̄ ̄ + * ----- ----- * EXP2 EXP1 */ // // LCDs and Controllers // -#if HAS_SPI_LCD +#if IS_TFTGLCD_PANEL + + #if ENABLED(TFTGLCD_PANEL_SPI) + #define TFTGLCD_CS PG10 + #endif + +#elif HAS_WIRED_LCD + #define BEEPER_PIN PG4 #define BTN_ENC PA8 #if ENABLED(CR10_STOCKDISPLAY) + #define LCD_PINS_RS PG6 #define BTN_EN1 PD11 @@ -301,10 +313,12 @@ #undef BOARD_ST7920_DELAY_3 #elif ENABLED(MKS_MINI_12864) + #define DOGLCD_A0 PG6 #define DOGLCD_CS PG3 #define BTN_EN1 PG10 #define BTN_EN2 PF11 + #else #define LCD_PINS_RS PD10 @@ -343,32 +357,32 @@ #endif - // Alter timing for graphical display - #if HAS_GRAPHICAL_LCD - #ifndef BOARD_ST7920_DELAY_1 - #define BOARD_ST7920_DELAY_1 DELAY_NS(96) - #endif - #ifndef BOARD_ST7920_DELAY_2 - #define BOARD_ST7920_DELAY_2 DELAY_NS(48) - #endif - #ifndef BOARD_ST7920_DELAY_3 - #define BOARD_ST7920_DELAY_3 DELAY_NS(600) - #endif - #endif +#endif // HAS_WIRED_LCD -#endif // HAS_SPI_LCD +// Alter timing for graphical display +#if HAS_MARLINUI_U8GLIB + #ifndef BOARD_ST7920_DELAY_1 + #define BOARD_ST7920_DELAY_1 DELAY_NS(96) + #endif + #ifndef BOARD_ST7920_DELAY_2 + #define BOARD_ST7920_DELAY_2 DELAY_NS(48) + #endif + #ifndef BOARD_ST7920_DELAY_3 + #define BOARD_ST7920_DELAY_3 DELAY_NS(600) + #endif +#endif // // WIFI // /** - * _____ + * ----- * TX | 1 2 | GND Enable PG1 // Must be high for module to run * Enable | 3 4 | GPIO2 Reset PG0 // active low, probably OK to leave floating * Reset | 5 6 | GPIO0 GPIO2 PF15 // must be high (ESP3D software configures this with a pullup so OK to leave as floating) - * 3.3V| 7 8 | RX GPIO0 PF14 // Leave as unused (ESP3D software configures this with a pullup so OK to leave as floating) - *  ̄ ̄ + * 3.3V | 7 8 | RX GPIO0 PF14 // Leave as unused (ESP3D software configures this with a pullup so OK to leave as floating) + * ----- * W1 */ #define ESP_WIFI_MODULE_COM 6 // Must also set either SERIAL_PORT or SERIAL_PORT_2 to this diff --git a/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h b/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h index a3a5ccdff8..808751d7a5 100644 --- a/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h +++ b/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h @@ -21,7 +21,7 @@ */ #pragma once -#if !defined(STM32F4) && !defined(STM32F4xx) +#if NOT_TARGET(STM32F4, STM32F4xx) #error "Oops! Select an STM32F4 board in 'Tools > Board.'" #elif HOTENDS > 6 || E_STEPPERS > 6 #error "FLYF407ZG supports up to 6 hotends / E-steppers." diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h index 9ffedc2ac4..151f6c3bc0 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h @@ -21,7 +21,7 @@ */ #pragma once -#ifndef STM32F4 +#if NOT_TARGET(STM32F4) #error "Oops! Select an STM32F4 board in 'Tools > Board.'" #elif HOTENDS > 3 || E_STEPPERS > 3 #error "RUMBA32 supports up to 3 hotends / E-steppers." @@ -199,7 +199,7 @@ // // LCD / Controller // -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #define BEEPER_PIN PC9 #define BTN_ENC PA8 @@ -261,7 +261,7 @@ #endif // Alter timing for graphical display - #if HAS_GRAPHICAL_LCD + #if HAS_MARLINUI_U8GLIB #ifndef BOARD_ST7920_DELAY_1 #define BOARD_ST7920_DELAY_1 DELAY_NS(96) #endif @@ -273,7 +273,7 @@ #endif #endif -#endif // HAS_SPI_LCD +#endif // HAS_WIRED_LCD #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN PB6 diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_S6_V2_0.h b/Marlin/src/pins/stm32f4/pins_FYSETC_S6_V2_0.h index 6cd970501f..021ef1d5f6 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_S6_V2_0.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_S6_V2_0.h @@ -16,7 +16,7 @@ * 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 . + * along with this program. If not, see . * */ #pragma once diff --git a/Marlin/src/pins/stm32f4/pins_GENERIC_STM32F4.h b/Marlin/src/pins/stm32f4/pins_GENERIC_STM32F4.h index 44b2e6b27c..4acfd743b7 100644 --- a/Marlin/src/pins/stm32f4/pins_GENERIC_STM32F4.h +++ b/Marlin/src/pins/stm32f4/pins_GENERIC_STM32F4.h @@ -25,7 +25,7 @@ * To build with Arduino IDE use "Discovery F407VG" * To build with PlatformIO use environment "STM32F4" */ -#if !defined(STM32F4) && !defined(STM32F4xx) +#if NOT_TARGET(STM32F4, STM32F4xx) #error "Oops! Select an STM32F4 board in 'Tools > Board.'" #elif HOTENDS > 2 || E_STEPPERS > 2 #error "STM32F4 supports up to 2 hotends / E-steppers." @@ -184,7 +184,7 @@ // // ST7920 Delays // -#if HAS_GRAPHICAL_LCD +#if HAS_MARLINUI_U8GLIB #ifndef BOARD_ST7920_DELAY_1 #define BOARD_ST7920_DELAY_1 DELAY_NS(96) #endif diff --git a/Marlin/src/pins/stm32f4/pins_LERDGE_K.h b/Marlin/src/pins/stm32f4/pins_LERDGE_K.h index 0f0d3d048c..48973688a0 100644 --- a/Marlin/src/pins/stm32f4/pins_LERDGE_K.h +++ b/Marlin/src/pins/stm32f4/pins_LERDGE_K.h @@ -18,7 +18,7 @@ */ #pragma once -#if !defined(STM32F4) && !defined(STM32F4xx) +#if NOT_TARGET(STM32F4, STM32F4xx) #error "Oops! Select an STM32F4 board in 'Tools > Board.'" #elif HOTENDS > 2 || E_STEPPERS > 2 #error "LERDGE K supports up to 2 hotends / E-steppers." diff --git a/Marlin/src/pins/stm32f4/pins_LERDGE_S.h b/Marlin/src/pins/stm32f4/pins_LERDGE_S.h index 2e55782edb..0600ed4338 100644 --- a/Marlin/src/pins/stm32f4/pins_LERDGE_S.h +++ b/Marlin/src/pins/stm32f4/pins_LERDGE_S.h @@ -18,7 +18,7 @@ */ #pragma once -#if !defined(STM32F4) && !defined(STM32F4xx) +#if NOT_TARGET(STM32F4, STM32F4xx) #error "Oops! Select an STM32F4 board in 'Tools > Board.'" #elif HOTENDS > 2 || E_STEPPERS > 2 #error "LERDGE S supports up to 2 hotends / E-steppers." diff --git a/Marlin/src/pins/stm32f4/pins_LERDGE_X.h b/Marlin/src/pins/stm32f4/pins_LERDGE_X.h index da2851c131..bed51ca660 100644 --- a/Marlin/src/pins/stm32f4/pins_LERDGE_X.h +++ b/Marlin/src/pins/stm32f4/pins_LERDGE_X.h @@ -18,7 +18,7 @@ */ #pragma once -#if !defined(STM32F4) && !defined(STM32F4xx) +#if NOT_TARGET(STM32F4, STM32F4xx) #error "Oops! Select an STM32F4 board in 'Tools > Board.'" #elif HOTENDS > 1 || E_STEPPERS > 1 #error "LERDGE X supports only one hotend / E-steppers" diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN2.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN2.h index bb04cb82ec..c2f5f324ba 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN2.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN2.h @@ -21,7 +21,7 @@ */ #pragma once -#ifndef STM32F4 +#if NOT_TARGET(STM32F4) #error "Oops! Select an STM32F4 board in 'Tools > Board.'" #elif HOTENDS > 2 || E_STEPPERS > 2 #error "MKS_ROBIN2 supports up to 2 hotends / E-steppers." diff --git a/Marlin/src/pins/stm32f4/pins_RUMBA32_MKS.h b/Marlin/src/pins/stm32f4/pins_RUMBA32_MKS.h index fe6e559bdb..ab277d4372 100644 --- a/Marlin/src/pins/stm32f4/pins_RUMBA32_MKS.h +++ b/Marlin/src/pins/stm32f4/pins_RUMBA32_MKS.h @@ -57,7 +57,7 @@ * Hardware serial communication ports. * If undefined software serial is used according to the pins below */ - //#define X_HARDWARE_SERIAL Serial + //#define X_HARDWARE_SERIAL Serial1 //#define X2_HARDWARE_SERIAL Serial1 //#define Y_HARDWARE_SERIAL Serial1 //#define Y2_HARDWARE_SERIAL Serial1 diff --git a/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h b/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h index 3b513b31ca..d52bb11d12 100644 --- a/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h +++ b/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h @@ -23,10 +23,9 @@ /** * Common pin assignments for all RUMBA32 boards - * */ -#ifndef STM32F4 +#if NOT_TARGET(STM32F4) #error "Oops! Select an STM32F4 board in 'Tools > Board.'" #elif HOTENDS > 3 || E_STEPPERS > 3 #error "RUMBA32 boards support up to 3 hotends / E-steppers." @@ -42,11 +41,12 @@ // Configure Timers // TIM6 is used for TONE // TIM7 is used for SERVO -// TIMER_SERIAL defaults to TIM7 so we'll override it here -// -#define STEP_TIMER 10 -#define TEMP_TIMER 14 -#define TIMER_SERIAL TIM9 +// TIMER_SERIAL defaults to TIM7 and must be overridden in the platformio.h file if SERVO will also be used. +// This will be difficult to solve from the Arduino IDE, without modifying the RUMBA32 variant +// included with the STM32 framework. + +#define STEP_TIMER 10 +#define TEMP_TIMER 14 #define HAL_TIMER_RATE F_CPU // @@ -146,7 +146,7 @@ // // LCD / Controller // -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #define BTN_EN1 PB2 #define BTN_EN2 PB1 @@ -168,7 +168,7 @@ #endif // Alter timing for graphical display - #if HAS_GRAPHICAL_LCD + #if HAS_MARLINUI_U8GLIB #ifndef BOARD_ST7920_DELAY_1 #define BOARD_ST7920_DELAY_1 DELAY_NS(96) #endif diff --git a/Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h b/Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h index a0bd38b6ac..0278dd8434 100644 --- a/Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h +++ b/Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h @@ -40,7 +40,7 @@ #pragma once -#ifndef STM32F4 +#if NOT_TARGET(STM32F4) #error "Oops! Select an STM32F4 board in 'Tools > Board.'" #endif diff --git a/Marlin/src/pins/stm32f4/pins_VAKE403D.h b/Marlin/src/pins/stm32f4/pins_VAKE403D.h index 1ffe25b499..e2463fd47e 100644 --- a/Marlin/src/pins/stm32f4/pins_VAKE403D.h +++ b/Marlin/src/pins/stm32f4/pins_VAKE403D.h @@ -21,7 +21,7 @@ */ #pragma once -#if !defined(STM32F4) && !defined(STM32F4xx) +#if NOT_TARGET(STM32F4, STM32F4xx) #error "Oops! Select an STM32F4 board in 'Tools > Board.'" #elif HOTENDS > 2 || E_STEPPERS > 2 #error "STM32F4 supports up to 2 hotends / E-steppers." @@ -165,7 +165,7 @@ // // LCD / Controller // -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #if ENABLED(SDSUPPORT) #define SDSS PB6 // CS for SD card in LCD #endif diff --git a/Marlin/src/pins/stm32f7/pins_REMRAM_V1.h b/Marlin/src/pins/stm32f7/pins_REMRAM_V1.h index 6706d26f64..c3dc004728 100644 --- a/Marlin/src/pins/stm32f7/pins_REMRAM_V1.h +++ b/Marlin/src/pins/stm32f7/pins_REMRAM_V1.h @@ -21,7 +21,7 @@ */ #pragma once -#ifndef STM32F7xx +#if NOT_TARGET(STM32F7xx) #error "Oops! Select an STM32F7 board in 'Tools > Board.'" #endif diff --git a/Marlin/src/pins/stm32f7/pins_THE_BORG.h b/Marlin/src/pins/stm32f7/pins_THE_BORG.h index 756f495e4b..c050824a83 100644 --- a/Marlin/src/pins/stm32f7/pins_THE_BORG.h +++ b/Marlin/src/pins/stm32f7/pins_THE_BORG.h @@ -21,7 +21,7 @@ */ #pragma once -#ifndef STM32F7 +#if NOT_TARGET(STM32F7) #error "Oops! Select an STM32F7 board in 'Tools > Board.'" #elif HOTENDS > 3 || E_STEPPERS > 3 #error "The-Borg supports up to 3 hotends / E-steppers." diff --git a/Marlin/src/pins/teensy2/pins_5DPRINT.h b/Marlin/src/pins/teensy2/pins_5DPRINT.h index 7ba1fbcf8d..908e12e0ba 100644 --- a/Marlin/src/pins/teensy2/pins_5DPRINT.h +++ b/Marlin/src/pins/teensy2/pins_5DPRINT.h @@ -68,7 +68,7 @@ * https://bitbucket.org/makible/5dprint-d8-controller-board */ -#ifndef __AVR_AT90USB1286__ +#if NOT_TARGET(__AVR_AT90USB1286__) #error "Oops! Select 'Teensy++ 2.0' or 'Printrboard' in 'Tools > Board.'" #endif diff --git a/Marlin/src/pins/teensy2/pins_BRAINWAVE.h b/Marlin/src/pins/teensy2/pins_BRAINWAVE.h index ce1b4e3bbf..97d210a0f8 100644 --- a/Marlin/src/pins/teensy2/pins_BRAINWAVE.h +++ b/Marlin/src/pins/teensy2/pins_BRAINWAVE.h @@ -68,7 +68,7 @@ * 4. The programmer is no longer needed. Remove it. */ -#ifndef __AVR_AT90USB646__ +#if NOT_TARGET(__AVR_AT90USB646__) #error "Oops! Select 'AT90USB646_TEENSYPP' in 'Tools > Board.'" #endif diff --git a/Marlin/src/pins/teensy2/pins_BRAINWAVE_PRO.h b/Marlin/src/pins/teensy2/pins_BRAINWAVE_PRO.h index eeca39c14c..e41fcaab94 100644 --- a/Marlin/src/pins/teensy2/pins_BRAINWAVE_PRO.h +++ b/Marlin/src/pins/teensy2/pins_BRAINWAVE_PRO.h @@ -75,7 +75,7 @@ * 4. The programmer is no longer needed. Remove it. */ -#ifndef __AVR_AT90USB1286__ +#if NOT_TARGET(__AVR_AT90USB1286__) #error "Oops! Select 'Teensy++ 2.0' or 'Printrboard' in 'Tools > Board.'" #endif diff --git a/Marlin/src/pins/teensy2/pins_PRINTRBOARD.h b/Marlin/src/pins/teensy2/pins_PRINTRBOARD.h index 51080b2fd1..ffecc03b4a 100644 --- a/Marlin/src/pins/teensy2/pins_PRINTRBOARD.h +++ b/Marlin/src/pins/teensy2/pins_PRINTRBOARD.h @@ -62,7 +62,7 @@ * 4. The programmer is no longer needed. Remove it. */ -#ifndef __AVR_AT90USB1286__ +#if NOT_TARGET(__AVR_AT90USB1286__) #error "Oops! Select 'Teensy++ 2.0' or 'Printrboard' in 'Tools > Board.'" #endif @@ -166,4 +166,4 @@ #endif -#endif // HAS_SPI_LCD && NEWPANEL +#endif // ULTRA_LCD && NEWPANEL diff --git a/Marlin/src/pins/teensy2/pins_PRINTRBOARD_REVF.h b/Marlin/src/pins/teensy2/pins_PRINTRBOARD_REVF.h index 83b17b6560..6ffd35dff2 100644 --- a/Marlin/src/pins/teensy2/pins_PRINTRBOARD_REVF.h +++ b/Marlin/src/pins/teensy2/pins_PRINTRBOARD_REVF.h @@ -63,7 +63,7 @@ * 4. The programmer is no longer needed. Remove it. */ -#ifndef __AVR_AT90USB1286__ +#if NOT_TARGET(__AVR_AT90USB1286__) #error "Oops! Select 'Teensy++ 2.0' or 'Printrboard' in 'Tools > Board.'" #endif @@ -201,7 +201,7 @@ // //#define USE_INTERNAL_SD -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #define LCD_PINS_RS 9 // E1 JP11-11 #define LCD_PINS_ENABLE 8 // E0 JP11-10 #define LCD_PINS_D4 7 // D7 JP11-8 diff --git a/Marlin/src/pins/teensy2/pins_SAV_MKI.h b/Marlin/src/pins/teensy2/pins_SAV_MKI.h index cdd9b634bd..4d083ecd12 100644 --- a/Marlin/src/pins/teensy2/pins_SAV_MKI.h +++ b/Marlin/src/pins/teensy2/pins_SAV_MKI.h @@ -62,7 +62,7 @@ * 4. The programmer is no longer needed. Remove it. */ -#ifndef __AVR_AT90USB1286__ +#if NOT_TARGET(__AVR_AT90USB1286__) #error "Oops! Select 'Teensy++ 2.0' or 'Printrboard' in 'Tools > Board.'" #endif diff --git a/Marlin/src/pins/teensy2/pins_TEENSY2.h b/Marlin/src/pins/teensy2/pins_TEENSY2.h index 9ef31e84ba..4efd83d9bc 100644 --- a/Marlin/src/pins/teensy2/pins_TEENSY2.h +++ b/Marlin/src/pins/teensy2/pins_TEENSY2.h @@ -107,7 +107,7 @@ * E DIR 35 a7 a3 31 Y DIR */ -#ifndef __AVR_AT90USB1286__ +#if NOT_TARGET(__AVR_AT90USB1286__) #error "Oops! Select 'Teensy++ 2.0' or 'Printrboard' in 'Tools > Board.'" #endif diff --git a/Marlin/src/pins/teensy2/pins_TEENSYLU.h b/Marlin/src/pins/teensy2/pins_TEENSYLU.h index 8ee07a427d..9de119b62b 100644 --- a/Marlin/src/pins/teensy2/pins_TEENSYLU.h +++ b/Marlin/src/pins/teensy2/pins_TEENSYLU.h @@ -17,7 +17,6 @@ * * You should have received a copy of the GNU General Public License * along with this program. If not, see . - * */ /** @@ -73,7 +72,7 @@ * The pin assignments in this file match the silkscreen. */ -#if !defined(__AVR_AT90USB1286__) && !defined(__AVR_AT90USB1286P__) +#if NOT_TARGET(__AVR_AT90USB1286__, __AVR_AT90USB1286P__) #error "Oops! Select 'Teensy++ 2.0' or 'Printrboard' in 'Tools > Board.'" #endif @@ -155,7 +154,7 @@ #define SD_DETECT_PIN -1 -#endif // HAS_SPI_LCD && NEWPANEL +#endif // ULTRA_LCD && NEWPANEL // // M3/M4/M5 - Spindle/Laser Control diff --git a/Marlin/src/pins/teensy3/pins_TEENSY31_32.h b/Marlin/src/pins/teensy3/pins_TEENSY31_32.h index 863137e9c8..45d1231f8e 100644 --- a/Marlin/src/pins/teensy3/pins_TEENSY31_32.h +++ b/Marlin/src/pins/teensy3/pins_TEENSY31_32.h @@ -27,7 +27,7 @@ * https://www.pjrc.com/teensy/teensyduino.html */ -#if !IS_32BIT_TEENSY +#if NOT_TARGET(IS_32BIT_TEENSY) #error "Oops! Select 'Teensy 3.1' or 'Teensy 3.2' in 'Tools > Board.'" #endif @@ -35,9 +35,6 @@ #define BOARD_INFO_NAME "Teensy3.2" #endif -#define AT90USB 1286 // Disable MarlinSerial etc. -#define USBCON //1286 // Disable MarlinSerial etc. - // // Limit Switches // @@ -92,22 +89,16 @@ // // Misc. Functions // - -//#define SDSS 16 // 8 #define LED_PIN 13 - //#define SOL1_PIN 28 +//#define SDSS 16 // 8 // // LCD / Controller // -//#define SCK_PIN 13 -//#define MISO_PIN 12 -//#define MOSI_PIN 11 - /* -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #define LCD_PINS_RS 40 #define LCD_PINS_ENABLE 41 #define LCD_PINS_D4 42 diff --git a/Marlin/src/pins/teensy3/pins_TEENSY35_36.h b/Marlin/src/pins/teensy3/pins_TEENSY35_36.h index 02d8374f23..b1cd3d1612 100644 --- a/Marlin/src/pins/teensy3/pins_TEENSY35_36.h +++ b/Marlin/src/pins/teensy3/pins_TEENSY35_36.h @@ -27,7 +27,7 @@ * https://www.pjrc.com/teensy/teensyduino.html ****************************************************************************************/ -#if !IS_32BIT_TEENSY +#if NOT_TARGET(IS_32BIT_TEENSY) #error "Oops! Select 'Teensy 3.5' or 'Teensy 3.6' in 'Tools > Board.'" #endif @@ -37,48 +37,44 @@ #define BOARD_INFO_NAME "Teensy3.6" #endif -#define AT90USB 1286 // Disable MarlinSerial etc. -#define USBCON //1286 // Disable MarlinSerial etc. -/* - - teemuatlut plan for Teensy3.5 and Teensy3.6: - USB - GND |-----#####-----| VIN 5V - X_STEP_PIN MOSI1 RX1 0 | ##### | Analog GND - X_DIR_PIN MISO1 TX1 1 | | 3.3V - Y_STEP_PIN PWM 2 | *NC AREF* | 23 A9 PWM - Y_DIR_PIN SCL2 CAN0TX PWM 3 | *A26 A10* | 22 A8 PWM - Z_STEP_PIN SDA2 CAN0RX PWM 4 | *A25 A11* | 21 A7 PWM CS0 MOSI1 RX1 - Z_DIR_PIN MISO1 TX1 PWM 5 | *GND * * 57 | 20 A6 PWM CS0 SCK1 FILWIDTH_PIN - X_ENABLE_PIN PWM 6 | *GND * * 56 | 19 A5 SCL0 E0_STEP_PIN - Y_ENABLE_PIN SCL0 MOSI0 RX3 PWM 7 | * * 55 | 18 A4 SDA0 E0_DIR_PIN - Z_ENABLE_PIN SDA0 MISO0 TX3 PWM 8 | * * 54 | 17 A3 SDA0 E0_ENABLE_PIN - CS0 RX2 PWM 9 | | 16 A2 SCL0 TEMP_0_PIN - CS0 TX2 PWM 10 | | 15 A1 CS0 TEMP_BED_PIN - X_STOP_PIN MOSI0 11 | | 14 A0 PWM CS0 TEMP_1_PIN - Y_STOP_PIN MISO0 12 | | 13 LED SCK0 LED_PIN - 3.3V | | GND - Z_STOP_PIN 24 | 40 * * 53 | A22 DAC1 -AUX2 25 | 41 * * 52 | A21 DAC0 -AUX2 FAN_PIN SCL2 TX1 26 | 42 * * 51 | 39 A20 MISO0 SDSS -AUX2 Z-PROBE PWR SCK0 RX1 27 | * * * * * | 38 A19 PWM SDA1 -AUX2 SOL1_PIN MOSI0 28 | 43 * * 50 | 37 A18 PWM SCL1 -D10 CONTROLLER_FAN_PIN CAN0TX PWM 29 | 44 * * 49 | 36 A17 PWM -D9 HEATER_0_PIN CAN0RX PWM 30 | 45 * * 48 | 35 A16 PWM E1_ENABLE_PIN -D8 HEATER_BED_PIN CS1 RX4 A12 31 | 46 * * 47 | 34 A15 PWM SDA0 RX5 E1_DIR_PIN - SCK1 TX4 A13 32 |__GND_*_*_3.3V_| 33 A14 PWM SCL0 TX5 E1_STEP_PIN - - Interior pins: - LCD_PINS_RS 40 * * 53 SCK2 - LCD_PINS_ENABLE 41 * * 52 MOSI2 - LCD_PINS_D4 42 * * 51 MISO2 - LCD_PINS_D5 CS2 43 * * 50 A24 - LCD_PINS_D6 MOSI2 44 * * 49 A23 - LCD_PINS_D7 MISO2 45 * * 48 TX6 SDA0 BTN_ENC - BTN_EN1 SCK2 46 * * 47 RX6 SCL0 BTN_EN2 - GND * * 3.3V - -*/ +/** + * Plan for Teensy 3.5 and Teensy 3.6: + * USB + * GND |-----#####-----| VIN 5V + * X_STEP_PIN MOSI1 RX1 0 | ##### | Analog GND + * X_DIR_PIN MISO1 TX1 1 | | 3.3V + * Y_STEP_PIN PWM 2 | *NC AREF* | 23 A9 PWM + * Y_DIR_PIN SCL2 CAN0TX PWM 3 | *A26 A10* | 22 A8 PWM + * Z_STEP_PIN SDA2 CAN0RX PWM 4 | *A25 A11* | 21 A7 PWM CS0 MOSI1 RX1 + * Z_DIR_PIN MISO1 TX1 PWM 5 | *GND * * 57 | 20 A6 PWM CS0 SCK1 FILWIDTH_PIN + * X_ENABLE_PIN PWM 6 | *GND * * 56 | 19 A5 SCL0 E0_STEP_PIN + * Y_ENABLE_PIN SCL0 MOSI0 RX3 PWM 7 | * * 55 | 18 A4 SDA0 E0_DIR_PIN + * Z_ENABLE_PIN SDA0 MISO0 TX3 PWM 8 | * * 54 | 17 A3 SDA0 E0_ENABLE_PIN + * CS0 RX2 PWM 9 | | 16 A2 SCL0 TEMP_0_PIN + * CS0 TX2 PWM 10 | | 15 A1 CS0 TEMP_BED_PIN + * X_STOP_PIN MOSI0 11 | | 14 A0 PWM CS0 TEMP_1_PIN + * Y_STOP_PIN MISO0 12 | | 13 LED SCK0 LED_PIN + * 3.3V | | GND + * Z_STOP_PIN 24 | 40 * * 53 | A22 DAC1 + * AUX2 25 | 41 * * 52 | A21 DAC0 + * AUX2 FAN_PIN SCL2 TX1 26 | 42 * * 51 | 39 A20 MISO0 SDSS + * AUX2 Z-PROBE PWR SCK0 RX1 27 | * * * * * | 38 A19 PWM SDA1 + * AUX2 SOL1_PIN MOSI0 28 | 43 * * 50 | 37 A18 PWM SCL1 + * D10 CONTROLLER_FAN_PIN CAN0TX PWM 29 | 44 * * 49 | 36 A17 PWM + * D9 HEATER_0_PIN CAN0RX PWM 30 | 45 * * 48 | 35 A16 PWM E1_ENABLE_PIN + * D8 HEATER_BED_PIN CS1 RX4 A12 31 | 46 * * 47 | 34 A15 PWM SDA0 RX5 E1_DIR_PIN + * SCK1 TX4 A13 32 |__GND_*_*_3.3V_| 33 A14 PWM SCL0 TX5 E1_STEP_PIN + * + * Interior pins: + * LCD_PINS_RS 40 * * 53 SCK2 + * LCD_PINS_ENABLE 41 * * 52 MOSI2 + * LCD_PINS_D4 42 * * 51 MISO2 + * LCD_PINS_D5 CS2 43 * * 50 A24 + * LCD_PINS_D6 MOSI2 44 * * 49 A23 + * LCD_PINS_D7 MISO2 45 * * 48 TX6 SDA0 BTN_ENC + * BTN_EN1 SCK2 46 * * 47 RX6 SCL0 BTN_EN2 + * GND * * 3.3V + */ // // Limit Switches @@ -121,26 +117,20 @@ D8 HEATER_BED_PIN CS1 RX4 A12 31 | 46 * * 47 | 34 A15 PWM #define TEMP_1_PIN 0 #define TEMP_BED_PIN 1 // Bed / Analog pin numbering -#define SDSS 39 // 8 +// +// Misc. Functions +// #define LED_PIN 13 #define PS_ON_PIN 1 -#define ALARM_PIN -1 - #define FILWIDTH_PIN 6 #define SOL1_PIN 28 -#if 0 -// Pretty sure this is obsolete! -// Please use Marlin 1.1.x pins files as reference for new pins files. -#ifndef SDSUPPORT - // these are defined in the SD library if building with SD support - #define SCK_PIN 13 - #define MISO_PIN 12 - #define MOSI_PIN 11 -#endif -#endif +// +// SD Card +// +#define SDSS 39 // 8 -#if HAS_SPI_LCD +#if HAS_WIRED_LCD #define LCD_PINS_RS 40 #define LCD_PINS_ENABLE 41 #define LCD_PINS_D4 42 diff --git a/Marlin/src/pins/teensy4/pins_T41U5XBB.h b/Marlin/src/pins/teensy4/pins_T41U5XBB.h new file mode 100644 index 0000000000..cb4c0ea879 --- /dev/null +++ b/Marlin/src/pins/teensy4/pins_T41U5XBB.h @@ -0,0 +1,126 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/**************************************************************************************** +* Teensy 4.1 (IMXRT1062) Breadboard pin assignments +* Requires the Teensyduino software with Teensy 4.1 selected in Arduino IDE! +* https://www.pjrc.com/teensy/teensyduino.html +****************************************************************************************/ + +#if NOT_TARGET(IS_32BIT_TEENSY) || NOT_TARGET(IS_TEENSY41) + #error "Oops! Select 'Teensy 4.1' in 'Tools > Board.'" +#else + #define BOARD_INFO_NAME "Teensy4.1" +#endif + +/** + * Plan for Teensy 4.0 and Teensy 4.1: + * USB + * GND |-----#####-----| VIN (3.65 TO 5.5V) + * RX1 CS1 RX1 PWM 0 | ##### | GND + * TX1 MISO1 TX1 PWM 1 | | 3.3V + * STPX PWM 2 | | 23 A9 PWM + * DIRX PWM 3 | | 22 A8 PWM LIMZ + * STPY PWM 4 | | 21 A7 RX5 LIMY + * DIRY PWM 5 | | 20 A6 TX5 LIMX + * STPZ PWM 6 | | 19 A5 PWM SCL0 COOL + * DIRZ RX2 PWM 7 | | 18 A4 PWM SDA0 MIST + * STPA TX2 PWM 8 | | 17 A3 RX4 SDA1 CYST + * DIRA PWM 9 | | 16 A2 TX4 SCL1 EHOLD + * STEN PWM 10 | | 15 A1 PWM RX3 PRB + * SPDI MOSI0 PWM 11 | | 14 A0 PWM TX3 PANIC + * SPEN MISO0 PWM 12 | | 13 LED PWM SCK0 SPWM + * 3.3V | | GND + * SCL PWM 24 | | 41 A17 KPSTR + * SDA PWM 25 | | 40 A16 STENY + * STPB MOSI1 26 | | 39 A15 MISO1 STENZ + * DIRB SCK1 27 | * * * * * | 38 A14 STENA + * LIMB RX7 PWM 28 | | 37 PWM STENB + * DOOR TX7 PWM 29 | | 36 PWM ST0 + * ST1 30 | | 35 TX8 ST3 + * AUX0 31 | SDCARD | 34 RX8 ST2 + * AUX1 32 |_______________| 33 PWM AUX2 + */ + +#ifndef SDCARD_CONNECTION + #define SDCARD_CONNECTION ONBOARD +#endif + +// +// Servos +// +#define SERVO0_PIN 24 +#define SERVO1_PIN 25 + +// +// Limit Switches +// +#define X_STOP_PIN 20 +#define Y_STOP_PIN 21 +#define Z_STOP_PIN 22 + +// +// Steppers +// +#define X_STEP_PIN 2 +#define X_DIR_PIN 3 +#define X_ENABLE_PIN 10 +//#define X_CS_PIN 30 + +#define Y_STEP_PIN 4 +#define Y_DIR_PIN 5 +#define Y_ENABLE_PIN 40 +//#define Y_CS_PIN 31 + +#define Z_STEP_PIN 6 +#define Z_DIR_PIN 7 +#define Z_ENABLE_PIN 39 +//#define Z_CS_PIN 32 + +#define E0_STEP_PIN 8 +#define E0_DIR_PIN 9 +#define E0_ENABLE_PIN 38 + +#define E1_STEP_PIN 26 +#define E1_DIR_PIN 27 +#define E1_ENABLE_PIN 37 + +// +// Heaters / Fans +// +#define HEATER_0_PIN 31 +#define HEATER_1_PIN 32 +#define HEATER_BED_PIN 33 + +// +// Temperature Sensors +// +#define TEMP_0_PIN 5 // Extruder / Analog pin numbering: 2 => A2 +#define TEMP_1_PIN 4 +#define TEMP_BED_PIN 15 // Bed / Analog pin numbering + +// +// Misc. Functions +// +#define LED_PIN 13 +#define SOL0_PIN 17 diff --git a/Marlin/src/pins/teensy4/pins_TEENSY41.h b/Marlin/src/pins/teensy4/pins_TEENSY41.h new file mode 100644 index 0000000000..cc7341bc23 --- /dev/null +++ b/Marlin/src/pins/teensy4/pins_TEENSY41.h @@ -0,0 +1,131 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/**************************************************************************************** +* Teensy 4.1 (IMXRT1062) Breadboard pin assignments +* Requires the Teensyduino software with Teensy 4.1 selected in Arduino IDE! +* https://www.pjrc.com/teensy/teensyduino.html +****************************************************************************************/ + +#if NOT_TARGET(IS_32BIT_TEENSY) || NOT_TARGET(IS_TEENSY41) + #error "Oops! Select 'Teensy 4.1' in 'Tools > Board.'" +#else + #define BOARD_INFO_NAME "Teensy4.1" +#endif + +/** + * Plan for Teensy 4.0 and Teensy 4.1: + * USB + * GND |-----#####-----| VIN (3.65 TO 5.5V) + * X_STEP_PIN CS1 RX1 PWM 0 | ##### | GND + * X_DIR_PIN MISO1 TX1 PWM 1 | | 3.3V + * Y_STEP_PIN PWM 2 | | 23 A9 PWM SERVO1_PIN + * Y_DIR_PIN PWM 3 | | 22 A8 PWM SERVO0_PIN + * Z_STEP_PIN PWM 4 | | 21 A7 RX5 + * Z_DIR_PIN PWM 5 | | 20 A6 TX5 FILWIDTH_PIN + * X_ENABLE_PIN PWM 6 | | 19 A5 PWM SCL0 + * Y_ENABLE_PIN RX2 PWM 7 | | 18 A4 PWM SDA0 HEATER_1_PIN + * Z_ENABLE_PIN TX2 PWM 8 | | 17 A3 RX4 SDA1 + * E0_STEP_PIN PWM 9 | | 16 A2 TX4 SCL1 TEMP_0_PIN + * E0_DIR_PIN PWM 10 | | 15 A1 PWM RX3 TEMP_BED_PIN + * MOSI_PIN MOSI0 PWM 11 | | 14 A0 PWM TX3 TEMP_1_PIN + * MISO_PIN MISO0 PWM 12 | | 13 LED PWM SCK0 SCK_PIN + * 3.3V | | GND + * Z_STOP_PIN PWM 24 | | 41 A17 + * E0_ENABLE_PIN PWM 25 | | 40 A16 + * FAN_PIN MOSI1 26 | | 39 A15 MISO1 X_STOP_PIN + * Z-PROBE PWR SCK1 27 | * * * * * | 38 A14 Y_STOP_PIN + * SOL1_PIN RX7 PWM 28 | | 37 PWM HEATER_0_PIN + * FAN_PIN TX7 PWM 29 | | 36 PWM HEATER_BED_PIN + * X_CS_PIN 30 | | 35 TX8 E1_ENABLE_PIN + * y_CS_PIN 31 | SDCARD | 34 RX8 E1_DIR_PIN + * Z_CS_PIN 32 |_______________| 33 PWM E1_STEP_PIN + */ + +// +// Servos +// +#define SERVO0_PIN 22 +#define SERVO1_PIN 23 + +// +// Limit Switches +// +#define X_STOP_PIN 39 +#define Y_STOP_PIN 38 +#define Z_STOP_PIN 24 + +// +// Steppers +// +#define X_STEP_PIN 0 +#define X_DIR_PIN 1 +#define X_ENABLE_PIN 6 +//#define X_CS_PIN 30 + +#define Y_STEP_PIN 2 +#define Y_DIR_PIN 3 +#define Y_ENABLE_PIN 7 +//#define Y_CS_PIN 31 + +#define Z_STEP_PIN 4 +#define Z_DIR_PIN 5 +#define Z_ENABLE_PIN 8 +//#define Z_CS_PIN 32 + +#define E0_STEP_PIN 9 +#define E0_DIR_PIN 10 +#define E0_ENABLE_PIN 25 + +#define E1_STEP_PIN 33 +#define E1_DIR_PIN 34 +#define E1_ENABLE_PIN 35 + +// +// Heaters / Fans +// +#define HEATER_0_PIN 37 +#define HEATER_1_PIN 18 +#define HEATER_BED_PIN 36 +#ifndef FAN_PIN + #define FAN_PIN 29 +#endif + +// +// Temperature Sensors +// +#define TEMP_0_PIN 2 // Extruder / Analog pin numbering: 2 => A2 +#define TEMP_1_PIN 0 +#define TEMP_BED_PIN 1 // Bed / Analog pin numbering + +// +// Misc. Functions +// +#define LED_PIN 13 +#define SOL0_PIN 28 +//#define PS_ON_PIN 1 +//#define FILWIDTH_PIN 6 // A6 + +#ifndef SDCARD_CONNECTION + #define SDCARD_CONNECTION ONBOARD +#endif diff --git a/Marlin/src/sd/SdBaseFile.cpp b/Marlin/src/sd/SdBaseFile.cpp index 98d762f10b..2bc9f96e8c 100644 --- a/Marlin/src/sd/SdBaseFile.cpp +++ b/Marlin/src/sd/SdBaseFile.cpp @@ -154,7 +154,6 @@ bool SdBaseFile::contiguousRange(uint32_t* bgnBlock, uint32_t* endBlock) { * an invalid DOS 8.3 file name, the FAT volume has not been initialized, * a file is already open, the file already exists, the root * directory is full or an I/O error. - * */ bool SdBaseFile::createContiguous(SdBaseFile* dirFile, const char* path, uint32_t size) { if (ENABLED(SDCARD_READONLY)) return false; @@ -1663,7 +1662,6 @@ bool SdBaseFile::truncate(uint32_t length) { * \a nbyte. If an error occurs, write() returns -1. Possible errors * include write() is called before a file has been opened, write is called * for a read-only file, device is full, a corrupt file system or an I/O error. - * */ int16_t SdBaseFile::write(const void* buf, uint16_t nbyte) { #if ENABLED(SDCARD_READONLY) diff --git a/Marlin/src/sd/SdFatStructs.h b/Marlin/src/sd/SdFatStructs.h index e06e05981a..484d4e50c6 100644 --- a/Marlin/src/sd/SdFatStructs.h +++ b/Marlin/src/sd/SdFatStructs.h @@ -128,7 +128,6 @@ typedef struct masterBootRecord mbr_t; * \struct fat_boot * * \brief Boot sector for a FAT12/FAT16 volume. - * */ struct fat_boot { /** @@ -409,7 +408,6 @@ uint32_t const FSINFO_LEAD_SIG = 0x41615252, // 'AaRR' Lead signature for a F * \struct fat32_fsinfo * * \brief FSINFO sector for a FAT32 volume. - * */ struct fat32_fsinfo { uint32_t leadSignature; // must be 0x52, 0x52, 0x61, 0x41 'RRaA' diff --git a/Marlin/src/sd/SdFile.cpp b/Marlin/src/sd/SdFile.cpp index a4f048d950..c82fe2c5ed 100644 --- a/Marlin/src/sd/SdFile.cpp +++ b/Marlin/src/sd/SdFile.cpp @@ -57,7 +57,6 @@ SdFile::SdFile(const char* path, uint8_t oflag) : SdBaseFile(path, oflag) { } * \a nbyte. If an error occurs, write() returns -1. Possible errors * include write() is called before a file has been opened, write is called * for a read-only file, device is full, a corrupt file system or an I/O error. - * */ int16_t SdFile::write(const void* buf, uint16_t nbyte) { return SdBaseFile::write(buf, nbyte); } diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index 0126cc4ce3..f4622f301e 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -24,13 +24,15 @@ #if ENABLED(SDSUPPORT) +//#define DEBUG_CARDREADER + #include "cardreader.h" #include "../MarlinCore.h" #include "../lcd/ultralcd.h" #if ENABLED(DWIN_CREALITY_LCD) - #include "../lcd/dwin/dwin.h" + #include "../lcd/dwin/e3v2/dwin.h" #endif #include "../module/planner.h" // for synchronize @@ -51,6 +53,10 @@ #include "../feature/pause.h" #endif +#define DEBUG_OUT EITHER(DEBUG_CARDREADER, MARLIN_DEV_MODE) +#include "../core/debug_out.h" +#include "../libs/hex_print.h" + // public: card_flags_t CardReader::flag; @@ -140,7 +146,7 @@ CardReader::CardReader() { #if ENABLED(SDSUPPORT) && PIN_EXISTS(SD_DETECT) SET_INPUT_PULLUP(SD_DETECT_PIN); #endif - + #if PIN_EXISTS(SDPOWER) OUT_WRITE(SDPOWER_PIN, HIGH); // Power the SD reader #endif @@ -288,8 +294,10 @@ void CardReader::printListing(SdFile parent, const char * const prepend/*=nullpt // List all files on the SD card // void CardReader::ls() { - root.rewind(); - printListing(root); + if (flag.mounted) { + root.rewind(); + printListing(root); + } } #if ENABLED(LONG_FILENAME_HOST_SUPPORT) @@ -408,10 +416,11 @@ void CardReader::mount() { if (flag.mounted) cdroot(); - else { - spiInit(SPI_SPEED); // Return to base SPI speed - ui.set_status_P(GET_TEXT(MSG_SD_INIT_FAIL), -1); - } + #if ENABLED(USB_FLASH_DRIVE_SUPPORT) || PIN_EXISTS(SD_DETECT) + else if (marlin_state != MF_INITIALIZING) + ui.set_status_P(GET_TEXT(MSG_SD_INIT_FAIL), -1); + #endif + ui.refresh(); } @@ -427,6 +436,8 @@ void CardReader::manage_media() { uint8_t stat = uint8_t(IS_SD_INSERTED()); if (stat == prev_stat) return; + DEBUG_ECHOLNPAIR("SD: Status changed from ", prev_stat, " to ", stat); + flag.workDirIsRoot = true; // Return to root on mount/release if (ui.detected()) { @@ -453,12 +464,15 @@ void CardReader::manage_media() { if (stat) { TERN_(SDCARD_EEPROM_EMULATION, settings.first_load()); if (old_stat == 2) // First mount? + DEBUG_ECHOLNPGM("First mount."); TERN(POWER_LOSS_RECOVERY, recovery.check(), // Check for PLR file. (If not there it will beginautostart) beginautostart() // Look for auto0.g on the next loop ); } } + else + DEBUG_ECHOLNPGM("SD: No UI Detected."); } void CardReader::release() { @@ -583,11 +597,11 @@ void CardReader::openFileRead(char * const path, const uint8_t subcall_type/*=0* endFilePrint(); - SdFile *curDir; - const char * const fname = diveToFile(true, curDir, path); + SdFile *diveDir; + const char * const fname = diveToFile(true, diveDir, path); if (!fname) return; - if (file.open(curDir, fname, O_READ)) { + if (file.open(diveDir, fname, O_READ)) { filesize = file.fileSize(); sdpos = 0; @@ -618,14 +632,14 @@ void CardReader::openFileWrite(char * const path) { endFilePrint(); - SdFile *curDir; - const char * const fname = diveToFile(false, curDir, path); + SdFile *diveDir; + const char * const fname = diveToFile(false, diveDir, path); if (!fname) return; #if ENABLED(SDCARD_READONLY) openFailed(fname); #else - if (file.open(curDir, fname, O_CREAT | O_APPEND | O_WRITE | O_TRUNC)) { + if (file.open(diveDir, fname, O_CREAT | O_APPEND | O_WRITE | O_TRUNC)) { flag.saving = true; selectFileByName(fname); TERN_(EMERGENCY_PARSER, emergency_parser.disable()); @@ -637,6 +651,22 @@ void CardReader::openFileWrite(char * const path) { #endif } +// +// Check if a file exists by absolute or workDir-relative path +// If the file exists, the long name can also be fetched. +// +bool CardReader::fileExists(const char * const path) { + if (!isMounted()) return false; + SdFile *diveDir = nullptr; + const char * const fname = diveToFile(false, diveDir, path); + if (fname) { + diveDir->rewind(); + selectByName(*diveDir, fname); + diveDir->close(); + } + return fname != nullptr; +} + // // Delete a file by name in the working directory // @@ -728,7 +758,7 @@ void CardReader::beginautostart() { cdroot(); } -void CardReader::closefile(const bool store_location) { +void CardReader::closefile(const bool store_location/*=false*/) { file.sync(); file.close(); flag.saving = flag.logging = false; @@ -782,13 +812,15 @@ uint16_t CardReader::countFilesInWorkDir() { /** * Dive to the given DOS 8.3 file path, with optional echo of the dive paths. * - * On exit, curDir contains an SdFile reference to the file's directory. + * On exit: + * - Your curDir pointer contains an SdFile reference to the file's directory. + * - If update_cwd was 'true' the workDir now points to the file's directory. * * Returns a pointer to the last segment (filename) of the given DOS 8.3 path. * * A nullptr result indicates an unrecoverable error. */ -const char* CardReader::diveToFile(const bool update_cwd, SdFile*& curDir, const char * const path, const bool echo/*=false*/) { +const char* CardReader::diveToFile(const bool update_cwd, SdFile*& diveDir, const char * const path, const bool echo/*=false*/) { // Track both parent and subfolder static SdFile newDir1, newDir2; SdFile *sub = &newDir1, *startDir; @@ -796,15 +828,21 @@ const char* CardReader::diveToFile(const bool update_cwd, SdFile*& curDir, const // Parsing the path string const char *item_name_adr = path; + DEBUG_ECHOLNPAIR("diveToFile: path = '", path, "'"); + if (path[0] == '/') { // Starting at the root directory? - curDir = &root; - if (update_cwd) workDirDepth = 0; // The cwd can be updated for the benefit of sub-programs + diveDir = &root; item_name_adr++; + DEBUG_ECHOLNPAIR("diveToFile: CWD to root: ", hex_address((void*)diveDir)); + if (update_cwd) workDirDepth = 0; // The cwd can be updated for the benefit of sub-programs } else - curDir = &workDir; // Dive from workDir (as set by the UI) + diveDir = &workDir; // Dive from workDir (as set by the UI) + + startDir = diveDir; + + DEBUG_ECHOLNPAIR("diveToFile: startDir = ", hex_address((void*)startDir)); - startDir = curDir; while (item_name_adr) { // Find next subdirectory delimiter char * const name_end = strchr(item_name_adr, '/'); @@ -820,30 +858,48 @@ const char* CardReader::diveToFile(const bool update_cwd, SdFile*& curDir, const if (echo) SERIAL_ECHOLN(dosSubdirname); - // Open curDir - if (!sub->open(curDir, dosSubdirname, O_READ)) { - SERIAL_ECHOLNPAIR(STR_SD_OPEN_FILE_FAIL, dosSubdirname, "."); - return nullptr; + DEBUG_ECHOLNPAIR("diveToFile: sub = ", hex_address((void*)sub)); + + // Open diveDir (closing first) + sub->close(); + if (!sub->open(diveDir, dosSubdirname, O_READ)) { + openFailed(dosSubdirname); + item_name_adr = nullptr; + break; } - // Close curDir if not at starting-point - if (curDir != startDir) curDir->close(); + // Close diveDir if not at starting-point + if (diveDir != startDir) { + DEBUG_ECHOLNPAIR("diveToFile: closing diveDir: ", hex_address((void*)diveDir)); + diveDir->close(); + } - // curDir now subDir - curDir = sub; + // diveDir now subDir + diveDir = sub; + DEBUG_ECHOLNPAIR("diveToFile: diveDir = sub: ", hex_address((void*)diveDir)); - // Update workDirParents, workDirDepth, and workDir + // Update workDirParents and workDirDepth if (update_cwd) { - if (workDirDepth < MAX_DIR_DEPTH) workDirParents[workDirDepth++] = *curDir; - workDir = *curDir; + DEBUG_ECHOLNPAIR("diveToFile: update_cwd"); + if (workDirDepth < MAX_DIR_DEPTH) + workDirParents[workDirDepth++] = *diveDir; } // Point sub at the other scratch object - sub = (curDir != &newDir1) ? &newDir1 : &newDir2; + sub = (diveDir != &newDir1) ? &newDir1 : &newDir2; + DEBUG_ECHOLNPAIR("diveToFile: swapping sub = ", hex_address((void*)sub)); // Next path atom address item_name_adr = name_end + 1; } + + if (update_cwd) { + workDir = *diveDir; + DEBUG_ECHOLNPAIR("diveToFile: final workDir = ", hex_address((void*)diveDir)); + flag.workDirIsRoot = (workDirDepth == 0); + TERN_(SDCARD_SORT_ALPHA, presort()); + } + return item_name_adr; } diff --git a/Marlin/src/sd/cardreader.h b/Marlin/src/sd/cardreader.h index 62a6d87acf..33645b6531 100644 --- a/Marlin/src/sd/cardreader.h +++ b/Marlin/src/sd/cardreader.h @@ -99,6 +99,7 @@ public: static void openFileRead(char * const path, const uint8_t subcall=0); static void openFileWrite(char * const path); static void closefile(const bool store_location=false); + static bool fileExists(const char * const name); static void removeFile(const char * const name); static inline char* longest_filename() { return longFilename[0] ? longFilename : filename; } diff --git a/Marlin/src/sd/usb_flashdrive/Sd2Card_FlashDrive.cpp b/Marlin/src/sd/usb_flashdrive/Sd2Card_FlashDrive.cpp index 78f338fdae..a097df5105 100644 --- a/Marlin/src/sd/usb_flashdrive/Sd2Card_FlashDrive.cpp +++ b/Marlin/src/sd/usb_flashdrive/Sd2Card_FlashDrive.cpp @@ -94,9 +94,7 @@ static_assert(USB_INTR_PIN != -1, "USB_INTR_PIN must be defined"); #include "Sd2Card_FlashDrive.h" -#if HAS_DISPLAY - #include "../../lcd/ultralcd.h" -#endif +#include "../../lcd/ultralcd.h" static enum { UNINITIALIZED, @@ -116,9 +114,7 @@ bool Sd2Card::usbStartup() { SERIAL_ECHOPGM("Starting USB host..."); if (!UHS_START) { SERIAL_ECHOLNPGM(" failed."); - #if EITHER(ULTRA_LCD, EXTENSIBLE_UI) - LCD_MESSAGEPGM(MSG_MEDIA_USB_FAILED); - #endif + LCD_MESSAGEPGM(MSG_MEDIA_USB_FAILED); return false; } @@ -213,9 +209,7 @@ void Sd2Card::idle() { #if USB_DEBUG >= 1 SERIAL_ECHOLNPGM("Waiting for media"); #endif - #if EITHER(ULTRA_LCD, EXTENSIBLE_UI) - LCD_MESSAGEPGM(MSG_MEDIA_WAITING); - #endif + LCD_MESSAGEPGM(MSG_MEDIA_WAITING); GOTO_STATE_AFTER_DELAY(state, 2000); } break; @@ -229,11 +223,9 @@ void Sd2Card::idle() { #if USB_DEBUG >= 1 SERIAL_ECHOLNPGM("USB device removed"); #endif - #if EITHER(ULTRA_LCD, EXTENSIBLE_UI) - if (state != MEDIA_READY) - LCD_MESSAGEPGM(MSG_MEDIA_USB_REMOVED); - #endif - GOTO_STATE_AFTER_DELAY( WAIT_FOR_DEVICE, 0 ); + if (state != MEDIA_READY) + LCD_MESSAGEPGM(MSG_MEDIA_USB_REMOVED); + GOTO_STATE_AFTER_DELAY(WAIT_FOR_DEVICE, 0); } else if (state > WAIT_FOR_LUN && !bulk.LUNIsGood(0)) { @@ -241,17 +233,13 @@ void Sd2Card::idle() { #if USB_DEBUG >= 1 SERIAL_ECHOLNPGM("Media removed"); #endif - #if EITHER(ULTRA_LCD, EXTENSIBLE_UI) - LCD_MESSAGEPGM(MSG_MEDIA_REMOVED); - #endif - GOTO_STATE_AFTER_DELAY( WAIT_FOR_DEVICE, 0 ); + LCD_MESSAGEPGM(MSG_MEDIA_REMOVED); + GOTO_STATE_AFTER_DELAY(WAIT_FOR_DEVICE, 0); } else if (task_state == UHS_STATE(ERROR)) { - #if EITHER(ULTRA_LCD, EXTENSIBLE_UI) - LCD_MESSAGEPGM(MSG_MEDIA_READ_ERROR); - #endif - GOTO_STATE_AFTER_DELAY( MEDIA_ERROR, 0 ); + LCD_MESSAGEPGM(MSG_MEDIA_READ_ERROR); + GOTO_STATE_AFTER_DELAY(MEDIA_ERROR, 0); } } } diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs2/Usb.cpp b/Marlin/src/sd/usb_flashdrive/lib-uhs2/Usb.cpp index 8f0dbf42e9..8a989157b4 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs2/Usb.cpp +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs2/Usb.cpp @@ -640,7 +640,6 @@ again: * 7: for (each driver) { * 7a: Ask device if it knows this VID/PID. Acts exactly like 6a, but using VID/PID * 8: if we get here, no driver likes the device plugged in, so exit failure. - * */ uint8_t USB::Configuring(uint8_t parent, uint8_t port, bool lowspeed) { //uint8_t bAddress = 0; diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs2/masstorage.cpp b/Marlin/src/sd/usb_flashdrive/lib-uhs2/masstorage.cpp index 8ead0b0093..d707a41a27 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs2/masstorage.cpp +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs2/masstorage.cpp @@ -828,7 +828,6 @@ uint8_t BulkOnly::ClearEpHalt(uint8_t index) { /** * For driver use only. - * */ void BulkOnly::Reset() { while (pUsb->ctrlReq(bAddress, 0, bmREQ_MASSOUT, MASS_REQ_BOMSR, 0, 0, bIface, 0, 0, nullptr, nullptr) == 0x01) delay(6); @@ -1163,7 +1162,6 @@ uint8_t BulkOnly::HandleSCSIError(uint8_t status) { //////////////////////////////////////////////////////////////////////////////// /** - * * @param ep_ptr */ void BulkOnly::PrintEndpointDescriptor(const USB_FD_ENDPOINT_DESCRIPTOR * ep_ptr) { diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_BULK_STORAGE/UHS_BULK_STORAGE_INLINE.h b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_BULK_STORAGE/UHS_BULK_STORAGE_INLINE.h index 45830de9a1..15ed427697 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_BULK_STORAGE/UHS_BULK_STORAGE_INLINE.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_BULK_STORAGE/UHS_BULK_STORAGE_INLINE.h @@ -318,7 +318,6 @@ UHS_NI UHS_Bulk_Storage::UHS_Bulk_Storage(UHS_USB_HOST_BASE *p) { } /** - * * @param ei Enumeration information * @return true if this interface driver can handle this interface description */ @@ -375,7 +374,6 @@ uint8_t UHS_NI UHS_Bulk_Storage::SetInterface(ENUMERATION_INFO *ei) { }; /** - * * @return 0 for success */ uint8_t UHS_NI UHS_Bulk_Storage::Start() { @@ -628,7 +626,6 @@ void UHS_NI UHS_Bulk_Storage::CheckMedia() { /** * For driver use only. - * */ void UHS_NI UHS_Bulk_Storage::Poll() { if((long)(millis() - qNextPollTime) >= 0L) { @@ -839,7 +836,6 @@ uint8_t UHS_NI UHS_Bulk_Storage::ClearEpHalt(uint8_t index) { /** * For driver use only. - * */ void UHS_NI UHS_Bulk_Storage::Reset() { if(!bAddress) return; @@ -1185,7 +1181,6 @@ uint8_t UHS_NI UHS_Bulk_Storage::HandleSCSIError(uint8_t status) { //////////////////////////////////////////////////////////////////////////////// /** - * * @param ep_ptr */ void UHS_NI UHS_Bulk_Storage::PrintEndpointDescriptor(const USB_FD_ENDPOINT_DESCRIPTOR * ep_ptr) { diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_host_INLINE.h b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_host_INLINE.h index dec083390e..7843013b04 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_host_INLINE.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_host_INLINE.h @@ -101,7 +101,6 @@ uint8_t UHS_USB_HOST_BASE::setEpInfoEntry(uint8_t addr, uint8_t iface, uint8_t e * * @param maxep How many endpoints to initialize * @param device pointer to the device driver instance (this) - * */ void UHS_USB_HOST_BASE::DeviceDefaults(uint8_t maxep, UHS_USBInterface *interface) { @@ -208,7 +207,6 @@ uint8_t UHS_USB_HOST_BASE::doSoftReset(uint8_t parent, uint8_t port, uint8_t add * example of one of these documents, see page Five: * https://www.ftdichip.com/Support/Documents/TechnicalNotes/TN_113_Simplified%20Description%20of%20USB%20Device%20Enumeration.pdf * - * */ /** diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_usbhost.h b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_usbhost.h index 625666170b..b289a896ef 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_usbhost.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_usbhost.h @@ -350,7 +350,6 @@ public: /** * Executed before anything else in Release(). - * */ virtual void OnRelease() { return; @@ -403,7 +402,6 @@ public: #if 0 /** - * * @return true if this interface is Vendor Specific. */ virtual bool IsVSI() { @@ -414,7 +412,6 @@ public: #if 0 /** - * * Vendor Specific interface class. * This is used by a partner interface. * It can also be used to force-enumerate an interface that diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/macro_logic.h b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/macro_logic.h index 114064044d..0ac90f0df3 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/macro_logic.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/macro_logic.h @@ -6,7 +6,6 @@ * * To test: * gcc -DAJK_TEST_MACRO_LOGIC -E macro_logic.h - * */ #ifndef MACRO_LOGIC_H diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs3/dyn_SWI/SWI_INLINE.h b/Marlin/src/sd/usb_flashdrive/lib-uhs3/dyn_SWI/SWI_INLINE.h index 5408a94ade..f86054cad8 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs3/dyn_SWI/SWI_INLINE.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs3/dyn_SWI/SWI_INLINE.h @@ -165,7 +165,6 @@ static void Init_dyn_SWI() { } /** - * * @param klass class that extends dyn_SWI * @return 0 on queue full, else returns queue position (ones based) */ @@ -219,7 +218,6 @@ static void Init_dyn_SWI() { } /** - * * @param klass class that extends dyn_SWI * @return 0 on queue full, else returns queue position (ones based) */ diff --git a/buildroot/bin/opt_set b/buildroot/bin/opt_set index f23a1d3d07..a646e09ae7 100755 --- a/buildroot/bin/opt_set +++ b/buildroot/bin/opt_set @@ -6,7 +6,7 @@ set -e SED=$(which gsed || which sed) # Logic for returning nonzero based on answer here: https://stackoverflow.com/a/15966279/104648 -eval "${SED} -i '/\(\/\/\)*\([[:blank:]]*\)\(#define \b${1}\b\).*$/{s//\2\3 ${2}/;h};\${x;/./{x;q0};x;q9}' Marlin/Configuration.h" || -eval "${SED} -i '/\(\/\/\)*\([[:blank:]]*\)\(#define \b${1}\b\).*$/{s//\2\3 ${2}/;h};\${x;/./{x;q0};x;q9}' Marlin/Configuration_adv.h" || +eval "${SED} -i '/\(\/\/\)*\([[:blank:]]*\)\(#define\s\+\b${1}\b\).*$/{s//\2\3 ${2}/;h};\${x;/./{x;q0};x;q9}' Marlin/Configuration.h" || +eval "${SED} -i '/\(\/\/\)*\([[:blank:]]*\)\(#define\s\+\b${1}\b\).*$/{s//\2\3 ${2}/;h};\${x;/./{x;q0};x;q9}' Marlin/Configuration_adv.h" || eval "echo '#define ${@}' >>Marlin/Configuration_adv.h" || (echo "ERROR: opt_set Can't set or add ${1}" >&2 && exit 9) diff --git a/buildroot/share/PlatformIO/boards/LERDGE.json b/buildroot/share/PlatformIO/boards/LERDGE.json index 21df8db48e..011814a133 100644 --- a/buildroot/share/PlatformIO/boards/LERDGE.json +++ b/buildroot/share/PlatformIO/boards/LERDGE.json @@ -15,7 +15,8 @@ ] ], "mcu": "stm32f407zgt6", - "variant": "LERDGE" + "variant": "LERDGE", + "ldscript": "LERDGE.ld" }, "debug": { "jlink_device": "STM32F407ZG", diff --git a/buildroot/share/PlatformIO/boards/fysetc_s6.json b/buildroot/share/PlatformIO/boards/fysetc_s6.json deleted file mode 100644 index 489a15b9ef..0000000000 --- a/buildroot/share/PlatformIO/boards/fysetc_s6.json +++ /dev/null @@ -1,35 +0,0 @@ -{ - "build": { - "cpu": "cortex-m4", - "extra_flags": "-DSTM32F446xx", - "f_cpu": "180000000L", - "mcu": "stm32f446ret6", - "variant": "FYSETC_S6" - }, - "connectivity": [ - "can" - ], - "debug": { - "jlink_device": "STM32F446RE", - "openocd_target": "stm32f4x", - "svd_path": "STM32F446x.svd" - }, - "frameworks": [ - "arduino", - "stm32cube" - ], - "name": "3D Printer control board", - "upload": { - "maximum_ram_size": 131072, - "maximum_size": 524288, - "protocol": "stlink", - "protocols": [ - "jlink", - "stlink", - "blackmagic", - "serial" - ] - }, - "url": "https://www.st.com/en/microcontrollers-microprocessors/stm32f446.html", - "vendor": "FYSETC" -} \ No newline at end of file diff --git a/buildroot/share/PlatformIO/boards/malyanM200v2.json b/buildroot/share/PlatformIO/boards/malyanM200v2.json index 9e301ee79f..765a0c0a00 100644 --- a/buildroot/share/PlatformIO/boards/malyanM200v2.json +++ b/buildroot/share/PlatformIO/boards/malyanM200v2.json @@ -4,7 +4,7 @@ "extra_flags": "-DSTM32F070xB", "f_cpu": "48000000L", "mcu": "stm32f070rbt6", - "variant": "MALYANM200_F070CB", + "variant": "MALYANMx00_F070CB", "vec_tab_addr": "0x8002000" }, "debug": { diff --git a/buildroot/share/PlatformIO/scripts/common-dependencies.h b/buildroot/share/PlatformIO/scripts/common-dependencies.h index c41027003e..02a4502e3f 100644 --- a/buildroot/share/PlatformIO/scripts/common-dependencies.h +++ b/buildroot/share/PlatformIO/scripts/common-dependencies.h @@ -73,14 +73,10 @@ // Feature checks for SR_LCD_3W_NL #elif EITHER(LCD_I2C_TYPE_MCP23017, LCD_I2C_TYPE_MCP23008) #define USES_LIQUIDTWI2 -#elif ANY(HAS_CHARACTER_LCD, LCD_I2C_TYPE_PCF8575, LCD_I2C_TYPE_PCA8574, SR_LCD_2W_NL, LCM1602) +#elif ANY(HAS_MARLINUI_HD44780, LCD_I2C_TYPE_PCF8575, LCD_I2C_TYPE_PCA8574, SR_LCD_2W_NL, LCM1602) #define USES_LIQUIDCRYSTAL #endif -#if BOTH(ANYCUBIC_LCD_I3MEGA, EXTENSIBLE_UI) - #define HAS_ANYCUBIC_TFT_EXTUI -#endif - #if SAVED_POSITIONS #define HAS_SAVED_POSITIONS #endif @@ -89,15 +85,8 @@ #define HAS_GCODE_M876 #endif -#if PREHEAT_COUNT - #define HAS_PREHEAT_COUNT -#endif - #if EXTRUDERS #define HAS_EXTRUDERS - #if EXTRUDERS > 1 - #define HAS_MULTI_EXTRUDER - #endif #endif #if HAS_LCD_MENU @@ -156,3 +145,6 @@ #define HAS_MENU_UBL #endif #endif + +// Include pins for the current board. Platform tests will be skipped. No HAL-defined pins. +#include "../../../../Marlin/src/pins/pins.h" diff --git a/buildroot/share/PlatformIO/scripts/common-dependencies.py b/buildroot/share/PlatformIO/scripts/common-dependencies.py index def3bf40c2..6005855156 100644 --- a/buildroot/share/PlatformIO/scripts/common-dependencies.py +++ b/buildroot/share/PlatformIO/scripts/common-dependencies.py @@ -238,7 +238,7 @@ def load_marlin_features(): else: cmd += ['-D' + s] - cmd += ['-w -dM -E -x c++ buildroot/share/PlatformIO/scripts/common-dependencies.h'] + cmd += ['-D__MARLIN_PREBUILD__ -w -dM -E -x c++ buildroot/share/PlatformIO/scripts/common-dependencies.h'] cmd = ' '.join(cmd) blab(cmd) define_list = subprocess.check_output(cmd, shell=True).splitlines() diff --git a/buildroot/share/PlatformIO/scripts/fysetc_STM32S6.py b/buildroot/share/PlatformIO/scripts/fysetc_STM32S6.py deleted file mode 100644 index f6598ede65..0000000000 --- a/buildroot/share/PlatformIO/scripts/fysetc_STM32S6.py +++ /dev/null @@ -1,33 +0,0 @@ -from os.path import join -Import("env") - -import os,shutil -from SCons.Script import DefaultEnvironment -from platformio import util - -env = DefaultEnvironment() -platform = env.PioPlatform() -board = env.BoardConfig() - -FRAMEWORK_DIR = platform.get_package_dir("framework-arduinoststm32") -#FRAMEWORK_DIR = platform.get_package_dir("framework-arduinoststm32@3.10500.190327") -CMSIS_DIR = os.path.join(FRAMEWORK_DIR, "CMSIS", "CMSIS") -assert os.path.isdir(FRAMEWORK_DIR) -assert os.path.isdir(CMSIS_DIR) -assert os.path.isdir("buildroot/share/PlatformIO/variants") - -mcu_type = board.get("build.mcu")[:-2] -variant = board.get("build.variant") -series = mcu_type[:7].upper() + "xx" -variant_dir = os.path.join(FRAMEWORK_DIR, "variants", variant) - -source_dir = os.path.join("buildroot/share/PlatformIO/variants", variant) -assert os.path.isdir(source_dir) - -if not os.path.isdir(variant_dir): - os.mkdir(variant_dir) - -for file_name in os.listdir(source_dir): - full_file_name = os.path.join(source_dir, file_name) - if os.path.isfile(full_file_name): - shutil.copy(full_file_name, variant_dir) diff --git a/buildroot/share/PlatformIO/scripts/mks_robin_nano.py b/buildroot/share/PlatformIO/scripts/mks_robin_nano.py index 1663b98c96..a68fd308d4 100755 --- a/buildroot/share/PlatformIO/scripts/mks_robin_nano.py +++ b/buildroot/share/PlatformIO/scripts/mks_robin_nano.py @@ -18,7 +18,6 @@ for i, flag in enumerate(env["LINKFLAGS"]): # Encrypt ${PROGNAME}.bin and save it as 'Robin_nano.bin' def encrypt(source, target, env): import sys - import shutil key = [0xA3, 0xBD, 0xAD, 0x0D, 0x41, 0x11, 0xBB, 0x8D, 0xDC, 0x80, 0x2D, 0xD0, 0xD2, 0xC4, 0x9B, 0x1E, 0x26, 0xEB, 0xE3, 0x33, 0x4A, 0x15, 0xE4, 0x0A, 0xB3, 0xB1, 0x3C, 0x93, 0xBB, 0xAF, 0xF7, 0x3E] @@ -38,13 +37,4 @@ def encrypt(source, target, env): finally: firmware.close() robin.close() - source = target[0].dir.path +'/Robin_nano.bin' - destination = target[0].dir.path +'/Robin_nano35.bin' - shutil.copyfile(source, destination) env.AddPostAction("$BUILD_DIR/${PROGNAME}.bin", encrypt); - - -env.Replace( - UPLOADER="curl", - UPLOADCMD="$UPLOADER -v -H 'Content-Type:application/octet-stream' http://$UPLOADERFLAGS/upload?X-Filename=Robin_Nano35.bin --data-binary @$BUILD_DIR/Robin_nano35.bin" -) \ No newline at end of file diff --git a/buildroot/share/PlatformIO/scripts/mks_robin_nano35.py b/buildroot/share/PlatformIO/scripts/mks_robin_nano35.py index ae7a566c04..0047289adf 100644 --- a/buildroot/share/PlatformIO/scripts/mks_robin_nano35.py +++ b/buildroot/share/PlatformIO/scripts/mks_robin_nano35.py @@ -38,8 +38,3 @@ def encrypt(source, target, env): firmware.close() robin.close() env.AddPostAction("$BUILD_DIR/${PROGNAME}.bin", encrypt); - -env.Replace( - UPLOADER="curl", - UPLOADCMD="$UPLOADER -v -H 'Content-Type:application/octet-stream' http://$UPLOADERFLAGS/upload?X-Filename=Robin_Nano35.bin --data-binary @$BUILD_DIR/Robin_nano35.bin" -) diff --git a/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/PeripheralPins.c b/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/PeripheralPins.c index 4014a519a3..db0a439562 100644 --- a/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/PeripheralPins.c +++ b/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/PeripheralPins.c @@ -125,38 +125,62 @@ const PinMap PinMap_I2C_SCL[] = { #ifdef HAL_TIM_MODULE_ENABLED const PinMap PinMap_PWM[] = { + + // Some pins can perform PWM from more than one timer. These were selected to utilize as many channels as + // possible from timers which were already dedicated to PWM output. + // TIM1 = [FAN4, FAN5, HEATER6, FAN7] + // TIM2 = [, HEATER1, BED, ] + // TIM3 = [, , HEATER2, HEATER0] + // TIM4 = [HEATER5, HEATER4, , HEATER3] + // TIM8 = [FAN3, HEATER7, FAN2, FAN6] + // TIM9 = [FAN0, FAN1, , ] + {PB_1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 HEATER0 - {PD_14, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3 HEATER1 + {PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 HEATER1 {PB_0, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 HEATER2 - {PD_12, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1 BED - {PC_8, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 0)}, // TIM8_CH3 FAN0 - {PE_5, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1 FAN1 - {PE_6, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 2, 0)}, // TIM9_CH2 FAN2 - {PC_9, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 4, 0)}, // TIM8_CH4 EXTENSION1-4 - {PA_1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2 BL-TOUCH-SERVO - - // These pins have been defined for something else on the board but they MIGHT be - // used by the user as PWM pins if they aren't used for their primary purpose. + {PD_15, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 HEATER3 + {PD_13, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2 HEATER4 + {PD_12, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1 HEATER5 + {PE_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 HEATER6 + {PI_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2 HEATER7 + {PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 BED + + {PE_5, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1 FAN0 + {PE_6, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 2, 0)}, // TIM9_CH2 FAN1 + {PC_8, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 0)}, // TIM8_CH3 FAN2 + {PI_5, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 0)}, // TIM8_CH1 FAN3 + {PE_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 FAN4 + {PE_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 FAN5 + {PC_9, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 4, 0)}, // TIM8_CH4 FAN6 + {PE_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 FAN7 + + + // Alternate timer assignments for pins commonly using PWM + //{PB_1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N HEATER0 + //{PB_1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N HEATER0 + //{PA_1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2 HEATER1 + //{PB_0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N HEATER2 + //{PB_0, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N HEATER2 + //{PA_2, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 3, 0)}, // TIM5_CH3 BED + //{PA_2, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1 BED + //{PC_8, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 FAN2 + //{PC_9, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 FAN6 + + // Pins with an available timer channel, on a timer already allocated for PWM. + // These can be freely used for purposes requiring PWM, without creating new timer conflicts. + // This pins are very likely already used for other purposes and enabling PWM on them won't be useful. + {PB_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 BLTouch / Probe Output {PC_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 ESP8266 connector. Available if 8266 isn't used {PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 ESP8266 connector. Available if 8266 isn't used - {PB_7, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2 I2C connector, SDA pin. Available if I2C isn't used. - // TIM5_CH1 is used by the Servo Library - {PA_2, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 3, 0)}, // TIM5_CH3 BL-TOUCH port. Available if Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN - /** - * Unused by specifications on SKR-Pro. + /* + * Pins not utilizing hardware PWM on the GTR. * Uncomment the corresponding line if you want to have HardwarePWM on some pins. * WARNING: check timers' usage first to avoid conflicts. * If you don't know what you're doing leave things as they are or you WILL break something (including hardware) - * If you alter this section DO NOT report bugs to Marlin team since they are most likely caused by you. Thank you. */ //{PA_0, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 //{PA_0, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 1, 0)}, // TIM5_CH1 - {PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 BLTOUCH is a "servo" - {PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 BLTOUCH is a "servo" - //{PA_1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2 - //{PA_2, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 3, 0)}, // TIM5_CH3 - //{PA_2, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1 //{PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 //{PA_3, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 4, 0)}, // TIM5_CH4 //{PA_3, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 2, 0)}, // TIM9_CH2 @@ -173,20 +197,16 @@ const PinMap PinMap_PWM[] = { //{PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 //{PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 //{PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 - //{PB_0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N - //{PB_0, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N - //{PB_1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N - //{PB_1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N //{PB_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 //{PB_4, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 //{PB_5, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 //{PB_6, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1 + //{PB_7, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2 //{PB_8, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3 //{PB_8, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)}, // TIM10_CH1 //{PB_9, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 //{PB_9, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1 //{PB_10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 - {PB_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 //{PB_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N //{PB_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N //{PB_14, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N @@ -197,30 +217,17 @@ const PinMap PinMap_PWM[] = { //{PC_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 0)}, // TIM8_CH1 //{PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 //{PC_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2 - //{PC_8, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 - //{PC_9, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 - {PD_13, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2 - {PD_15, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 + //{PD_14, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3 //{PE_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N - {PE_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 //{PE_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N - {PE_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 //{PE_12, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N - {PE_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 - {PE_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 - #if STM32F4X_PIN_NUM >= 144 //144 pins mcu, 114 gpio - //{PF_6, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)}, // TIM10_CH1 - //{PF_7, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1 - //{PF_8, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1 - //{PF_9, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1 - #endif - #if STM32F4X_PIN_NUM >= 176 //176 pins mcu, 140 gpio - {PH_10, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 1, 0)}, // TIM5_CH1 - {PH_6, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 1, 0)}, // TIM12_CH1 - //{PH_11, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2 - {PI_5, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 0)}, // TIM8_CH1 - {PI_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2 - #endif + //{PF_6, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)}, // TIM10_CH1 + //{PF_7, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1 + //{PF_8, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1 + //{PF_9, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1 + //{PH_10, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 1, 0)}, // TIM5_CH1 + //{PH_6, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 1, 0)}, // TIM12_CH1 + //{PH_11, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2 {NC, NP, 0} }; #endif diff --git a/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/variant.h b/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/variant.h index 1ba0a18d6a..2da195c6cf 100644 --- a/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/variant.h +++ b/buildroot/share/PlatformIO/variants/BIGTREE_GTR_V1/variant.h @@ -255,8 +255,8 @@ extern "C" { // Timer Definitions //Do not use timer used by PWM pins when possible. See PinMap_PWM in PeripheralPins.c -#define TIMER_TONE TIM2 -#define TIMER_SERVO TIM5 // Only 1 Servo PIN on SKR-PRO, so use the same timer as defined in PeripheralPins +#define TIMER_TONE TIM10 +#define TIMER_SERVO TIM5 #define TIMER_SERIAL TIM7 // UART Definitions diff --git a/buildroot/share/PlatformIO/variants/FYSETC_S6/PeripheralPins.c b/buildroot/share/PlatformIO/variants/FYSETC_S6/PeripheralPins.c deleted file mode 100644 index cc700201aa..0000000000 --- a/buildroot/share/PlatformIO/variants/FYSETC_S6/PeripheralPins.c +++ /dev/null @@ -1,361 +0,0 @@ -/* - ******************************************************************************* - * Copyright (c) 2016, STMicroelectronics - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * 3. Neither the name of STMicroelectronics nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE - * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL - * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR - * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, - * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE - * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - ******************************************************************************* - */ -#include "Arduino.h" -#include "PeripheralPins.h" - -// ===== -// Note: Commented lines are alternative possibilities which are not used per default. -// If you change them, you will have to know what you do -// ===== - - -//*** ADC *** - -#ifdef HAL_ADC_MODULE_ENABLED -const PinMap PinMap_ADC[] = { - // {PA_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC1_IN0 - // {PA_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC2_IN0 - // {PA_0, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC3_IN0 - // {PA_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC1_IN1 - // {PA_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC2_IN1 - // {PA_1, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC3_IN1 - // {PA_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC1_IN2 - // {PA_2, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC2_IN2 - // {PA_2, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC3_IN2 - {PA_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC1_IN3 - // {PA_3, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC2_IN3 - // {PA_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC3_IN3 - {PA_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC1_IN4 - // {PA_4, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC2_IN4 - // {PA_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC1_IN5 - // {PA_5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC2_IN5 - // {PA_6, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC1_IN6 - // {PA_6, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC2_IN6 - // {PA_7, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC1_IN7 - // {PA_7, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC2_IN7 - // {PB_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC1_IN8 - // {PB_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC2_IN8 - // {PB_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC1_IN9 - // {PB_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC2_IN9 - {PC_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC1_IN10 - // {PC_0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC2_IN10 - // {PC_0, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC3_IN10 - {PC_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC1_IN11 - // {PC_1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC2_IN11 - // {PC_1, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC3_IN11 - {PC_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC1_IN12 - // {PC_2, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC2_IN12 - // {PC_2, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC3_IN12 - {PC_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC1_IN13 - // {PC_3, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC2_IN13 - // {PC_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC3_IN13 - {PC_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC1_IN14 - // {PC_4, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC2_IN14 - // {PC_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC1_IN15 - // {PC_5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC2_IN15 - {NC, NP, 0} -}; -#endif - -//*** DAC *** - -#ifdef HAL_DAC_MODULE_ENABLED -const PinMap PinMap_DAC[] = { - // {PA_4, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // DAC_OUT1 - // {PA_5, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // DAC_OUT2 - LD2 - {NC, NP, 0} -}; -#endif - -//*** I2C *** - -#ifdef HAL_I2C_MODULE_ENABLED -const PinMap PinMap_I2C_SDA[] = { - // {PB_3, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, - // {PB_4, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, - // {PB_7, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)}, - {PB_9, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)}, - // {PC_7, FMPI2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_FMPI2C1)}, - // {PC_9, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, - // {PC_12, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, - {NC, NP, 0} -}; -#endif - -#ifdef HAL_I2C_MODULE_ENABLED -const PinMap PinMap_I2C_SCL[] = { - // {PA_8, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, - // {PB_6, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)}, - {PB_8, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)}, - // {PB_10, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, - // {PC_6, FMPI2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_FMPI2C1)}, - {NC, NP, 0} -}; -#endif - -//*** PWM *** - -#ifdef HAL_TIM_MODULE_ENABLED -const PinMap PinMap_PWM[] = { - {PA_0, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 - // {PA_0, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 1, 0)}, // TIM5_CH1 - // {PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 - {PA_1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2 - // {PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 - STLink Tx - // {PA_2, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 3, 0)}, // TIM5_CH3 - STLink Tx - // {PA_2, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1 - STLink Tx - // {PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 - STLink Rx - // {PA_3, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 4, 0)}, // TIM5_CH4 - STLink Rx - // {PA_3, TIM9, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 2, 0)}, // TIM9_CH2 - STLink Rx - {PA_5, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 - // {PA_5, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N - {PA_6, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1 - // {PA_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 - //{PA_7, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1 - // {PA_7, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N - // {PA_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 - // {PA_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N - // {PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 - {PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 - {PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 - {PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 - {PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 - // {PB_0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N - // {PB_0, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 - {PB_0, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // Fan0, TIM8_CH2N - // {PB_1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N - // {PB_1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 - {PB_1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // Fan1, TIM8_CH3N - {PB_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // Fan2, TIM2_CH4 - {PB_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // E0 Heater, TIM2_CH2 - {PB_4, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // E1 Heater, TIM3_CH1 - {PB_5, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // LED G, TIM3_CH2 - {PB_6, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // LED R, TIM4_CH1 - {PB_7, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // LED B, TIM4_CH2 - // {PB_8, TIM10, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)}, // TIM10_CH1 - // {PB_8, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 - {PB_8, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3 - {PB_9, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1 - // {PB_9, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 - // {PB_9, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 - {PB_10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 - {PB_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N - {PB_14, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 1, 0)}, // TIM12_CH1 - // {PB_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N - // {PB_14, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N - {PB_15, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 2, 0)}, // TIM12_CH2 - // {PB_15, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N - // {PB_15, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N - {PC_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 - // {PC_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 0)}, // TIM8_CH1 - // {PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 - {PC_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2 - {PC_8, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 - // {PC_8, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 0)}, // TIM8_CH3 - // {PC_9, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 - {PC_9, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 4, 0)}, // TIM8_CH4 - {PD_15, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 - {PE_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 - {PE_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N - {NC, NP, 0} -}; -#endif - -//*** SERIAL *** - -#ifdef HAL_UART_MODULE_ENABLED -const PinMap PinMap_UART_TX[] = { - // {PA_0, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, - // {PA_2, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, - {PA_9, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, - // {PB_6, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, - // {PB_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - // {PC_6, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, - // {PC_10, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, - {PC_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - // {PC_12, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, - {NC, NP, 0} -}; -#endif - -#ifdef HAL_UART_MODULE_ENABLED -const PinMap PinMap_UART_RX[] = { - // {PA_1, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, - // {PA_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, - {PA_10, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, - // {PB_7, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, - // {PC_5, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - // {PC_7, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)}, - // {PC_11, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, - {PC_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - // {PD_2, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, - {NC, NP, 0} -}; -#endif - -#ifdef HAL_UART_MODULE_ENABLED -const PinMap PinMap_UART_RTS[] = { - // {PA_1, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, - // {PA_12, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, - // {PA_15, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, - // {PB_14, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - // {PC_8, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_UART5)}, - {NC, NP, 0} -}; -#endif - -#ifdef HAL_UART_MODULE_ENABLED -const PinMap PinMap_UART_CTS[] = { - // {PA_0, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, - // {PA_11, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, - // {PB_0, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, - // {PB_13, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, - // {PC_9, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_UART5)}, - {NC, NP, 0} -}; -#endif - -//*** SPI *** - -#ifdef HAL_SPI_MODULE_ENABLED -const PinMap PinMap_SPI_MOSI[] = { - {PA_7, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, - // {PB_0, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_SPI3)}, - // {PB_2, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_SPI3)}, - // {PB_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, - // {PB_5, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, - // {PB_15, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, - // {PC_1, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_SPI2)}, - // {PC_1, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI3)}, - // {PC_3, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, - // {PC_12, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, - {NC, NP, 0} -}; -#endif - -#ifdef HAL_SPI_MODULE_ENABLED -const PinMap PinMap_SPI_MISO[] = { - {PA_6, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, - // {PB_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, - // {PB_4, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, - // {PB_14, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, - // {PC_2, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, - // {PC_11, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, - {NC, NP, 0} -}; -#endif - -#ifdef HAL_SPI_MODULE_ENABLED -const PinMap PinMap_SPI_SCLK[] = { - {PA_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, - // {PA_9, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, - // {PB_3, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, - // {PB_3, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, - // {PB_10, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, - // {PB_13, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, - // {PC_7, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, - // {PC_10, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, - {NC, NP, 0} -}; -#endif - -#ifdef HAL_SPI_MODULE_ENABLED -const PinMap PinMap_SPI_SSEL[] = { - {PA_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, - // {PA_4, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, - // {PA_15, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, - // {PA_15, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, - // {PB_4, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_SPI2)}, - // {PB_9, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, - // {PB_12, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, - {NC, NP, 0} -}; -#endif - -//*** CAN *** - -#ifdef HAL_CAN_MODULE_ENABLED -const PinMap PinMap_CAN_RD[] = { - // {PA_11, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)}, - // {PB_5, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)}, - // {PB_8, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)}, - // {PB_12, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)}, - {NC, NP, 0} -}; -#endif - -#ifdef HAL_CAN_MODULE_ENABLED -const PinMap PinMap_CAN_TD[] = { - // {PA_12, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)}, - // {PB_6, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)}, - // {PB_9, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)}, - // {PB_13, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)}, - {NC, NP, 0} -}; -#endif - -//*** ETHERNET *** - -//*** No Ethernet *** - -//*** QUADSPI *** - -#ifdef HAL_QSPI_MODULE_ENABLED -const PinMap PinMap_QUADSPI[] = { - // {PA_1, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QSPI)}, // QUADSPI_BK1_IO3 - // {PB_2, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QSPI)}, // QUADSPI_CLK - // {PB_6, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_QSPI)}, // QUADSPI_BK1_NCS - // {PC_9, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QSPI)}, // QUADSPI_BK1_IO0 - // {PC_10, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QSPI)}, // QUADSPI_BK1_IO1 - // {PC_11, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QSPI)}, // QUADSPI_BK2_NCS - {NC, NP, 0} -}; -#endif - -//*** USB *** - -#ifdef HAL_PCD_MODULE_ENABLED -const PinMap PinMap_USB_OTG_FS[] = { - // {PA_8, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_SOF - // {PA_9, USB_OTG_FS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, 0)}, // USB_OTG_FS_VBUS - // {PA_10, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_ID - {PA_11, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DM - {PA_12, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DP - {NC, NP, 0} -}; -#endif - -#ifdef HAL_PCD_MODULE_ENABLED -const PinMap PinMap_USB_OTG_HS[] = { - {NC, NP, 0} -}; -#endif - - diff --git a/buildroot/share/PlatformIO/variants/FYSETC_S6/PinNamesVar.h b/buildroot/share/PlatformIO/variants/FYSETC_S6/PinNamesVar.h deleted file mode 100644 index bff3f21349..0000000000 --- a/buildroot/share/PlatformIO/variants/FYSETC_S6/PinNamesVar.h +++ /dev/null @@ -1,30 +0,0 @@ -/* SYS_WKUP */ -#ifdef PWR_WAKEUP_PIN1 - SYS_WKUP1 = PA_0, /* SYS_WKUP0 */ -#endif -#ifdef PWR_WAKEUP_PIN2 - SYS_WKUP2 = NC, -#endif -#ifdef PWR_WAKEUP_PIN3 - SYS_WKUP3 = NC, -#endif -#ifdef PWR_WAKEUP_PIN4 - SYS_WKUP4 = NC, -#endif -#ifdef PWR_WAKEUP_PIN5 - SYS_WKUP5 = NC, -#endif -#ifdef PWR_WAKEUP_PIN6 - SYS_WKUP6 = NC, -#endif -#ifdef PWR_WAKEUP_PIN7 - SYS_WKUP7 = NC, -#endif -#ifdef PWR_WAKEUP_PIN8 - SYS_WKUP8 = NC, -#endif -/* USB */ -#ifdef USBCON - USB_OTG_FS_DM = PA_11, - USB_OTG_FS_DP = PA_12, -#endif diff --git a/buildroot/share/PlatformIO/variants/FYSETC_S6/ldscript.ld b/buildroot/share/PlatformIO/variants/FYSETC_S6/ldscript.ld deleted file mode 100644 index 2a61072cb1..0000000000 --- a/buildroot/share/PlatformIO/variants/FYSETC_S6/ldscript.ld +++ /dev/null @@ -1,187 +0,0 @@ -/* -***************************************************************************** -** - -** File : LinkerScript.ld -** -** Abstract : Linker script for STM32F407VETx Device with -** 512KByte FLASH, 128KByte RAM -** -** Set heap size, stack size and stack location according -** to application requirements. -** -** Set memory bank area and size if external memory is used. -** -** Target : STMicroelectronics STM32 -** -** -** Distribution: The file is distributed as is, without any warranty -** of any kind. -** -***************************************************************************** -** @attention -** -**

© COPYRIGHT(c) 2014 Ac6

-** -** Redistribution and use in source and binary forms, with or without modification, -** are permitted provided that the following conditions are met: -** 1. Redistributions of source code must retain the above copyright notice, -** this list of conditions and the following disclaimer. -** 2. Redistributions in binary form must reproduce the above copyright notice, -** this list of conditions and the following disclaimer in the documentation -** and/or other materials provided with the distribution. -** 3. Neither the name of Ac6 nor the names of its contributors -** may be used to endorse or promote products derived from this software -** without specific prior written permission. -** -** THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -** AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -** IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE -** DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE -** FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL -** DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR -** SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER -** CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, -** OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE -** OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. -** -***************************************************************************** -*/ - -/* Entry Point */ -ENTRY(Reset_Handler) - -/* Highest address of the user mode stack */ -_estack = 0x20020000; /* end of RAM */ -/* Generate a link error if heap and stack don't fit into RAM */ -_Min_Heap_Size = 0x200;; /* required amount of heap */ -_Min_Stack_Size = 0x400;; /* required amount of stack */ - -/* Specify the memory areas */ -MEMORY -{ -FLASH (rx) : ORIGIN = 0x8010000, LENGTH = 512K -RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K -} - -/* Define output sections */ -SECTIONS -{ - /* The startup code goes first into FLASH */ - .isr_vector : - { - . = ALIGN(4); - KEEP(*(.isr_vector)) /* Startup code */ - . = ALIGN(4); - } >FLASH - - /* The program code and other data goes into FLASH */ - .text ALIGN(4): - { - . = ALIGN(4); - *(.text) /* .text sections (code) */ - *(.text*) /* .text* sections (code) */ - *(.glue_7) /* glue arm to thumb code */ - *(.glue_7t) /* glue thumb to arm code */ - *(.eh_frame) - - KEEP (*(.init)) - KEEP (*(.fini)) - - . = ALIGN(4); - _etext = .; /* define a global symbols at end of code */ - } >FLASH - - /* Constant data goes into FLASH */ - .rodata ALIGN(4): - { - . = ALIGN(4); - *(.rodata) /* .rodata sections (constants, strings, etc.) */ - *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ - . = ALIGN(4); - } >FLASH - - .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH - .ARM : { - __exidx_start = .; - *(.ARM.exidx*) - __exidx_end = .; - } >FLASH - - .preinit_array : - { - PROVIDE_HIDDEN (__preinit_array_start = .); - KEEP (*(.preinit_array*)) - PROVIDE_HIDDEN (__preinit_array_end = .); - } >FLASH - .init_array : - { - PROVIDE_HIDDEN (__init_array_start = .); - KEEP (*(SORT(.init_array.*))) - KEEP (*(.init_array*)) - PROVIDE_HIDDEN (__init_array_end = .); - } >FLASH - .fini_array : - { - PROVIDE_HIDDEN (__fini_array_start = .); - KEEP (*(SORT(.fini_array.*))) - KEEP (*(.fini_array*)) - PROVIDE_HIDDEN (__fini_array_end = .); - } >FLASH - - /* used by the startup to initialize data */ - _sidata = LOADADDR(.data); - - /* Initialized data sections goes into RAM, load LMA copy after code */ - .data : - { - . = ALIGN(4); - _sdata = .; /* create a global symbol at data start */ - *(.data) /* .data sections */ - *(.data*) /* .data* sections */ - - . = ALIGN(4); - _edata = .; /* define a global symbol at data end */ - } >RAM AT> FLASH - - /*_siccmram = LOADADDR(.ccmram);*/ - - /* Uninitialized data section */ - . = ALIGN(4); - .bss : - { - /* This is used by the startup in order to initialize the .bss secion */ - _sbss = .; /* define a global symbol at bss start */ - __bss_start__ = _sbss; - *(.bss) - *(.bss*) - *(COMMON) - - . = ALIGN(4); - _ebss = .; /* define a global symbol at bss end */ - __bss_end__ = _ebss; - } >RAM - - /* User_heap_stack section, used to check that there is enough RAM left */ - ._user_heap_stack : - { - . = ALIGN(4); - PROVIDE ( end = . ); - PROVIDE ( _end = . ); - . = . + _Min_Heap_Size; - . = . + _Min_Stack_Size; - . = ALIGN(4); - } >RAM - - /* Remove information from the standard libraries */ - /DISCARD/ : - { - libc.a ( * ) - libm.a ( * ) - libgcc.a ( * ) - } - - .ARM.attributes 0 : { *(.ARM.attributes) } -} - - diff --git a/buildroot/share/PlatformIO/variants/FYSETC_S6/variant.cpp b/buildroot/share/PlatformIO/variants/FYSETC_S6/variant.cpp deleted file mode 100644 index 7e3df41f1b..0000000000 --- a/buildroot/share/PlatformIO/variants/FYSETC_S6/variant.cpp +++ /dev/null @@ -1,201 +0,0 @@ -/* - Copyright (c) 2011 Arduino. All right reserved. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - See the GNU Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#include "pins_arduino.h" - -#ifdef __cplusplus -extern "C" { -#endif - -// Pin number -const PinName digitalPin[] = { - PA_0, //D0 - PA_1, //D1 - PA_2, //D2 - PA_3, //D3 - PA_4, //D4 - PA_5, //D5 - PA_6, //D6 - PA_7, //D7 - PA_8, //D8 - PA_9, //D9 - PA_10, //D10 - PA_11, //D11 - PA_12, //D12 - PA_13, //D13 - PA_14, //D14 - PA_15, //D15 - PB_0, //D16 - PB_1, //D17 - PB_2, //D18 - PB_3, //D19 - PB_4, //D20 - PB_5, //D21 - PB_6, //D22 - PB_7, //D23 - PB_8, //D24 - PB_9, //D25 - PB_10, //D26 - PB_11, //D27 - PB_12, //D28 - PB_13, //D29 - PB_14, //D30 - PB_15, //D31 - PC_0, //D32 - PC_1, //D33 - PC_2, //D34 - PC_3, //D35 - PC_4, //D36 - PC_5, //D37 - PC_6, //D38 - PC_7, //D39 - PC_8, //D40 - PC_9, //D41 - PC_10, //D42 - PC_11, //D43 - PC_12, //D44 - PC_13, //D45 - PC_14, //D46 - PC_15, //D47 - PD_0, //D48 - PD_1, //D49 - PD_2, //D50 - PD_3, //D51 - PD_4, //D52 - PD_5, //D53 - PD_6, //D54 - PD_7, //D55 - PD_8, //D56 - PD_9, //D57 - PD_10, //D58 - PD_11, //D59 - PD_12, //D60 - PD_13, //D61 - PD_14, //D62 - PD_15, //D63 - PE_0, //D64 - PE_1, //D65 - PE_2, //D66 - PE_3, //D67 - PE_4, //D68 - PE_5, //D69 - PE_6, //D70 - PE_7, //D71 - PE_8, //D72 - PE_9, //D73 - PE_10, //D74 - PE_11, //D75 - PE_12, //D76 - PE_13, //D77 - PE_14, //D78 - PE_15, //D79 - - //Duplicated ADC Pins - PA_3, //D80/A0 - PA_4, //D81/A1 - PC_0, //D82/A2 - PC_1, //D83/A3 - PC_2, //D84/A4 - PC_3, //D85/A5 - PC_4 //D86/A6 -}; - -#ifdef __cplusplus -} -#endif - -// ---------------------------------------------------------------------------- - -#ifdef __cplusplus -extern "C" { -#endif - -/** - * @brief System Clock Configuration - * The system Clock is configured as follow : - * System Clock source = PLL (HSE) - * SYSCLK(Hz) = 180000000 - * HCLK(Hz) = 180000000 - * AHB Prescaler = 1 - * APB1 Prescaler = 4 - * APB2 Prescaler = 2 - * HSE Frequency(Hz) = 12000000 - * PLL_M = 6 - * PLL_N = 180 - * PLL_P = 2 - * PLL_Q = 7 - * VDD(V) = 3.3 - * Main regulator output voltage = Scale1 mode - * Flash Latency(WS) = 5 - * @param None - * @retval None - */ -WEAK void SystemClock_Config(void) -{ - RCC_ClkInitTypeDef RCC_ClkInitStruct; - RCC_OscInitTypeDef RCC_OscInitStruct; - RCC_PeriphCLKInitTypeDef PeriphClkInitStruct; - - - /* Enable Power Control clock */ - __HAL_RCC_PWR_CLK_ENABLE(); - -#ifdef HAL_PWR_MODULE_ENABLED - /* The voltage scaling allows optimizing the power consumption when the device is - clocked below the maximum system frequency, to update the voltage scaling value - regarding system frequency refer to product datasheet. */ - __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1); -#endif - - /* Enable HSE Oscillator and activate PLL with HSE as source */ - RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; - RCC_OscInitStruct.HSEState = RCC_HSE_ON; - RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; - RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; - RCC_OscInitStruct.PLL.PLLM = 6; - RCC_OscInitStruct.PLL.PLLN = 180; - RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; - RCC_OscInitStruct.PLL.PLLQ = 7; - RCC_OscInitStruct.PLL.PLLR = 2; - HAL_RCC_OscConfig(&RCC_OscInitStruct); - - HAL_PWREx_EnableOverDrive(); - - /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 - clocks dividers */ - RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | - RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2); - RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLRCLK; - RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; - RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4; - RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2; - HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_5); - - PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_CLK48; - PeriphClkInitStruct.PLLSAI.PLLSAIM = 6; - PeriphClkInitStruct.PLLSAI.PLLSAIN = 96; - PeriphClkInitStruct.PLLSAI.PLLSAIQ = 2; - PeriphClkInitStruct.PLLSAI.PLLSAIP = RCC_PLLSAIP_DIV4; - PeriphClkInitStruct.PLLSAIDivQ = 1; - PeriphClkInitStruct.Clk48ClockSelection = RCC_CLK48CLKSOURCE_PLLSAIP; - HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct); -} - -#ifdef __cplusplus -} -#endif diff --git a/buildroot/share/PlatformIO/variants/FYSETC_S6/variant.h b/buildroot/share/PlatformIO/variants/FYSETC_S6/variant.h deleted file mode 100644 index da6a8249ee..0000000000 --- a/buildroot/share/PlatformIO/variants/FYSETC_S6/variant.h +++ /dev/null @@ -1,182 +0,0 @@ -/* - Copyright (c) 2011 Arduino. All right reserved. - - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. - - This library is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - See the GNU Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public - License along with this library; if not, write to the Free Software - Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA -*/ - -#ifndef _VARIANT_ARDUINO_STM32_ -#define _VARIANT_ARDUINO_STM32_ - -#ifdef __cplusplus -extern "C" { -#endif // __cplusplus - -/*---------------------------------------------------------------------------- - * Pins - *----------------------------------------------------------------------------*/ - -#define PA0 0 //D0 -#define PA1 1 //D1 -#define PA2 2 //D2 -#define PA3 3 //D3 -#define PA4 4 //D4 -#define PA5 5 //D5 -#define PA6 6 //D6 -#define PA7 7 //D7 -#define PA8 8 //D8 -#define PA9 9 //D9 -#define PA10 10 //D10 -#define PA11 11 //D11 -#define PA12 12 //D12 -#define PA13 13 //D13 -#define PA14 14 //D14 -#define PA15 15 //D15 -#define PB0 16 //D16 -#define PB1 17 //D17 -#define PB2 18 //D18 -#define PB3 19 //D19 -#define PB4 20 //D20 -#define PB5 21 //D21 -#define PB6 22 //D22 -#define PB7 23 //D23 -#define PB8 24 //D24 -#define PB9 25 //D25 -#define PB10 26 //D26 -#define PB11 27 //D27 -#define PB12 28 //D28 -#define PB13 29 //D29 -#define PB14 30 //D30 -#define PB15 31 //D31 -#define PC0 32 //D32 -#define PC1 33 //D33 -#define PC2 34 //D34 -#define PC3 35 //D35 -#define PC4 36 //D36 -#define PC5 37 //D37 -#define PC6 38 //D38 -#define PC7 39 //D39 -#define PC8 40 //D40 -#define PC9 41 //D41 -#define PC10 42 //D42 -#define PC11 43 //D43 -#define PC12 44 //D44 -#define PC13 45 //D45 -#define PC14 46 //D46 -#define PC15 47 //D47 -#define PD0 48 //D48 -#define PD1 49 //D49 -#define PD2 50 //D50 -#define PD3 51 //D51 -#define PD4 52 //D52 -#define PD5 53 //D53 -#define PD6 54 //D54 -#define PD7 55 //D55 -#define PD8 56 //D56 -#define PD9 57 //D57 -#define PD10 58 //D58 -#define PD11 59 //D59 -#define PD12 60 //D60 -#define PD13 61 //D61 -#define PD14 62 //D62 -#define PD15 63 //D63 -#define PE0 64 //D64 -#define PE1 65 //D65 -#define PE2 66 //D66 -#define PE3 67 //D67 -#define PE4 68 //D68 -#define PE5 69 //D69 -#define PE6 70 //D70 -#define PE7 71 //D71 -#define PE8 72 //D72 -#define PE9 73 //D73 -#define PE10 74 //D74 -#define PE11 75 //D75 -#define PE12 76 //D76 -#define PE13 77 //D77 -#define PE14 78 //D78 -#define PE15 79 //D79 - -// This must be a literal with the same value as PEND -#define NUM_DIGITAL_PINS 87 -// This must be a literal with a value less than or equal to to MAX_ANALOG_INPUTS -#define NUM_ANALOG_INPUTS 7 -#define NUM_ANALOG_FIRST 80 - -// PWM resolution -#define PWM_RESOLUTION 12 -#define PWM_FREQUENCY 20000 // >= 20 Khz => inaudible noise for fans -#define PWM_MAX_DUTY_CYCLE 255 - -// SPI Definitions -#define PIN_SPI_SS PA4 -#define PIN_SPI_MOSI PA7 -#define PIN_SPI_MISO PA6 -#define PIN_SPI_SCK PA5 - -// I2C Definitions -#define PIN_WIRE_SDA PB9 -#define PIN_WIRE_SCL PB8 - -// Timer Definitions -// Do not use timer used by PWM pin. See PinMap_PWM. -#define TIMER_TONE TIM6 -#define TIMER_SERVO TIM5 -#define TIMER_SERIAL TIM7 - -// UART Definitions -//#define SERIAL_UART_INSTANCE 1 // Connected to EXP3 header -/* Enable Serial 3 */ -#define HAVE_HWSERIAL1 -#define HAVE_HWSERIAL3 - -// Default pin used for 'Serial' instance (ex: ST-Link) -// Mandatory for Firmata -#define PIN_SERIAL_RX PA10 -#define PIN_SERIAL_TX PA9 - -/* HAL configuration */ -#define HSE_VALUE 12000000U - -#define FLASH_PAGE_SIZE (4U * 1024U) - -#ifdef __cplusplus -} // extern "C" -#endif - -/*---------------------------------------------------------------------------- - * Arduino objects - C++ only - *----------------------------------------------------------------------------*/ - -#ifdef __cplusplus -// These serial port names are intended to allow libraries and architecture-neutral -// sketches to automatically default to the correct port name for a particular type -// of use. For example, a GPS module would normally connect to SERIAL_PORT_HARDWARE_OPEN, -// the first hardware serial port whose RX/TX pins are not dedicated to another use. -// -// SERIAL_PORT_MONITOR Port which normally prints to the Arduino Serial Monitor -// -// SERIAL_PORT_USBVIRTUAL Port which is USB virtual serial -// -// SERIAL_PORT_LINUXBRIDGE Port which connects to a Linux system via Bridge library -// -// SERIAL_PORT_HARDWARE Hardware serial port, physical RX & TX pins. -// -// SERIAL_PORT_HARDWARE_OPEN Hardware serial ports which are open for use. Their RX & TX -// pins are NOT connected to anything by default. -#define SERIAL_PORT_MONITOR Serial -#define SERIAL_PORT_HARDWARE_OPEN Serial -#endif - -#endif /* _VARIANT_ARDUINO_STM32_ */ diff --git a/buildroot/share/fonts/marlin-6x12-3.bdf b/buildroot/share/fonts/marlin-6x12-3.bdf index ef90656eba..bc7a8827c0 100644 --- a/buildroot/share/fonts/marlin-6x12-3.bdf +++ b/buildroot/share/fonts/marlin-6x12-3.bdf @@ -106,16 +106,15 @@ B8 ENDCHAR STARTCHAR uni0006 ENCODING 6 -SWIDTH 545 0 -DWIDTH 6 0 -BBX 5 6 0 1 +SWIDTH 504 0 +DWIDTH 7 0 +BBX 8 5 0 1 BITMAP -E0 -8C -EA -8C -8A -0A +D8 +6C +36 +6C +D8 ENDCHAR STARTCHAR uni0007 ENCODING 7 diff --git a/buildroot/share/git/mfinfo b/buildroot/share/git/mfinfo index c7bf04fb14..e17138e456 100755 --- a/buildroot/share/git/mfinfo +++ b/buildroot/share/git/mfinfo @@ -49,7 +49,8 @@ while [[ $# -gt 0 ]]; do done case "$REPO" in - Marlin ) TARG=bugfix-1.1.x ; [[ $INDEX == 2 ]] && TARG=bugfix-2.0.x ; [[ $INDEX == 3 ]] && TARG=dev-2.1.x ;; + Marlin ) TARG=bugfix-2.0.x ; [[ $INDEX == 1 ]] && TARG=bugfix-1.1.x ; [[ $INDEX == 3 ]] && TARG=dev-2.1.x ;; + Configurations ) TARG=import-2.0.x ;; MarlinDocumentation ) TARG=master ;; esac diff --git a/buildroot/share/git/mfrb b/buildroot/share/git/mfrb index 1edc99bbe9..071b0b3d59 100755 --- a/buildroot/share/git/mfrb +++ b/buildroot/share/git/mfrb @@ -23,8 +23,5 @@ done [[ $USAGE == 1 ]] && { echo "usage: `basename $0` [1|2|3]" 1>&2 ; exit 1 ; } -# If the branch isn't currently the PR target -if [[ $TARG != $CURR ]]; then - [[ $QUICK ]] || git fetch upstream - git rebase upstream/$TARG && git rebase -i upstream/$TARG -fi +[[ $QUICK ]] || git fetch upstream +git rebase upstream/$TARG && git rebase -i upstream/$TARG diff --git a/buildroot/share/git/mftest b/buildroot/share/git/mftest index 3a88bf5f28..cfb5dd05f3 100755 --- a/buildroot/share/git/mftest +++ b/buildroot/share/git/mftest @@ -48,6 +48,8 @@ case $TESTENV in t32) TESTENV='teensy31' ;; t35) TESTENV='teensy35' ;; t36) TESTENV='teensy35' ;; + t40) TESTENV='teensy41' ;; + t41) TESTENV='teensy41' ;; -h|--help) echo -e "$(basename $0) : Marlin Firmware test, build, and upload\n" echo "Usage: $(basename $0) ................. Select env and test to apply / run" @@ -56,7 +58,7 @@ case $TESTENV in echo " $(basename $0) -b [variant] .... Auto-build the specified variant" echo " $(basename $0) -u [variant] .... Auto-build and upload the specified variant" echo - echo "env shortcuts: tree due esp lin lpc|lpc8 lpc9 m128 m256|mega stm|f1 f4 f7 s6 teensy|t31|t32 t35|t36" + echo "env shortcuts: tree due esp lin lpc|lpc8 lpc9 m128 m256|mega stm|f1 f4 f7 s6 teensy|t31|t32 t35|t36 t40|t41" exit ;; diff --git a/buildroot/tests/BIGTREE_GTR_V1_0-tests b/buildroot/tests/BIGTREE_GTR_V1_0-tests index 58f6f71fda..e8d47562aa 100644 --- a/buildroot/tests/BIGTREE_GTR_V1_0-tests +++ b/buildroot/tests/BIGTREE_GTR_V1_0-tests @@ -36,7 +36,10 @@ opt_set TEMP_SENSOR_3 1 opt_set TEMP_SENSOR_4 1 opt_set TEMP_SENSOR_5 1 opt_set NUM_Z_STEPPER_DRIVERS 3 -opt_enable TOOLCHANGE_FILAMENT_SWAP TOOLCHANGE_MIGRATION_FEATURE TOOLCHANGE_FS_INIT_BEFORE_SWAP TOOLCHANGE_FS_PRIME_FIRST_USED +opt_set DEFAULT_Kp_LIST "{ 22.2, 20.0, 21.0, 19.0, 18.0, 17.0 }" +opt_set DEFAULT_Ki_LIST "{ 1.08 }" +opt_set DEFAULT_Kd_LIST "{ 114.0, 112.0, 110.0, 108.0 }" +opt_enable TOOLCHANGE_FILAMENT_SWAP TOOLCHANGE_MIGRATION_FEATURE TOOLCHANGE_FS_INIT_BEFORE_SWAP TOOLCHANGE_FS_PRIME_FIRST_USED PID_PARAMS_PER_HOTEND exec_test $1 $2 "BigTreeTech GTR 6 Extruders Triple Z" # clean up diff --git a/buildroot/tests/LPC1769-tests b/buildroot/tests/LPC1769-tests index 9c7a1ba10e..a7a6456d02 100755 --- a/buildroot/tests/LPC1769-tests +++ b/buildroot/tests/LPC1769-tests @@ -26,6 +26,20 @@ opt_enable VIKI2 SDSUPPORT ADAPTIVE_FAN_SLOWING NO_FAN_SLOWING_IN_PID_TUNING \ opt_set GRID_MAX_POINTS_X 16 exec_test $1 $2 "Smoothieboard with many features" +restore_configs +opt_set MOTHERBOARD BOARD_SMOOTHIEBOARD +opt_set EXTRUDERS 2 +opt_set TEMP_SENSOR_1 -1 +opt_set TEMP_SENSOR_BED 5 +opt_enable TFTGLCD_PANEL_SPI SDSUPPORT ADAPTIVE_FAN_SLOWING NO_FAN_SLOWING_IN_PID_TUNING \ + FIX_MOUNTED_PROBE AUTO_BED_LEVELING_BILINEAR G29_RETRY_AND_RECOVER Z_MIN_PROBE_REPEATABILITY_TEST DEBUG_LEVELING_FEATURE \ + BABYSTEPPING BABYSTEP_XY BABYSTEP_ZPROBE_OFFSET \ + PRINTCOUNTER NOZZLE_PARK_FEATURE NOZZLE_CLEAN_FEATURE SLOW_PWM_HEATERS PIDTEMPBED EEPROM_SETTINGS INCH_MODE_SUPPORT TEMPERATURE_UNITS_SUPPORT \ + Z_SAFE_HOMING ADVANCED_PAUSE_FEATURE PARK_HEAD_ON_PAUSE \ + LCD_INFO_MENU ARC_SUPPORT BEZIER_CURVE_SUPPORT EXTENDED_CAPABILITIES_REPORT AUTO_REPORT_TEMPERATURES SDCARD_SORT_ALPHA EMERGENCY_PARSER +opt_set GRID_MAX_POINTS_X 16 +exec_test $1 $2 "Smoothieboard with TFTGLCD_PANEL_SPI" + #restore_configs #opt_set MOTHERBOARD BOARD_AZTEEG_X5_MINI_WIFI #opt_enable COREYX USE_XMAX_PLUG DAC_MOTOR_CURRENT_DEFAULT \ diff --git a/buildroot/tests/STM32F103RC_btt-tests b/buildroot/tests/STM32F103RC_btt-tests index 8780eb535c..ad15ee7237 100644 --- a/buildroot/tests/STM32F103RC_btt-tests +++ b/buildroot/tests/STM32F103RC_btt-tests @@ -16,7 +16,12 @@ opt_set SERIAL_PORT_2 -1 opt_set X_DRIVER_TYPE TMC2209 opt_set Y_DRIVER_TYPE TMC2209 opt_set Z_DRIVER_TYPE TMC2209 -opt_set E_DRIVER_TYPE TMC2209 +opt_set E0_DRIVER_TYPE TMC2209 +opt_set X_SLAVE_ADDRESS 0 +opt_set Y_SLAVE_ADDRESS 1 +opt_set Z_SLAVE_ADDRESS 2 +opt_set E0_SLAVE_ADDRESS 3 + exec_test $1 $2 "BigTreeTech SKR Mini E3 1.0 - Basic Config with TMC2209 HW Serial" # clean up diff --git a/buildroot/tests/esp32-tests b/buildroot/tests/esp32-tests index 992b3ec5ff..204e7aa708 100755 --- a/buildroot/tests/esp32-tests +++ b/buildroot/tests/esp32-tests @@ -30,6 +30,10 @@ opt_set X_HARDWARE_SERIAL Serial1 opt_set Y_HARDWARE_SERIAL Serial1 opt_set Z_HARDWARE_SERIAL Serial1 opt_set E0_HARDWARE_SERIAL Serial1 +opt_set X_SLAVE_ADDRESS 0 +opt_set Y_SLAVE_ADDRESS 1 +opt_set Z_SLAVE_ADDRESS 2 +opt_set E0_SLAVE_ADDRESS 3 opt_enable HOTEND_IDLE_TIMEOUT exec_test $1 $2 "ESP32, TMC HW Serial, Hotend Idle" diff --git a/buildroot/tests/malyan_M300-tests b/buildroot/tests/malyan_M300-tests index ada60d5584..1955accaa5 100755 --- a/buildroot/tests/malyan_M300-tests +++ b/buildroot/tests/malyan_M300-tests @@ -9,6 +9,7 @@ set -e restore_configs use_example_configs "delta/Malyan M300" opt_disable AUTO_BED_LEVELING_3POINT +opt_set LCD_SERIAL_PORT 1 exec_test $1 $2 "Malyan M300 (delta)" # cleanup diff --git a/buildroot/tests/mks_robin_pro-tests b/buildroot/tests/mks_robin_pro-tests index cfd36832fd..7ae4670fed 100644 --- a/buildroot/tests/mks_robin_pro-tests +++ b/buildroot/tests/mks_robin_pro-tests @@ -7,6 +7,7 @@ set -e use_example_configs Mks/Robin_Pro +opt_enable EMERGENCY_PARSER opt_set SDCARD_CONNECTION LCD opt_set X_DRIVER_TYPE TMC2209 opt_set Y_DRIVER_TYPE TMC2130 diff --git a/config/README.md b/config/README.md index 906c9dd71c..95d7611557 100644 --- a/config/README.md +++ b/config/README.md @@ -1,3 +1,3 @@ # Where have all the configurations gone? -## https://github.com/MarlinFirmware/Configurations/archive/release-2.0.6.1.zip +## https://github.com/MarlinFirmware/Configurations/archive/release-2.0.7.zip diff --git a/firmware/all_drv_2208/Robin_nano35.bin b/firmware/all_drv_2208/Robin_nano35.bin index be9e226805..0715510260 100644 Binary files a/firmware/all_drv_2208/Robin_nano35.bin and b/firmware/all_drv_2208/Robin_nano35.bin differ diff --git a/firmware/fb_4s/Robin_nano35.bin b/firmware/fb_4s/Robin_nano35.bin index ea03110d75..6c17e1a6a1 100644 Binary files a/firmware/fb_4s/Robin_nano35.bin and b/firmware/fb_4s/Robin_nano35.bin differ diff --git a/firmware/fb_5/Robin_nano35.bin b/firmware/fb_5/Robin_nano35.bin index bafbba9093..6b3d815c03 100644 Binary files a/firmware/fb_5/Robin_nano35.bin and b/firmware/fb_5/Robin_nano35.bin differ diff --git a/platformio.ini b/platformio.ini index 9a33a84713..eec46619f8 100644 --- a/platformio.ini +++ b/platformio.ini @@ -4,7 +4,7 @@ # # For detailed documentation with EXAMPLES: # -# https://docs.platformio.org/en/latest/projectconf.html +# https://docs.platformio.org/en/latest/projectconf/index.html # # Automatic targets - enable auto-uploading @@ -26,18 +26,165 @@ include_dir = Marlin # [common] default_src_filter = + - - + - - - - - - - - - - + - - - - - + - + - - - + - - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - - + - + - + - + - + - - + - - - - + - + - - - - - - - - + - - + - + - - + - - + - + - - - - - - + - - + - + - + - + - - + - - + - + - + - + - + - + - + - + - + - + - + - + - - + - - + - + - + - - + - - + - + - - + - + - + - - + - - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - - + - + - + - - + - + - + - + - + - - + - extra_scripts = pre:buildroot/share/PlatformIO/scripts/common-dependencies.py pre:buildroot/share/PlatformIO/scripts/common-cxxflags.py + post:buildroot/share/PlatformIO/scripts/common-dependencies-post.py build_flags = -fmax-errors=5 -g -D__MARLIN_FIRMWARE__ -fmerge-all-constants lib_deps = @@ -45,35 +192,169 @@ lib_deps = # Feature Dependencies # [features] -HAS_TFT_LVGL_UI = lvgl=https://github.com/makerbase-mks/MKS-LittlevGL/archive/master.zip +HAS_TFT_LVGL_UI = lvgl=https://github.com/makerbase-mks/LVGL-6.1.1-MKS/archive/master.zip src_filter=+ extra_scripts=download_mks_assets.py HAS_TRINAMIC_CONFIG = TMCStepper@~0.7.1 - src_filter=+ + src_filter=+ + + + + +HAS_STEALTHCHOP = src_filter=+ SR_LCD_3W_NL = SailfishLCD=https://github.com/mikeshub/SailfishLCD/archive/master.zip -DIGIPOT_MCP4... = SlowSoftI2CMaster +HAS_I2C_DIGIPOT = SlowSoftI2CMaster + src_filter=+ HAS_TMC26X = TMC26XStepper=https://github.com/trinamic/TMC26XStepper/archive/master.zip + src_filter=+ HAS_L64XX = Arduino-L6470@0.8.0 + src_filter=+ + + NEOPIXEL_LED = Adafruit NeoPixel@1.5.0 + src_filter=+ MAX6675_IS_MAX31865 = Adafruit MAX31865 library@~1.1.0 -HAS_GRAPHICAL_LCD = U8glib-HAL@0.4.1 - src_filter=+ USES_LIQUIDCRYSTAL = LiquidCrystal@1.5.0 USES_LIQUIDTWI2 = LiquidTWI2@1.2.7 +HAS_WIRED_LCD = src_filter=+ +HAS_MARLINUI_HD44780 = src_filter=+ +HAS_MARLINUI_U8GLIB = U8glib-HAL@~0.4.1 + src_filter=+ +HAS_GRAPHICAL_TFT = src_filter=+ DWIN_CREALITY_LCD = src_filter=+ -HAS_CHARACTER_LCD = src_filter=+ +IS_TFTGLCD_PANEL = src_filter=+ HAS_LCD_MENU = src_filter=+ -HAS_DGUS_LCD = src_filter=+ +HAS_GAMES = src_filter=+ +MARLIN_BRICKOUT = src_filter=+ +MARLIN_INVADERS = src_filter=+ +MARLIN_MAZE = src_filter=+ +MARLIN_SNAKE = src_filter=+ +HAS_MENU_BACKLASH = src_filter=+ +HAS_MENU_BED_CORNERS = src_filter=+ +LCD_BED_LEVELING = src_filter=+ +HAS_MENU_CANCELOBJECT = src_filter=+ +HAS_MENU_DELTA_CALIBRATE = src_filter=+ +HAS_MENU_FILAMENT = src_filter=+ +LCD_INFO_MENU = src_filter=+ +HAS_MENU_JOB_RECOVERY = src_filter=+ +HAS_MENU_LED = src_filter=+ +HAS_MENU_MEDIA = src_filter=+ +HAS_MENU_MIXER = src_filter=+ +HAS_MENU_MMU2 = src_filter=+ +HAS_MENU_PASSWORD = src_filter=+ +HAS_MENU_POWER_MONITOR = src_filter=+ +HAS_MENU_CUTTER = src_filter=+ +HAS_MENU_TEMPERATURE = src_filter=+ +HAS_MENU_TMC = src_filter=+ +HAS_MENU_TOUCH_SCREEN = src_filter=+ +HAS_MENU_UBL = src_filter=+ +ANYCUBIC_LCD_CHIRON = src_filter=+ +ANYCUBIC_LCD_I3MEGA = src_filter=+ + +HAS_DGUS_LCD = src_filter=+ + TOUCH_UI_FTDI_EVE = src_filter=+ -ANYCUBIC_TFT_MODEL = src_filter=+ +EXTUI_EXAMPLE = src_filter=+ +MALYAN_LCD = src_filter=+ USB_FLASH_DRIVE_SUPPORT = src_filter=+ -AUTO_BED_LEVELING_(3POINT|(BI)?LINEAR) = src_filter=+ + +AUTO_BED_LEVELING_BILINEAR = src_filter=+ +AUTO_BED_LEVELING_(3POINT|(BI)?LINEAR) = src_filter=+ MESH_BED_LEVELING = src_filter=+ + AUTO_BED_LEVELING_UBL = src_filter=+ + +BACKLASH_COMPENSATION = src_filter=+ +BARICUDA = src_filter=+ + +BINARY_FILE_TRANSFER = src_filter=+ + +BLTOUCH = src_filter=+ +CANCEL_OBJECTS = src_filter=+ + +CASE_LIGHT_ENABLE = src_filter=+ + +EXTERNAL_CLOSED_LOOP_CONTROLLER = src_filter=+ + +USE_CONTROLLER_FAN = src_filter=+ DAC_STEPPER_CURRENT = src_filter=+ -HAS_I2C_DIGIPOT = src_filter=+ -HAS_LED_FEATURE = src_filter=+ -(ESP3D_)?WIFISUPPORT = AsyncTCP, ESP Async WebServer +DIRECT_STEPPING = src_filter=+ + +EMERGENCY_PARSER = src_filter=+ - +I2C_POSITION_ENCODERS = src_filter=+ +HAS_FANMUX = src_filter=+ +FILAMENT_WIDTH_SENSOR = src_filter=+ + +FWRETRACT = src_filter=+ + +HOST_ACTION_COMMANDS = src_filter=+ +HOTEND_IDLE_TIMEOUT = src_filter=+ +JOYSTICK = src_filter=+ +BLINKM = src_filter=+ +HAS_COLOR_LEDS = src_filter=+ + +PCA9533 = src_filter=+ +PCA9632 = src_filter=+ +PRINTER_EVENT_LEDS = src_filter=+ +TEMP_STAT_LEDS = src_filter=+ +MAX7219_DEBUG = src_filter=+ + +MIXING_EXTRUDER = src_filter=+ + +PRUSA_MMU2 = src_filter=+ + +PASSWORD_FEATURE = src_filter=+ + +ADVANCED_PAUSE_FEATURE = src_filter=+ + + +AUTO_POWER_CONTROL = src_filter=+ +HAS_POWER_MONITOR = src_filter=+ + +POWER_LOSS_RECOVERY = src_filter=+ + +PROBE_TEMP_COMPENSATION = src_filter=+ + +HAS_FILAMENT_SENSOR = src_filter=+ + +MK2_MULTIPLEXER = src_filter=+ +EXT_SOLENOID|MANUAL_SOLENOID_CONTROL = src_filter=+ +HAS_CUTTER = src_filter=+ + +EXPERIMENTAL_I2CBUS = src_filter=+ + +Z_STEPPER_AUTO_ALIGN = src_filter=+ + +G26_MESH_VALIDATION = src_filter=+ +ASSISTED_TRAMMING = src_filter=+ +HAS_MESH = src_filter=+ +HAS_LEVELING = src_filter=+ +DELTA_AUTO_CALIBRATION = src_filter=+ +CALIBRATION_GCODE = src_filter=+ +Z_MIN_PROBE_REPEATABILITY_TEST = src_filter=+ +M100_FREE_MEMORY_WATCHER = src_filter=+ +BACKLASH_GCODE = src_filter=+ +IS_KINEMATIC = src_filter=+ +HAS_EXTRA_ENDSTOPS = src_filter=+ +SKEW_CORRECTION_GCODE = src_filter=+ +PINS_DEBUGGING = src_filter=- +NO_VOLUMETRICS = src_filter=- +HAS_MULTI_EXTRUDER = src_filter=+ +HAS_HOTEND_OFFSET = src_filter=+ +EDITABLE_SERVO_ANGLES = src_filter=+ +PREVENT_COLD_EXTRUSION = src_filter=+ +HAS_USER_THERMISTORS = src_filter=+ +SD_ABORT_ON_ENDSTOP_HIT = src_filter=+ +COOLANT_CONTROL = src_filter=+ +HAS_SOFTWARE_ENDSTOPS = src_filter=+ +HAS_DUPLICATION_MODE = src_filter=+ +LIN_ADVANCE = src_filter=+ +PHOTO_GCODE = src_filter=+ +CONTROLLER_FAN_EDITABLE = src_filter=+ +GCODE_MACROS = src_filter=+ +GRADIENT_MIX = src_filter=+ +HAS_SAVED_POSITIONS = src_filter=+ + +PARK_HEAD_ON_PAUSE = src_filter=+ +FILAMENT_LOAD_UNLOAD_GCODES = src_filter=+ +CNC_WORKSPACE_PLANES = src_filter=+ +CNC_COORDINATE_SYSTEMS = src_filter=+ +HAS_M206_COMMAND = src_filter=+ +EXPECTED_PRINTER_CHECK = src_filter=+ +HOST_KEEPALIVE_FEATURE = src_filter=+ +REPETIER_GCODE_M360 = src_filter=+ +HAS_GCODE_M876 = src_filter=+ +HAS_RESUME_CONTINUE = src_filter=+ +HAS_LCD_CONTRAST = src_filter=+ +LCD_SET_PROGRESS_MANUALLY = src_filter=+ +TOUCH_SCREEN_CALIBRATION = src_filter=+ +ARC_SUPPORT = src_filter=+ +GCODE_MOTION_MODES = src_filter=+ +BABYSTEPPING = src_filter=+ +Z_PROBE_SLED = src_filter=+ +G38_PROBE_TARGET = src_filter=+ +MAGNETIC_PARKING_EXTRUDER = src_filter=+ +SDSUPPORT = src_filter=+ +HAS_EXTRUDERS = src_filter=+ + +INCH_MODE_SUPPORT = src_filter=+ +TEMPERATURE_UNITS_SUPPORT = src_filter=+ +NEED_HEX_PRINT = src_filter=+ +NEED_LSF = src_filter=+ +NOZZLE_PARK_FEATURE = src_filter=+ + +NOZZLE_CLEAN_FEATURE = src_filter=+ + +DELTA = src_filter=+ + +BEZIER_CURVE_SUPPORT = src_filter=+ + +PRINTCOUNTER = src_filter=+ +HAS_BED_PROBE = src_filter=+ + + + +IS_SCARA = src_filter=+ +MORGAN_SCARA = src_filter=+ +(ESP3D_)?WIFISUPPORT = AsyncTCP, ESP Async WebServer ESP3DLib=https://github.com/luc-github/ESP3DLib.git arduinoWebSockets=https://github.com/Links2004/arduinoWebSockets.git ESP32SSDP=https://github.com/luc-github/ESP32SSDP.git @@ -98,7 +379,6 @@ monitor_flags = --filter time - ################################# # # # Unique Core Architectures # @@ -126,9 +406,20 @@ src_filter = ${common.default_src_filter} + # ATmega2560 # [env:mega2560] -platform = atmelavr -extends = common_avr8 -board = megaatmega2560 +platform = atmelavr +extends = common_avr8 +board = megaatmega2560 + +# +# ATmega2560 with extended pins 70-85 defined +# +[env:mega2560ext] +platform = atmelavr +extends = mega2560 +board = megaatmega2560 +board_build.variant = megaextendedpins +extra_scripts = ${common.extra_scripts} + pre:buildroot/share/PlatformIO/scripts/copy_marlin_variant_to_framework.py # # ATmega1280 @@ -268,14 +559,13 @@ src_filter = ${common.default_src_filter} + [env:DUE_USB] platform = atmelsam +extends = env:DUE board = dueUSB -src_filter = ${common.default_src_filter} + [env:DUE_debug] # Used when WATCHDOG_RESET_MANUAL is enabled platform = atmelsam -board = due -src_filter = ${common.default_src_filter} + +extends = env:DUE build_flags = ${common.build_flags} -funwind-tables -mpoke-function-name @@ -285,8 +575,7 @@ build_flags = ${common.build_flags} # [common_DUE_archim] platform = atmelsam -board = due -src_filter = ${common.default_src_filter} + +extends = env:DUE build_flags = ${common.build_flags} -DARDUINO_SAM_ARCHIM -DARDUINO_ARCH_SAM -D__SAM3X8E__ -DUSBCON extra_scripts = ${common.extra_scripts} @@ -320,7 +609,7 @@ src_filter = ${common.default_src_filter} + lib_deps = ${common.lib_deps} SoftwareSerialM Adafruit SPIFlash - SdFat - Adafruit Fork +custom_marlin.SDSUPPORT = SdFat - Adafruit Fork debug_tool = jlink ################################# @@ -334,6 +623,7 @@ debug_tool = jlink # [common_LPC] platform = https://github.com/p3p/pio-nxplpc-arduino-lpc176x/archive/0.1.3.zip +platform_packages = framework-arduino-lpc176x@^0.2.5 board = nxp_lpc1768 lib_ldf_mode = off lib_compat_mode = strict @@ -342,8 +632,8 @@ extra_scripts = ${common.extra_scripts} src_filter = ${common.default_src_filter} + lib_deps = ${common.lib_deps} Servo - LiquidCrystal@1.0.0 - Adafruit NeoPixel=https://github.com/p3p/Adafruit_NeoPixel/archive/1.5.0.zip +custom_marlin.USES_LIQUIDCRYSTAL = LiquidCrystal@1.0.0 +custom_marlin.NEOPIXEL_LED = Adafruit NeoPixel=https://github.com/p3p/Adafruit_NeoPixel/archive/1.5.0.zip build_flags = ${common.build_flags} -DU8G_HAL_LINKS -IMarlin/src/HAL/LPC1768/include -IMarlin/src/HAL/LPC1768/u8g # debug options for backtrace #-funwind-tables @@ -372,13 +662,10 @@ board = nxp_lpc1769 # HAL/STM32 Base Environment values # [common_stm32] -platform = ststm32@~6.1.0 -platform_packages = framework-arduinoststm32@>=4.10700,<4.10800 -lib_ignore = SoftwareSerial +platform = ststm32@~8.0 build_flags = ${common.build_flags} - -IMarlin/src/HAL/STM32 -std=gnu++14 + -std=gnu++14 -DUSBCON -DUSBD_USE_CDC - -DUSBD_VID=0x0483 -DTIM_IRQ_PRIO=13 build_unflags = -std=gnu++11 src_filter = ${common.default_src_filter} + @@ -387,10 +674,10 @@ src_filter = ${common.default_src_filter} + # HAL/STM32F1 Common Environment values # [common_stm32f1] -platform = ${common_stm32.platform} +platform = ststm32@~6.1 build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py ${common.build_flags} -std=gnu++14 -DHAVE_SW_SERIAL -build_unflags = -std=gnu11 +build_unflags = -std=gnu11 -std=gnu++11 src_filter = ${common.default_src_filter} + lib_ignore = SPI lib_deps = ${common.lib_deps} @@ -426,9 +713,9 @@ extra_scripts = ${common.extra_scripts} pre:buildroot/share/PlatformIO/scripts/STM32F1_create_variant.py buildroot/share/PlatformIO/scripts/STM32F103RC_MEEB_3DP.py lib_deps = ${common.lib_deps} - Adafruit NeoPixel=https://github.com/ccccmagicboy/Adafruit_NeoPixel#meeb_3dp_use SoftwareSerialM USBComposite for STM32F1@0.91 +custom_marlin.NEOPIXEL_LED = Adafruit NeoPixel=https://github.com/ccccmagicboy/Adafruit_NeoPixel#meeb_3dp_use debug_tool = stlink upload_protocol = dfu @@ -453,6 +740,11 @@ upload_protocol = serial # STM32F103RC_btt_512K ........ RCT6 with 512K # STM32F103RC_btt_512K_USB .... RCT6 with 512K (USB mass storage) # +# WARNING! If you have an SKR Mini v1.1 or an SKR Mini E3 1.0 / 1.2 / 2.0 / DIP +# and experience a printer freeze, re-flash Marlin using the regular (non-512K) +# build option. 256K chips may be re-branded 512K chips, but this means the +# upper 256K is sketchy, and failure is very likely. +# [env:STM32F103RC_btt] platform = ${common_stm32f1.platform} @@ -539,7 +831,6 @@ platform = ${common_stm32.platform} extends = common_stm32 board = armed_v1 build_flags = ${common_stm32.build_flags} - '-DUSB_PRODUCT="ARMED_V1"' -O2 -ffreestanding -fsigned-char -fno-move-loop-invariants -fno-strict-aliasing # @@ -595,7 +886,6 @@ board = genericSTM32F103VE platform_packages = tool-stm32duino extra_scripts = ${common.extra_scripts} buildroot/share/PlatformIO/scripts/mks_robin_nano35.py -lib_deps = ${common_stm32f1.lib_deps} build_flags = ${common_stm32f1.build_flags} -DMCU_STM32F103VE -DSS_TIMER=4 debug_tool = jlink @@ -614,6 +904,28 @@ extra_scripts = ${common.extra_scripts} build_flags = ${common_stm32f1.build_flags} -DSS_TIMER=4 -DSTM32_XL_DENSITY +# MKS Robin (STM32F103ZET6) +# Uses HAL STM32 to support Marlin UI for TFT screen with optional touch panel +# +[env:mks_robin_stm32] +platform = ${common_stm32.platform} +extends = common_stm32 +board = genericSTM32F103ZE +board_build.core = stm32 +board_build.variant = MARLIN_F103Zx +board_build.ldscript = ldscript.ld +board_build.offset = 0x7000 +board_build.firmware = Robin.bin +build_flags = ${common_stm32.build_flags} + -DENABLE_HWSERIAL3 -DTRANSFER_CLOCK_DIV=8 +build_unflags = ${common_stm32.build_unflags} + -DUSBCON -DUSBD_USE_CDC +extra_scripts = ${common.extra_scripts} + pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py + buildroot/share/PlatformIO/scripts/stm32_bootloader.py + buildroot/share/PlatformIO/scripts/mks_encrypt.py +lib_deps = + # # MKS Robin Pro (STM32F103ZET6) # @@ -646,6 +958,22 @@ extra_scripts = ${common.extra_scripts} build_flags = ${common_stm32f1.build_flags} -DDEBUG_LEVEL=0 -DSS_TIMER=4 +# +# MKS Robin E3p (STM32F103VET6) +# - LVGL UI +# +[env:mks_robin_e3p] +platform = ${common_stm32f1.platform} +extends = common_stm32f1 +board = genericSTM32F103VE +platform_packages = tool-stm32duino +extra_scripts = ${common.extra_scripts} + buildroot/share/PlatformIO/scripts/mks_robin_e3p.py +build_flags = ${common_stm32f1.build_flags} + -DMCU_STM32F103VE -DSS_TIMER=4 +debug_tool = jlink +upload_protocol = jlink + # # MKS Robin Lite/Lite2 (STM32F103RCT6) # @@ -699,20 +1027,29 @@ lib_ignore = ${common_stm32f1.lib_ignore} platform = ${common_stm32.platform} extends = common_stm32 board = malyanM200v2 -build_flags = ${common_stm32.build_flags} -DSTM32F0xx -DUSB_PRODUCT=\"STM32F070RB\" -DHAL_PCD_MODULE_ENABLED - -O2 -ffreestanding -fsigned-char -fno-move-loop-invariants -fno-strict-aliasing -std=gnu11 -std=gnu++11 +build_flags = ${common_stm32.build_flags} -DHAL_PCD_MODULE_ENABLED + -O2 -ffreestanding -fsigned-char -fno-move-loop-invariants -fno-strict-aliasing -DCUSTOM_STARTUP_FILE -lib_ignore = SoftwareSerial + +# +# Malyan M200 v2 (STM32F070CB) +# +[env:STM32F070CB_malyan] +platform = ${common_stm32.platform} +extends = common_stm32 +board = malyanm200_f070cb +build_flags = ${common_stm32.build_flags} + -DHAL_PCD_MODULE_ENABLED -DDISABLE_GENERIC_SERIALUSB -DHAL_UART_MODULE_ENABLED -DCUSTOM_STARTUP_FILE # # Malyan M300 (STM32F070CB) # [env:malyan_M300] -platform = ststm32@>=6.1.0,<6.2.0 +platform = ${common_stm32.platform} +extends = common_stm32 board = malyanm300_f070cb -build_flags = ${common.build_flags} - -DUSBCON -DUSBD_VID=0x0483 "-DUSB_MANUFACTURER=\"Unknown\"" "-DUSB_PRODUCT=\"MALYAN_M300\"" - -DHAL_PCD_MODULE_ENABLED -DUSBD_USE_CDC -DDISABLE_GENERIC_SERIALUSB -DHAL_UART_MODULE_ENABLED +build_flags = ${common_stm32.build_flags} + -DHAL_PCD_MODULE_ENABLED -DDISABLE_GENERIC_SERIALUSB -DHAL_UART_MODULE_ENABLED src_filter = ${common.default_src_filter} + # @@ -745,7 +1082,7 @@ build_flags = ${env:chitu_f103.build_flags} -DCHITU_V5_Z_MIN_BUGFIX [env:STM32F103RET6_creality] platform = ${common_stm32f1.platform} extends = common_stm32f1 -board = genericSTM32F103RC +board = genericSTM32F103RE build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py ${common.build_flags} -std=gnu++14 -DSTM32_XL_DENSITY -DTEMP_TIMER_CHAN=4 extra_scripts = ${common.extra_scripts} @@ -765,13 +1102,11 @@ platform = ${common_stm32.platform} extends = common_stm32 board = STEVAL_STM32F401VE build_flags = ${common_stm32.build_flags} - -DTARGET_STM32F4 -DARDUINO_STEVAL -DSTM32F401xE - -DUSB_PRODUCT=\"STEVAL_F401VE\" + -DARDUINO_STEVAL -DSTM32F401xE -DDISABLE_GENERIC_SERIALUSB -DUSBD_USE_CDC_COMPOSITE -DUSE_USB_FS extra_scripts = ${common.extra_scripts} pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py buildroot/share/PlatformIO/scripts/STEVAL__F401XX.py -lib_ignore = SoftwareSerial # # FLYF407ZG @@ -781,8 +1116,7 @@ platform = ${common_stm32.platform} extends = common_stm32 board = FLYF407ZG build_flags = ${common_stm32.build_flags} - -DSTM32F4 -DUSB_PRODUCT=\"STM32F407ZG\" - -DTARGET_STM32F4 -DVECT_TAB_OFFSET=0x8000 + -DVECT_TAB_OFFSET=0x8000 extra_scripts = ${common.extra_scripts} pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py @@ -792,14 +1126,13 @@ extra_scripts = ${common.extra_scripts} [env:FYSETC_S6] platform = ${common_stm32.platform} extends = common_stm32 -platform_packages = ${common_stm32.platform_packages} - tool-stm32duino -board = fysetc_s6 +platform_packages = tool-stm32duino +board = marlin_fysetc_s6 build_flags = ${common_stm32.build_flags} - -DTARGET_STM32F4 -DVECT_TAB_OFFSET=0x10000 - -DHAL_PCD_MODULE_ENABLED '-DUSB_PRODUCT="FYSETC_S6"' + -DVECT_TAB_OFFSET=0x10000 + -DHAL_PCD_MODULE_ENABLED extra_scripts = ${common.extra_scripts} - pre:buildroot/share/PlatformIO/scripts/fysetc_STM32S6.py + pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py debug_tool = stlink upload_protocol = dfu upload_command = dfu-util -a 0 -s 0x08010000:leave -D "$SOURCE" @@ -814,12 +1147,10 @@ platform = ${common_stm32.platform} extends = common_stm32 board = blackSTM32F407VET6 build_flags = ${common_stm32.build_flags} - -DTARGET_STM32F4 -DARDUINO_BLACK_F407VE - -DUSB_PRODUCT=\"BLACK_F407VE\" + -DARDUINO_BLACK_F407VE -DUSBD_USE_CDC_COMPOSITE -DUSE_USB_FS extra_scripts = ${common.extra_scripts} pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py -lib_ignore = SoftwareSerial # # BigTreeTech SKR Pro (STM32F407ZGT6 ARM Cortex-M4) @@ -829,8 +1160,7 @@ platform = ${common_stm32.platform} extends = common_stm32 board = BigTree_SKR_Pro build_flags = ${common_stm32.build_flags} - -DUSB_PRODUCT=\"STM32F407ZG\" - -DTARGET_STM32F4 -DSTM32F407_5ZX -DVECT_TAB_OFFSET=0x8000 + -DSTM32F407_5ZX -DVECT_TAB_OFFSET=0x8000 extra_scripts = ${common.extra_scripts} pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py #upload_protocol = stlink @@ -842,14 +1172,13 @@ debug_init_break = # Bigtreetech GTR V1.0 (STM32F407IGT6 ARM Cortex-M4) # [env:BIGTREE_GTR_V1_0] -platform = ststm32@>=5.7.0,<6.2.0 +platform = ${common_stm32.platform} extends = common_stm32 board = BigTree_GTR_v1 extra_scripts = ${common.extra_scripts} pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py build_flags = ${common_stm32.build_flags} - -DUSB_PRODUCT=\"STM32F407IG\" - -DTARGET_STM32F4 -DSTM32F407IX -DVECT_TAB_OFFSET=0x8000 + -DSTM32F407IX -DVECT_TAB_OFFSET=0x8000 # # BigTreeTech BTT002 V1.0 (STM32F407VGT6 ARM Cortex-M4) @@ -859,8 +1188,7 @@ platform = ${common_stm32.platform} extends = common_stm32 board = BigTree_Btt002 build_flags = ${common_stm32.build_flags} - -DUSB_PRODUCT=\"STM32F407VG\" - -DTARGET_STM32F4 -DSTM32F407_5VX -DVECT_TAB_OFFSET=0x8000 + -DSTM32F407_5VX -DVECT_TAB_OFFSET=0x8000 -DHAVE_HWSERIAL2 -DHAVE_HWSERIAL3 -DPIN_SERIAL2_RX=PD_6 @@ -917,10 +1245,10 @@ platform = ${common_stm32.platform} extends = common_stm32 build_flags = ${common_stm32.build_flags} -Os - "-DUSB_PRODUCT=\"RUMBA32\"" -DHAL_PCD_MODULE_ENABLED -DDISABLE_GENERIC_SERIALUSB -DHAL_UART_MODULE_ENABLED + -DTIMER_SERIAL=TIM9 board = rumba32_f446ve upload_protocol = dfu monitor_speed = 500000 @@ -959,6 +1287,19 @@ platform = teensy board = teensy35 src_filter = ${common.default_src_filter} + +[env:teensy36] +platform = teensy +board = teensy36 +src_filter = ${common.default_src_filter} + + +# +# Teensy 4.0 / 4.1 (ARM Cortex-M7) +# +[env:teensy41] +platform = teensy +board = teensy41 +src_filter = ${common.default_src_filter} + + # # Native # No supported Arduino libraries, base Marlin only