diff --git a/.vscode/extensions.json b/.vscode/extensions.json index 7226831cb1829..f495d14f53e87 100644 --- a/.vscode/extensions.json +++ b/.vscode/extensions.json @@ -4,5 +4,8 @@ "recommendations": [ "marlinfirmware.auto-build", "platformio.platformio-ide" + ], + "unwantedRecommendations": [ + "ms-vscode.cpptools-extension-pack" ] } diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index d3c36ad4850de..c2d5dced283b5 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -459,6 +459,7 @@ * 61 : 100kΩ Formbot/Vivedino 350°C Thermistor - beta 3950 * 66 : 4.7MΩ Dyze Design High Temperature Thermistor * 67 : 500kΩ SliceEngineering 450°C Thermistor + * 68 : PT100 amplifier board from Dyze Design * 70 : 100kΩ bq Hephestos 2 * 75 : 100kΩ Generic Silicon Heat Pad with NTC100K MGB18-104F39050L32 * 2000 : 100kΩ Ultimachine Rambo TDK NTCG104LH104KT1 NTC100K motherboard Thermistor @@ -1913,8 +1914,7 @@ #if ENABLED(NOZZLE_PARK_FEATURE) // Specify a park position as { X, Y, Z_raise } #define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 } - //#define NOZZLE_PARK_X_ONLY // X move only is required to park - //#define NOZZLE_PARK_Y_ONLY // Y move only is required to park + #define NOZZLE_PARK_MOVE 0 // Park motion: 0 = XY Move, 1 = X Only, 2 = Y Only, 3 = X before Y, 4 = Y before X #define NOZZLE_PARK_Z_RAISE_MIN 2 // (mm) Always raise Z by at least this distance #define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis) #define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers) @@ -2807,7 +2807,7 @@ // Ender-3 v2 OEM display. A DWIN display with Rotary Encoder. // //#define DWIN_CREALITY_LCD // Creality UI -//#define DWIN_CREALITY_LCD_ENHANCED // Enhanced UI +//#define DWIN_LCD_PROUI // Pro UI by MRiscoC //#define DWIN_CREALITY_LCD_JYERSUI // Jyers UI by Jacob Myers //#define DWIN_MARLINUI_PORTRAIT // MarlinUI (portrait orientation) //#define DWIN_MARLINUI_LANDSCAPE // MarlinUI (landscape orientation) @@ -2820,7 +2820,7 @@ #define BUTTON_DELAY_EDIT 50 // (ms) Button repeat delay for edit screens #define BUTTON_DELAY_MENU 250 // (ms) Button repeat delay for menus - //#define TOUCH_IDLE_SLEEP 300 // (secs) Turn off the TFT backlight if set (5mn) + //#define TOUCH_IDLE_SLEEP 300 // (s) Turn off the TFT backlight if set (5mn) #define TOUCH_SCREEN_CALIBRATION diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index f2676828fffbd..83a8eaa0fb877 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -347,7 +347,11 @@ #endif #if ANY(THERMAL_PROTECTION_HOTENDS, THERMAL_PROTECTION_BED, THERMAL_PROTECTION_CHAMBER, THERMAL_PROTECTION_COOLER) - #define THERMAL_PROTECTION_VARIANCE_MONITOR // Detect a sensor malfunction preventing temperature updates + /** + * Thermal Protection Variance Monitor - EXPERIMENTAL. + * Kill the machine on a stuck temperature sensor. Disable if you get false positives. + */ + //#define THERMAL_PROTECTION_VARIANCE_MONITOR // Detect a sensor malfunction preventing temperature updates #endif #if ENABLED(PIDTEMP) @@ -959,15 +963,17 @@ //#define Z_STEPPERS_ORIENTATION 0 #endif - // Provide Z stepper positions for more rapid convergence in bed alignment. - // Requires triple stepper drivers (i.e., set NUM_Z_STEPPER_DRIVERS to 3) - //#define Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS - #if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) - // Define Stepper XY positions for Z1, Z2, Z3 corresponding to - // the Z screw positions in the bed carriage. - // Define one position per Z stepper in stepper driver order. - #define Z_STEPPER_ALIGN_STEPPER_XY { { 210.7, 102.5 }, { 152.6, 220.0 }, { 94.5, 102.5 } } - #else + /** + * Z Stepper positions for more rapid convergence in bed alignment. + * Requires NUM_Z_STEPPER_DRIVERS to be 3 or 4. + * + * Define Stepper XY positions for Z1, Z2, Z3... corresponding to the screw + * positions in the bed carriage, with one position per Z stepper in stepper + * driver order. + */ + //#define Z_STEPPER_ALIGN_STEPPER_XY { { 210.7, 102.5 }, { 152.6, 220.0 }, { 94.5, 102.5 } } + + #ifndef Z_STEPPER_ALIGN_STEPPER_XY // Amplification factor. Used to scale the correction step up or down in case // the stepper (spindle) position is farther out than the test point. #define Z_STEPPER_ALIGN_AMP 1.0 // Use a value > 1.0 NOTE: This may cause instability! @@ -1277,6 +1283,11 @@ #define FEEDRATE_CHANGE_BEEP_FREQUENCY 440 #endif +// +// LCD Backlight Timeout +// +//#define LCD_BACKLIGHT_TIMEOUT 30 // (s) Timeout before turning off the backlight + #if HAS_BED_PROBE && EITHER(HAS_MARLINUI_MENU, HAS_TFT_LVGL_UI) //#define PROBE_OFFSET_WIZARD // Add a Probe Z Offset calibration option to the LCD menu #if ENABLED(PROBE_OFFSET_WIZARD) @@ -1294,7 +1305,7 @@ #if HAS_MARLINUI_MENU - #if BOTH(HAS_BED_PROBE, AUTO_BED_LEVELING_BILINEAR) + #if HAS_BED_PROBE // Add calibration in the Probe Offsets menu to compensate for X-axis twist. //#define X_AXIS_TWIST_COMPENSATION #if ENABLED(X_AXIS_TWIST_COMPENSATION) @@ -1306,6 +1317,7 @@ #define XATC_START_Z 0.0 #define XATC_MAX_POINTS 3 // Number of points to probe in the wizard #define XATC_Y_POSITION Y_CENTER // (mm) Y position to probe + #define XATC_Z_OFFSETS { 0, 0, 0 } // Z offsets for X axis sample points #endif #endif @@ -1323,11 +1335,11 @@ #endif // HAS_MARLINUI_MENU -#if ANY(HAS_DISPLAY, DWIN_CREALITY_LCD_ENHANCED, DWIN_CREALITY_LCD_JYERSUI) +#if ANY(HAS_DISPLAY, DWIN_LCD_PROUI, DWIN_CREALITY_LCD_JYERSUI) //#define SOUND_MENU_ITEM // Add a mute option to the LCD menu #endif -#if EITHER(HAS_DISPLAY, DWIN_CREALITY_LCD_ENHANCED) +#if EITHER(HAS_DISPLAY, DWIN_LCD_PROUI) // The timeout (in ms) to return to the status screen from sub-menus //#define LCD_TIMEOUT_TO_STATUS 15000 @@ -1626,7 +1638,10 @@ // Enable if SD detect is rendered useless (e.g., by using an SD extender) //#define NO_SD_DETECT - // Multiple volume support - EXPERIMENTAL. + /** + * Multiple volume support - EXPERIMENTAL. + * Adds 'M21 Pm' / 'M21 S' / 'M21 U' to mount SD Card / USB Drive. + */ //#define MULTI_VOLUME #if ENABLED(MULTI_VOLUME) #define VOLUME_SD_ONBOARD @@ -2337,6 +2352,15 @@ // For serial echo, the number of digits after the decimal point //#define SERIAL_FLOAT_PRECISION 4 +/** + * Set the number of proportional font spaces required to fill up a typical character space. + * This can help to better align the output of commands like `G29 O` Mesh Output. + * + * For clients that use a fixed-width font (like OctoPrint), leave this set to 1.0. + * Otherwise, adjust according to your client and font. + */ +#define PROPORTIONAL_FONT_RATIO 1.0 + // @section extras /** @@ -2417,7 +2441,7 @@ #if ENABLED(TOOLCHANGE_FILAMENT_SWAP) // Load / Unload #define TOOLCHANGE_FS_LENGTH 12 // (mm) Load / Unload length - #define TOOLCHANGE_FS_EXTRA_RESUME_LENGTH 0 // (mm) Extra length for better restart, fine tune by LCD/Gcode) + #define TOOLCHANGE_FS_EXTRA_RESUME_LENGTH 0 // (mm) Extra length for better restart. Adjust with LCD or M217 B. #define TOOLCHANGE_FS_RETRACT_SPEED (50*60) // (mm/min) (Unloading) #define TOOLCHANGE_FS_UNRETRACT_SPEED (25*60) // (mm/min) (On SINGLENOZZLE or Bowden loading must be slowed down) @@ -2431,12 +2455,12 @@ #define TOOLCHANGE_FS_FAN_SPEED 255 // 0-255 #define TOOLCHANGE_FS_FAN_TIME 10 // (seconds) - // Swap uninitialized extruder with TOOLCHANGE_FS_PRIME_SPEED for all lengths (recover + prime) + // Swap uninitialized extruder (using TOOLCHANGE_FS_PRIME_SPEED feedrate) // (May break filament if not retracted beforehand.) //#define TOOLCHANGE_FS_INIT_BEFORE_SWAP - // Prime on the first T0 (If other, TOOLCHANGE_FS_INIT_BEFORE_SWAP applied) - // Enable it (M217 V[0/1]) before printing, to avoid unwanted priming on host connect + // Prime on the first T0 (For other tools use TOOLCHANGE_FS_INIT_BEFORE_SWAP) + // Enable with M217 V1 before printing to avoid unwanted priming on host connect //#define TOOLCHANGE_FS_PRIME_FIRST_USED /** @@ -3431,7 +3455,7 @@ * You'll need to select a pin for the ON/OFF function and optionally choose a 0-5V * hardware PWM pin for the speed control and a pin for the rotation direction. * - * See https://marlinfw.org/docs/configuration/laser_spindle.html for more config details. + * See https://marlinfw.org/docs/configuration/2.0.9/laser_spindle.html for more config details. */ //#define SPINDLE_FEATURE //#define LASER_FEATURE @@ -3780,15 +3804,6 @@ //#define REPORT_FAN_CHANGE // Report the new fan speed when changed by M106 (and others) -/** - * Set the number of proportional font spaces required to fill up a typical character space. - * This can help to better align the output of commands like `G29 O` Mesh Output. - * - * For clients that use a fixed-width font (like OctoPrint), leave this set to 1.0. - * Otherwise, adjust according to your client and font. - */ -#define PROPORTIONAL_FONT_RATIO 1.0 - /** * Spend 28 bytes of SRAM to optimize the G-code parser */ diff --git a/Marlin/Version.h b/Marlin/Version.h index 497f49e284a04..49daf8dd7f073 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2022-02-08" +//#define STRING_DISTRIBUTION_DATE "2022-03-12" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/HAL/AVR/HAL.cpp b/Marlin/src/HAL/AVR/HAL.cpp index 666802725bc0d..7c39c5200b4d7 100644 --- a/Marlin/src/HAL/AVR/HAL.cpp +++ b/Marlin/src/HAL/AVR/HAL.cpp @@ -36,7 +36,7 @@ // ------------------------ // Don't initialize/override variable (which would happen in .init4) -uint8_t reset_reason __attribute__((section(".noinit"))); +uint8_t MarlinHAL::reset_reason __attribute__((section(".noinit"))); // ------------------------ // Public functions @@ -45,22 +45,22 @@ uint8_t reset_reason __attribute__((section(".noinit"))); __attribute__((naked)) // Don't output function pro- and epilogue __attribute__((used)) // Output the function, even if "not used" __attribute__((section(".init3"))) // Put in an early user definable section -void HAL_save_reset_reason() { +void save_reset_reason() { #if ENABLED(OPTIBOOT_RESET_REASON) __asm__ __volatile__( A("STS %0, r2") - : "=m"(reset_reason) + : "=m"(hal.reset_reason) ); #else - reset_reason = MCUSR; + hal.reset_reason = MCUSR; #endif // Clear within 16ms since WDRF bit enables a 16ms watchdog timer -> Boot loop - MCUSR = 0; + hal.clear_reset_source(); wdt_disable(); } -void HAL_init() { +void MarlinHAL::init() { // Init Servo Pins #define INIT_SERVO(N) OUT_WRITE(SERVO##N##_PIN, LOW) #if HAS_SERVO_0 @@ -79,7 +79,7 @@ void HAL_init() { init_pwm_timers(); // Init user timers to default frequency - 1000HZ } -void HAL_reboot() { +void MarlinHAL::reboot() { #if ENABLED(USE_WATCHDOG) while (1) { /* run out the watchdog */ } #else @@ -95,20 +95,20 @@ void HAL_reboot() { #else // !SDSUPPORT -extern "C" { - extern char __bss_end; - extern char __heap_start; - extern void* __brkval; - - int freeMemory() { - int free_memory; - if ((int)__brkval == 0) - free_memory = ((int)&free_memory) - ((int)&__bss_end); - else - free_memory = ((int)&free_memory) - ((int)__brkval); - return free_memory; + extern "C" { + extern char __bss_end; + extern char __heap_start; + extern void* __brkval; + + int freeMemory() { + int free_memory; + if ((int)__brkval == 0) + free_memory = ((int)&free_memory) - ((int)&__bss_end); + else + free_memory = ((int)&free_memory) - ((int)__brkval); + return free_memory; + } } -} #endif // !SDSUPPORT diff --git a/Marlin/src/HAL/AVR/HAL.h b/Marlin/src/HAL/AVR/HAL.h index f5cbcc9d51e1e..e825b4def3af8 100644 --- a/Marlin/src/HAL/AVR/HAL.h +++ b/Marlin/src/HAL/AVR/HAL.h @@ -74,9 +74,9 @@ #define CRITICAL_SECTION_START() unsigned char _sreg = SREG; cli() #define CRITICAL_SECTION_END() SREG = _sreg #endif -#define ISRS_ENABLED() TEST(SREG, SREG_I) -#define ENABLE_ISRS() sei() -#define DISABLE_ISRS() cli() + +#define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment +#define PWM_FREQUENCY 1000 // Default PWM frequency when set_pwm_duty() is called without set_pwm_frequency() // ------------------------ // Types @@ -84,16 +84,15 @@ typedef int8_t pin_t; -#define SHARED_SERVOS HAS_SERVOS -#define HAL_SERVO_LIB Servo +#define SHARED_SERVOS HAS_SERVOS // Use shared/servos.cpp + +class Servo; +typedef Servo hal_servo_t; // ------------------------ -// Public Variables +// Serial ports // ------------------------ -extern uint8_t reset_reason; - -// Serial ports #ifdef USBCON #include "../../core/serial_hook.h" typedef ForwardSerial1Class< decltype(Serial) > DefaultSerial1; @@ -142,20 +141,31 @@ extern uint8_t reset_reason; #endif #endif -// ------------------------ -// Public functions -// ------------------------ +// +// ADC +// +#define HAL_ADC_VREF 5.0 +#define HAL_ADC_RESOLUTION 10 -void HAL_init(); +// +// Pin Mapping for M42, M43, M226 +// +#define GET_PIN_MAP_PIN(index) index +#define GET_PIN_MAP_INDEX(pin) pin +#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) -//void cli(); +#define HAL_SENSITIVE_PINS 0, 1, -//void _delay_ms(const int delay); +#ifdef __AVR_AT90USB1286__ + #define JTAG_DISABLE() do{ MCUCR = 0x80; MCUCR = 0x80; }while(0) +#endif -inline void HAL_clear_reset_source() { } -inline uint8_t HAL_get_reset_source() { return reset_reason; } +// AVR compatibility +#define strtof strtod -void HAL_reboot(); +// ------------------------ +// Class Utilities +// ------------------------ #pragma GCC diagnostic push #if GCC_VERSION <= 50000 @@ -166,70 +176,96 @@ extern "C" int freeMemory(); #pragma GCC diagnostic pop -// ADC -#ifdef DIDR2 - #define HAL_ANALOG_SELECT(ind) do{ if (ind < 8) SBI(DIDR0, ind); else SBI(DIDR2, ind & 0x07); }while(0) -#else - #define HAL_ANALOG_SELECT(ind) SBI(DIDR0, ind); -#endif +// ------------------------ +// MarlinHAL Class +// ------------------------ -inline void HAL_adc_init() { - ADCSRA = _BV(ADEN) | _BV(ADSC) | _BV(ADIF) | 0x07; - DIDR0 = 0; - #ifdef DIDR2 - DIDR2 = 0; - #endif -} +class MarlinHAL { +public: -#define SET_ADMUX_ADCSRA(ch) ADMUX = _BV(REFS0) | (ch & 0x07); SBI(ADCSRA, ADSC) -#ifdef MUX5 - #define HAL_START_ADC(ch) if (ch > 7) ADCSRB = _BV(MUX5); else ADCSRB = 0; SET_ADMUX_ADCSRA(ch) -#else - #define HAL_START_ADC(ch) ADCSRB = 0; SET_ADMUX_ADCSRA(ch) -#endif + // Earliest possible init, before setup() + MarlinHAL() {} -#define HAL_ADC_VREF 5.0 -#define HAL_ADC_RESOLUTION 10 -#define HAL_READ_ADC() ADC -#define HAL_ADC_READY() !TEST(ADCSRA, ADSC) + static void init(); // Called early in setup() + static void init_board() {} // Called less early in setup() + static void reboot(); // Restart the firmware from 0x0 -#define GET_PIN_MAP_PIN(index) index -#define GET_PIN_MAP_INDEX(pin) pin -#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) + // Interrupts + static bool isr_state() { return TEST(SREG, SREG_I); } + static void isr_on() { sei(); } + static void isr_off() { cli(); } -#define HAL_SENSITIVE_PINS 0, 1, + static void delay_ms(const int ms) { _delay_ms(ms); } -#ifdef __AVR_AT90USB1286__ - #define JTAG_DISABLE() do{ MCUCR = 0x80; MCUCR = 0x80; }while(0) -#endif + // Tasks, called from idle() + static void idletask() {} -// AVR compatibility -#define strtof strtod + // Reset + static uint8_t reset_reason; + static uint8_t get_reset_source() { return reset_reason; } + static void clear_reset_source() { MCUSR = 0; } -#define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment -#define PWM_FREQUENCY 1000 // Default PWM frequency when set_pwm_duty() is called without set_pwm_frequency() + // Free SRAM + static int freeMemory() { return ::freeMemory(); } -/** - * set_pwm_frequency - * Sets the frequency of the timer corresponding to the provided pin - * as close as possible to the provided desired frequency. Internally - * calculates the required waveform generation mode, prescaler and - * resolution values required and sets the timer registers accordingly. - * NOTE that the frequency is applied to all pins on the timer (Ex OC3A, OC3B and OC3B) - * NOTE that there are limitations, particularly if using TIMER2. (see Configuration_adv.h -> FAST FAN PWM Settings) - */ -void set_pwm_frequency(const pin_t pin, const uint16_t f_desired); + // + // ADC Methods + // -/** - * set_pwm_duty - * Set the PWM duty cycle of the provided pin to the provided value - * Optionally allows inverting the duty cycle [default = false] - * Optionally allows changing the maximum size of the provided value to enable finer PWM duty control [default = 255] - */ -void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false); + // Called by Temperature::init once at startup + static void adc_init() { + ADCSRA = _BV(ADEN) | _BV(ADSC) | _BV(ADIF) | 0x07; + DIDR0 = 0; + #ifdef DIDR2 + DIDR2 = 0; + #endif + } -/* - * init_pwm_timers - * sets the default frequency for timers 2-5 to 1000HZ - */ -void init_pwm_timers(); + // Called by Temperature::init for each sensor at startup + static void adc_enable(const uint8_t ch) { + #ifdef DIDR2 + if (ch > 7) { SBI(DIDR2, ch & 0x07); return; } + #endif + SBI(DIDR0, ch); + } + + // Begin ADC sampling on the given channel + static void adc_start(const uint8_t ch) { + #ifdef MUX5 + ADCSRB = ch > 7 ? _BV(MUX5) : 0; + #else + ADCSRB = 0; + #endif + ADMUX = _BV(REFS0) | (ch & 0x07); + SBI(ADCSRA, ADSC); + } + + // Is the ADC ready for reading? + static bool adc_ready() { return !TEST(ADCSRA, ADSC); } + + // The current value of the ADC register + static __typeof__(ADC) adc_value() { return ADC; } + + /** + * init_pwm_timers + * Set the default frequency for timers 2-5 to 1000HZ + */ + static void init_pwm_timers(); + + /** + * Set the PWM duty cycle for the pin to the given value. + * Optionally invert the duty cycle [default = false] + * Optionally change the scale of the provided value to enable finer PWM duty control [default = 255] + */ + static void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false); + + /** + * Set the frequency of the timer for the given pin as close as + * possible to the provided desired frequency. Internally calculate + * the required waveform generation mode, prescaler, and resolution + * values and set timer registers accordingly. + * NOTE that the frequency is applied to all pins on the timer (Ex OC3A, OC3B and OC3B) + * NOTE that there are limitations, particularly if using TIMER2. (see Configuration_adv.h -> FAST_PWM_FAN Settings) + */ + static void set_pwm_frequency(const pin_t pin, const uint16_t f_desired); +}; diff --git a/Marlin/src/HAL/AVR/MarlinSerial.cpp b/Marlin/src/HAL/AVR/MarlinSerial.cpp index cd8bf5e6903b8..986462437c8f5 100644 --- a/Marlin/src/HAL/AVR/MarlinSerial.cpp +++ b/Marlin/src/HAL/AVR/MarlinSerial.cpp @@ -486,7 +486,7 @@ void MarlinSerial::write(const uint8_t c) { 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()) { + if (!hal.isr_state()) { // Make room by polling if it is possible to transmit, and do so! while (i == tx_buffer.tail) { @@ -534,7 +534,7 @@ void MarlinSerial::flushTX() { if (!_written) return; // If global interrupts are disabled (as the result of being called from an ISR)... - if (!ISRS_ENABLED()) { + if (!hal.isr_state()) { // Wait until everything was transmitted - We must do polling, as interrupts are disabled while (tx_buffer.head != tx_buffer.tail || !B_TXC) { diff --git a/Marlin/src/HAL/AVR/MarlinSerial.h b/Marlin/src/HAL/AVR/MarlinSerial.h index 84c5ddd2978ee..7eb76000d66e4 100644 --- a/Marlin/src/HAL/AVR/MarlinSerial.h +++ b/Marlin/src/HAL/AVR/MarlinSerial.h @@ -191,13 +191,13 @@ rx_framing_errors; static ring_buffer_pos_t rx_max_enqueued; - static FORCE_INLINE ring_buffer_pos_t atomic_read_rx_head(); + FORCE_INLINE static ring_buffer_pos_t atomic_read_rx_head(); static volatile bool rx_tail_value_not_stable; static volatile uint16_t rx_tail_value_backup; - static FORCE_INLINE void atomic_set_rx_tail(ring_buffer_pos_t value); - static FORCE_INLINE ring_buffer_pos_t atomic_read_rx_tail(); + FORCE_INLINE static void atomic_set_rx_tail(ring_buffer_pos_t value); + FORCE_INLINE static ring_buffer_pos_t atomic_read_rx_tail(); public: FORCE_INLINE static void store_rxd_char(); diff --git a/Marlin/src/HAL/AVR/fast_pwm.cpp b/Marlin/src/HAL/AVR/fast_pwm.cpp index f8201d028ebd0..0a384172c32a7 100644 --- a/Marlin/src/HAL/AVR/fast_pwm.cpp +++ b/Marlin/src/HAL/AVR/fast_pwm.cpp @@ -107,7 +107,7 @@ const Timer get_pwm_timer(const pin_t pin) { return Timer(); } -void set_pwm_frequency(const pin_t pin, const uint16_t f_desired) { +void MarlinHAL::set_pwm_frequency(const pin_t pin, const uint16_t f_desired) { const Timer timer = get_pwm_timer(pin); if (timer.isProtected || !timer.isPWM) return; // Don't proceed if protected timer or not recognized @@ -176,7 +176,7 @@ void set_pwm_frequency(const pin_t pin, const uint16_t f_desired) { _SET_ICRn(timer, res); // Set ICRn value (TOP) = res } -void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { +void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { // If v is 0 or v_size (max), digitalWrite to LOW or HIGH. // Note that digitalWrite also disables PWM output for us (sets COM bit to 0) if (v == 0) @@ -201,7 +201,7 @@ void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255 } } -void init_pwm_timers() { +void MarlinHAL::init_pwm_timers() { // Init some timer frequencies to a default 1KHz const pin_t pwm_pin[] = { #ifdef __AVR_ATmega2560__ diff --git a/Marlin/src/HAL/AVR/math.h b/Marlin/src/HAL/AVR/math.h index 7ede4accc09e1..7dd1018ff1990 100644 --- a/Marlin/src/HAL/AVR/math.h +++ b/Marlin/src/HAL/AVR/math.h @@ -35,7 +35,7 @@ // C B A is longIn1 // D C B A is longIn2 // -static FORCE_INLINE uint16_t MultiU24X32toH16(uint32_t longIn1, uint32_t longIn2) { +FORCE_INLINE static uint16_t MultiU24X32toH16(uint32_t longIn1, uint32_t longIn2) { uint8_t tmp1; uint8_t tmp2; uint16_t intRes; @@ -89,7 +89,7 @@ static FORCE_INLINE uint16_t MultiU24X32toH16(uint32_t longIn1, uint32_t longIn2 // uses: // r26 to store 0 // r27 to store the byte 1 of the 24 bit result -static FORCE_INLINE uint16_t MultiU16X8toH16(uint8_t charIn1, uint16_t intIn2) { +FORCE_INLINE static uint16_t MultiU16X8toH16(uint8_t charIn1, uint16_t intIn2) { uint8_t tmp; uint16_t intRes; __asm__ __volatile__ ( diff --git a/Marlin/src/HAL/AVR/timers.h b/Marlin/src/HAL/AVR/timers.h index ba3c4acd29eac..33c3880b6b99f 100644 --- a/Marlin/src/HAL/AVR/timers.h +++ b/Marlin/src/HAL/AVR/timers.h @@ -109,12 +109,12 @@ FORCE_INLINE void HAL_timer_start(const uint8_t timer_num, const uint32_t) { * (otherwise, characters will be lost due to UART overflow). * Then: Stepper, Endstops, Temperature, and -finally- all others. */ -#define HAL_timer_isr_prologue(T) -#define HAL_timer_isr_epilogue(T) +#define HAL_timer_isr_prologue(T) NOOP +#define HAL_timer_isr_epilogue(T) NOOP -/* 18 cycles maximum latency */ #ifndef HAL_STEP_TIMER_ISR +/* 18 cycles maximum latency */ #define HAL_STEP_TIMER_ISR() \ extern "C" void TIMER1_COMPA_vect() __attribute__ ((signal, naked, used, externally_visible)); \ extern "C" void TIMER1_COMPA_vect_bottom() asm ("TIMER1_COMPA_vect_bottom") __attribute__ ((used, externally_visible, noinline)); \ diff --git a/Marlin/src/HAL/DUE/HAL.cpp b/Marlin/src/HAL/DUE/HAL.cpp index a3985652e71dd..bbd13dc05aac2 100644 --- a/Marlin/src/HAL/DUE/HAL.cpp +++ b/Marlin/src/HAL/DUE/HAL.cpp @@ -34,7 +34,7 @@ // Public Variables // ------------------------ -uint16_t HAL_adc_result; +uint16_t MarlinHAL::adc_result; // ------------------------ // Public functions @@ -42,8 +42,7 @@ uint16_t HAL_adc_result; TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial()); -// HAL initialization task -void HAL_init() { +void MarlinHAL::init() { // Initialize the USB stack #if ENABLED(SDSUPPORT) OUT_WRITE(SDSS, HIGH); // Try to set SDSS inactive before any other SPI users start up @@ -52,21 +51,15 @@ void HAL_init() { TERN_(POSTMORTEM_DEBUGGING, install_min_serial()); // Install the min serial handler } -// HAL idle task -void HAL_idletask() { - // Perform USB stack housekeeping - usb_task_idle(); +void MarlinHAL::init_board() { + #ifdef BOARD_INIT + BOARD_INIT(); + #endif } -// Disable interrupts -void cli() { noInterrupts(); } - -// Enable interrupts -void sei() { interrupts(); } - -void HAL_clear_reset_source() { } +void MarlinHAL::idletask() { usb_task_idle(); } // Perform USB stack housekeeping -uint8_t HAL_get_reset_source() { +uint8_t MarlinHAL::get_reset_source() { switch ((RSTC->RSTC_SR >> 8) & 0x07) { case 0: return RST_POWER_ON; case 1: return RST_BACKUP; @@ -77,12 +70,7 @@ uint8_t HAL_get_reset_source() { } } -void HAL_reboot() { rstc_start_software_reset(RSTC); } - -void _delay_ms(const int delay_ms) { - // Todo: port for Due? - delay(delay_ms); -} +void MarlinHAL::reboot() { rstc_start_software_reset(RSTC); } extern "C" { extern unsigned int _ebss; // end of bss section @@ -94,19 +82,6 @@ int freeMemory() { return (int)&free_memory - (heap_end ?: (int)&_ebss); } -// ------------------------ -// ADC -// ------------------------ - -void HAL_adc_start_conversion(const uint8_t ch) { - HAL_adc_result = analogRead(ch); -} - -uint16_t HAL_adc_get_result() { - // nop - return HAL_adc_result; -} - // Forward the default serial ports #if USING_HW_SERIAL0 DefaultSerial1 MSerial0(false, Serial); diff --git a/Marlin/src/HAL/DUE/HAL.h b/Marlin/src/HAL/DUE/HAL.h index 96ab5d9808ac1..9a02c9a0dcf5f 100644 --- a/Marlin/src/HAL/DUE/HAL.h +++ b/Marlin/src/HAL/DUE/HAL.h @@ -38,6 +38,10 @@ #include "../../core/serial_hook.h" +// ------------------------ +// Serial ports +// ------------------------ + typedef ForwardSerial1Class< decltype(Serial) > DefaultSerial1; typedef ForwardSerial1Class< decltype(Serial1) > DefaultSerial2; typedef ForwardSerial1Class< decltype(Serial2) > DefaultSerial3; @@ -97,60 +101,38 @@ extern DefaultSerial4 MSerial3; #include "MarlinSerial.h" #include "MarlinSerialUSB.h" -// On AVR this is in math.h? -#define square(x) ((x)*(x)) +// ------------------------ +// Types +// ------------------------ typedef int8_t pin_t; -#define SHARED_SERVOS HAS_SERVOS -#define HAL_SERVO_LIB Servo +#define SHARED_SERVOS HAS_SERVOS // Use shared/servos.cpp + +class Servo; +typedef Servo hal_servo_t; // // Interrupts // -#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() - -void cli(); // Disable interrupts -void sei(); // Enable interrupts +#define sei() noInterrupts() +#define cli() interrupts() -void HAL_clear_reset_source(); // clear reset reason -uint8_t HAL_get_reset_source(); // get reset reason - -void HAL_reboot(); +#define CRITICAL_SECTION_START() const bool _irqon = hal.isr_state(); hal.isr_off() +#define CRITICAL_SECTION_END() if (_irqon) hal.isr_on() // // ADC // -extern uint16_t HAL_adc_result; // result of last ADC conversion +#define HAL_ADC_VREF 3.3 +#define HAL_ADC_RESOLUTION 10 #ifndef analogInputToDigitalPin #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1) #endif -#define HAL_ANALOG_SELECT(ch) - -inline void HAL_adc_init() {}//todo - -#define HAL_ADC_VREF 3.3 -#define HAL_ADC_RESOLUTION 10 -#define HAL_START_ADC(ch) HAL_adc_start_conversion(ch) -#define HAL_READ_ADC() HAL_adc_result -#define HAL_ADC_READY() true - -void HAL_adc_start_conversion(const uint8_t ch); -uint16_t HAL_adc_get_result(); - -// -// PWM // -inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } - -// -// Pin Map +// Pin Mapping for M42, M43, M226 // #define GET_PIN_MAP_PIN(index) index #define GET_PIN_MAP_INDEX(pin) pin @@ -159,27 +141,18 @@ inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, // // Tone // -void toneInit(); void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration=0); void noTone(const pin_t _pin); -// Enable hooks into idle and setup for HAL -#define HAL_IDLETASK 1 -void HAL_idletask(); -void HAL_init(); - -// -// Utility functions -// -void _delay_ms(const int delay); +// ------------------------ +// Class Utilities +// ------------------------ #pragma GCC diagnostic push #if GCC_VERSION <= 50000 #pragma GCC diagnostic ignored "-Wunused-function" #endif -int freeMemory(); - #pragma GCC diagnostic pop #ifdef __cplusplus @@ -189,3 +162,69 @@ char *dtostrf(double __val, signed char __width, unsigned char __prec, char *__s #ifdef __cplusplus } #endif + +// Return free RAM between end of heap (or end bss) and whatever is current +int freeMemory(); + +// ------------------------ +// MarlinHAL Class +// ------------------------ + +class MarlinHAL { +public: + + // Earliest possible init, before setup() + MarlinHAL() {} + + static void init(); // Called early in setup() + static void init_board(); // Called less early in setup() + static void reboot(); // Software reset + + // Interrupts + static bool isr_state() { return !__get_PRIMASK(); } + static void isr_on() { __enable_irq(); } + static void isr_off() { __disable_irq(); } + + static void delay_ms(const int ms) { delay(ms); } + + // Tasks, called from idle() + static void idletask(); + + // Reset + static uint8_t get_reset_source(); + static void clear_reset_source() {} + + // Free SRAM + static int freeMemory() { return ::freeMemory(); } + + // + // ADC Methods + // + + static uint16_t adc_result; + + // Called by Temperature::init once at startup + static void adc_init() {} + + // Called by Temperature::init for each sensor at startup + static void adc_enable(const uint8_t ch) {} + + // Begin ADC sampling on the given channel + static void adc_start(const uint8_t ch) { adc_result = analogRead(ch); } + + // Is the ADC ready for reading? + static bool adc_ready() { return true; } + + // The current value of the ADC register + static uint16_t adc_value() { return adc_result; } + + /** + * Set the PWM duty cycle for the pin to the given value. + * No inverting the duty cycle in this HAL. + * No changing the maximum size of the provided value to enable finer PWM duty control in this HAL. + */ + static void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { + analogWrite(pin, v); + } + +}; diff --git a/Marlin/src/HAL/DUE/MarlinSerial.cpp b/Marlin/src/HAL/DUE/MarlinSerial.cpp index fe62ff5607d51..638f7a100722d 100644 --- a/Marlin/src/HAL/DUE/MarlinSerial.cpp +++ b/Marlin/src/HAL/DUE/MarlinSerial.cpp @@ -406,7 +406,7 @@ size_t MarlinSerial::write(const uint8_t c) { 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()) { + if (!hal.isr_state()) { // Make room by polling if it is possible to transmit, and do so! while (i == tx_buffer.tail) { @@ -454,7 +454,7 @@ void MarlinSerial::flushTX() { if (!_written) return; // If global interrupts are disabled (as the result of being called from an ISR)... - if (!ISRS_ENABLED()) { + if (!hal.isr_state()) { // Wait until everything was transmitted - We must do polling, as interrupts are disabled while (tx_buffer.head != tx_buffer.tail || !(HWUART->UART_SR & UART_SR_TXEMPTY)) { diff --git a/Marlin/src/HAL/DUE/Tone.cpp b/Marlin/src/HAL/DUE/Tone.cpp index 1ac81faaf0e1c..4bc8142aba272 100644 --- a/Marlin/src/HAL/DUE/Tone.cpp +++ b/Marlin/src/HAL/DUE/Tone.cpp @@ -35,7 +35,7 @@ static pin_t tone_pin; volatile static int32_t toggles; -void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration) { +void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration/*=0*/) { tone_pin = _pin; toggles = 2 * frequency * duration / 1000; HAL_timer_start(MF_TIMER_TONE, 2 * frequency); diff --git a/Marlin/src/HAL/DUE/timers.h b/Marlin/src/HAL/DUE/timers.h index e2932ff36f91b..bcfd07e268c57 100644 --- a/Marlin/src/HAL/DUE/timers.h +++ b/Marlin/src/HAL/DUE/timers.h @@ -125,4 +125,4 @@ FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) { pConfig->pTimerRegs->TC_CHANNEL[pConfig->channel].TC_SR; } -#define HAL_timer_isr_epilogue(T) +#define HAL_timer_isr_epilogue(T) NOOP diff --git a/Marlin/src/HAL/ESP32/HAL.cpp b/Marlin/src/HAL/ESP32/HAL.cpp index 499582b8c194f..4000dcc90853d 100644 --- a/Marlin/src/HAL/ESP32/HAL.cpp +++ b/Marlin/src/HAL/ESP32/HAL.cpp @@ -52,7 +52,7 @@ // Externs // ------------------------ -portMUX_TYPE spinlock = portMUX_INITIALIZER_UNLOCKED; +portMUX_TYPE MarlinHAL::spinlock = portMUX_INITIALIZER_UNLOCKED; // ------------------------ // Local defines @@ -64,7 +64,7 @@ portMUX_TYPE spinlock = portMUX_INITIALIZER_UNLOCKED; // Public Variables // ------------------------ -uint16_t HAL_adc_result; +uint16_t MarlinHAL::adc_result; // ------------------------ // Private Variables @@ -95,20 +95,22 @@ volatile int numPWMUsed = 0, #endif #if ENABLED(USE_ESP32_EXIO) + HardwareSerial YSerial2(2); void Write_EXIO(uint8_t IO, uint8_t v) { - if (ISRS_ENABLED()) { - DISABLE_ISRS(); + if (hal.isr_state()) { + hal.isr_off(); YSerial2.write(0x80 | (((char)v) << 5) | (IO - 100)); - ENABLE_ISRS(); + hal.isr_on(); } else YSerial2.write(0x80 | (((char)v) << 5) | (IO - 100)); } + #endif -void HAL_init_board() { +void MarlinHAL::init_board() { #if ENABLED(USE_ESP32_TASK_WDT) esp_task_wdt_init(10, true); #endif @@ -154,27 +156,26 @@ void HAL_init_board() { #endif } -void HAL_idletask() { +void MarlinHAL::idletask() { #if BOTH(WIFISUPPORT, OTASUPPORT) OTA_handle(); #endif TERN_(ESP3D_WIFISUPPORT, esp3dlib.idletask()); } -void HAL_clear_reset_source() { } +uint8_t MarlinHAL::get_reset_source() { return rtc_get_reset_reason(1); } -uint8_t HAL_get_reset_source() { return rtc_get_reset_reason(1); } - -void HAL_reboot() { ESP.restart(); } +void MarlinHAL::reboot() { ESP.restart(); } void _delay_ms(int delay_ms) { delay(delay_ms); } // return free memory between end of heap (or end bss) and whatever is current -int freeMemory() { return ESP.getFreeHeap(); } +int MarlinHAL::freeMemory() { return ESP.getFreeHeap(); } // ------------------------ // ADC // ------------------------ + #define ADC1_CHANNEL(pin) ADC1_GPIO ## pin ## _CHANNEL adc1_channel_t get_channel(int pin) { @@ -196,7 +197,7 @@ void adc1_set_attenuation(adc1_channel_t chan, adc_atten_t atten) { } } -void HAL_adc_init() { +void MarlinHAL::adc_init() { // Configure ADC adc1_config_width(ADC_WIDTH_12Bit); @@ -228,11 +229,11 @@ void HAL_adc_init() { } } -void HAL_adc_start_conversion(const uint8_t adc_pin) { - const adc1_channel_t chan = get_channel(adc_pin); +void MarlinHAL::adc_start(const pin_t pin) { + const adc1_channel_t chan = get_channel(pin); uint32_t mv; esp_adc_cal_get_voltage((adc_channel_t)chan, &characteristics[attenuations[chan]], &mv); - HAL_adc_result = mv * 1023.0 / 3300.0; + adc_result = mv * 1023.0 / 3300.0; // Change the attenuation level based on the new reading adc_atten_t atten; diff --git a/Marlin/src/HAL/ESP32/HAL.h b/Marlin/src/HAL/ESP32/HAL.h index 78eebc8d823c0..df52e2186cbd3 100644 --- a/Marlin/src/HAL/ESP32/HAL.h +++ b/Marlin/src/HAL/ESP32/HAL.h @@ -49,8 +49,6 @@ // Defines // ------------------------ -extern portMUX_TYPE spinlock; - #define MYSERIAL1 flushableSerial #if EITHER(WIFISUPPORT, ESP3D_WIFISUPPORT) @@ -65,9 +63,6 @@ extern portMUX_TYPE spinlock; #define CRITICAL_SECTION_START() portENTER_CRITICAL(&spinlock) #define CRITICAL_SECTION_END() portEXIT_CRITICAL(&spinlock) -#define ISRS_ENABLED() (spinlock.owner == portMUX_FREE_VAL) -#define ENABLE_ISRS() if (spinlock.owner != portMUX_FREE_VAL) portEXIT_CRITICAL(&spinlock) -#define DISABLE_ISRS() portENTER_CRITICAL(&spinlock) // ------------------------ // Types @@ -75,14 +70,8 @@ extern portMUX_TYPE spinlock; typedef int16_t pin_t; -#define HAL_SERVO_LIB Servo - -// ------------------------ -// Public Variables -// ------------------------ - -/** result of last ADC conversion */ -extern uint16_t HAL_adc_result; +class Servo; +typedef Servo hal_servo_t; // ------------------------ // Public functions @@ -91,59 +80,18 @@ extern uint16_t HAL_adc_result; // // Tone // -void toneInit(); void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration=0); void noTone(const pin_t _pin); -// clear reset reason -void HAL_clear_reset_source(); - -// reset reason -uint8_t HAL_get_reset_source(); - -void HAL_reboot(); - -void _delay_ms(int delay); - -#pragma GCC diagnostic push -#if GCC_VERSION <= 50000 - #pragma GCC diagnostic ignored "-Wunused-function" -#endif - -int freeMemory(); - -#pragma GCC diagnostic pop - void analogWrite(pin_t pin, int value); -// ADC -#define HAL_ANALOG_SELECT(pin) - -void HAL_adc_init(); - -#define HAL_ADC_VREF 3.3 -#define HAL_ADC_RESOLUTION 10 -#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) -#define HAL_READ_ADC() HAL_adc_result -#define HAL_ADC_READY() true - -void HAL_adc_start_conversion(const uint8_t adc_pin); - -// PWM -inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } - -// Pin Map +// +// Pin Mapping for M42, M43, M226 +// #define GET_PIN_MAP_PIN(index) index #define GET_PIN_MAP_INDEX(pin) pin #define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) -// Enable hooks into idle and setup for HAL -#define HAL_IDLETASK 1 -#define BOARD_INIT() HAL_init_board() -void HAL_idletask(); -inline void HAL_init() {} -void HAL_init_board(); - #if ENABLED(USE_ESP32_EXIO) void Write_EXIO(uint8_t IO, uint8_t v); #endif @@ -188,3 +136,85 @@ FORCE_INLINE static void DELAY_CYCLES(uint32_t x) { } } + +// ------------------------ +// Class Utilities +// ------------------------ + +#pragma GCC diagnostic push +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic ignored "-Wunused-function" +#endif + +int freeMemory(); + +#pragma GCC diagnostic pop + +void _delay_ms(const int ms); + +// ------------------------ +// MarlinHAL Class +// ------------------------ + +#define HAL_ADC_VREF 3.3 +#define HAL_ADC_RESOLUTION 10 + +class MarlinHAL { +public: + + // Earliest possible init, before setup() + MarlinHAL() {} + + static void init() {} // Called early in setup() + static void init_board(); // Called less early in setup() + static void reboot(); // Restart the firmware + + // Interrupts + static portMUX_TYPE spinlock; + static bool isr_state() { return spinlock.owner == portMUX_FREE_VAL; } + static void isr_on() { if (spinlock.owner != portMUX_FREE_VAL) portEXIT_CRITICAL(&spinlock); } + static void isr_off() { portENTER_CRITICAL(&spinlock); } + + static void delay_ms(const int ms) { _delay_ms(ms); } + + // Tasks, called from idle() + static void idletask(); + + // Reset + static uint8_t get_reset_source(); + static void clear_reset_source() {} + + // Free SRAM + static int freeMemory(); + + // + // ADC Methods + // + + static uint16_t adc_result; + + // Called by Temperature::init once at startup + static void adc_init(); + + // Called by Temperature::init for each sensor at startup + static void adc_enable(const pin_t pin) {} + + // Begin ADC sampling on the given channel + static void adc_start(const pin_t pin); + + // Is the ADC ready for reading? + static bool adc_ready() { return true; } + + // The current value of the ADC register + static uint16_t adc_value() { return adc_result; } + + /** + * Set the PWM duty cycle for the pin to the given value. + * No inverting the duty cycle in this HAL. + * No changing the maximum size of the provided value to enable finer PWM duty control in this HAL. + */ + static void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { + analogWrite(pin, v); + } + +}; diff --git a/Marlin/src/HAL/ESP32/Tone.cpp b/Marlin/src/HAL/ESP32/Tone.cpp index 9c16cdde800ae..839c612b6a870 100644 --- a/Marlin/src/HAL/ESP32/Tone.cpp +++ b/Marlin/src/HAL/ESP32/Tone.cpp @@ -35,7 +35,7 @@ static pin_t tone_pin; volatile static int32_t toggles; -void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration) { +void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration/*=0*/) { tone_pin = _pin; toggles = 2 * frequency * duration / 1000; HAL_timer_start(MF_TIMER_TONE, 2 * frequency); diff --git a/Marlin/src/HAL/ESP32/timers.cpp b/Marlin/src/HAL/ESP32/timers.cpp index df0065f45396b..c37ad2430cb20 100644 --- a/Marlin/src/HAL/ESP32/timers.cpp +++ b/Marlin/src/HAL/ESP32/timers.cpp @@ -81,7 +81,7 @@ void IRAM_ATTR timer_isr(void *para) { * @param timer_num timer number to initialize * @param frequency frequency of the timer */ -void HAL_timer_start(const uint8_t timer_num, uint32_t frequency) { +void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { const tTimerConfig timer = timer_config[timer_num]; timer_config_t config; diff --git a/Marlin/src/HAL/ESP32/timers.h b/Marlin/src/HAL/ESP32/timers.h index 266169848daf7..aa4e1551f0666 100644 --- a/Marlin/src/HAL/ESP32/timers.h +++ b/Marlin/src/HAL/ESP32/timers.h @@ -127,7 +127,7 @@ extern const tTimerConfig timer_config[]; // Public functions // ------------------------ -void HAL_timer_start (const uint8_t timer_num, uint32_t frequency); +void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency); void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t count); hal_timer_t HAL_timer_get_compare(const uint8_t timer_num); hal_timer_t HAL_timer_get_count(const uint8_t timer_num); @@ -136,5 +136,5 @@ void HAL_timer_enable_interrupt(const uint8_t timer_num); void HAL_timer_disable_interrupt(const uint8_t timer_num); bool HAL_timer_interrupt_enabled(const uint8_t timer_num); -#define HAL_timer_isr_prologue(T) -#define HAL_timer_isr_epilogue(T) +#define HAL_timer_isr_prologue(T) NOOP +#define HAL_timer_isr_epilogue(T) NOOP diff --git a/Marlin/src/HAL/ESP32/u8g_esp32_spi.cpp b/Marlin/src/HAL/ESP32/u8g_esp32_spi.cpp index e454130d43f30..0aa66ed2cf0d9 100644 --- a/Marlin/src/HAL/ESP32/u8g_esp32_spi.cpp +++ b/Marlin/src/HAL/ESP32/u8g_esp32_spi.cpp @@ -30,6 +30,7 @@ #include #include "Arduino.h" #include "../shared/HAL_SPI.h" +#include "HAL.h" #include "SPI.h" static SPISettings spiConfig; diff --git a/Marlin/src/HAL/LINUX/HAL.cpp b/Marlin/src/HAL/LINUX/HAL.cpp index 0b679170ef171..db43f42eaafd3 100644 --- a/Marlin/src/HAL/LINUX/HAL.cpp +++ b/Marlin/src/HAL/LINUX/HAL.cpp @@ -24,6 +24,10 @@ #include "../../inc/MarlinConfig.h" #include "../shared/Delay.h" +// ------------------------ +// Serial ports +// ------------------------ + MSerialT usb_serial(TERN0(EMERGENCY_PARSER, true)); // U8glib required functions @@ -37,42 +41,21 @@ extern "C" { //************************// // return free heap space -int freeMemory() { - return 0; -} +int freeMemory() { return 0; } // ------------------------ // ADC // ------------------------ -void HAL_adc_init() { - -} - -void HAL_adc_enable_channel(const uint8_t ch) { - -} - -uint8_t active_ch = 0; -void HAL_adc_start_conversion(const uint8_t ch) { - active_ch = ch; -} - -bool HAL_adc_finished() { - return true; -} +uint8_t MarlinHAL::active_ch = 0; -uint16_t HAL_adc_get_result() { - pin_t pin = analogInputToDigitalPin(active_ch); +uint16_t MarlinHAL::adc_value() { + const pin_t pin = analogInputToDigitalPin(active_ch); if (!VALID_PIN(pin)) return 0; - uint16_t data = ((Gpio::get(pin) >> 2) & 0x3FF); + const uint16_t data = ((Gpio::get(pin) >> 2) & 0x3FF); return data; // return 10bit value as Marlin expects } -void HAL_pwm_init() { - -} - -void HAL_reboot() { /* Reset the application state and GPIO */ } +void MarlinHAL::reboot() { /* Reset the application state and GPIO */ } #endif // __PLAT_LINUX__ diff --git a/Marlin/src/HAL/LINUX/HAL.h b/Marlin/src/HAL/LINUX/HAL.h index d7d3a92b73b95..43899c632de5f 100644 --- a/Marlin/src/HAL/LINUX/HAL.h +++ b/Marlin/src/HAL/LINUX/HAL.h @@ -21,25 +21,42 @@ */ #pragma once -#define CPU_32_BIT - -#define F_CPU 100000000UL -#define SystemCoreClock F_CPU #include #include #include - #undef min #undef max - #include -void _printf (const char *format, ...); +#include "hardware/Clock.h" + +#include "../shared/Marduino.h" +#include "../shared/math_32bit.h" +#include "../shared/HAL_SPI.h" +#include "fastio.h" +#include "watchdog.h" +#include "serial.h" + +// ------------------------ +// Defines +// ------------------------ + +#define CPU_32_BIT +#define SHARED_SERVOS HAS_SERVOS // Use shared/servos.cpp + +#define F_CPU 100000000UL +#define SystemCoreClock F_CPU + +#define DELAY_CYCLES(x) Clock::delayCycles(x) + +#define CPU_ST7920_DELAY_1 600 +#define CPU_ST7920_DELAY_2 750 +#define CPU_ST7920_DELAY_3 750 + +void _printf(const char *format, ...); void _putc(uint8_t c); uint8_t _getc(); -//extern "C" volatile uint32_t _millis; - //arduino: Print.h #define DEC 10 #define HEX 16 @@ -49,36 +66,27 @@ uint8_t _getc(); #define B01 1 #define B10 2 -#include "hardware/Clock.h" - -#include "../shared/Marduino.h" -#include "../shared/math_32bit.h" -#include "../shared/HAL_SPI.h" -#include "fastio.h" -#include "watchdog.h" -#include "serial.h" - -#define SHARED_SERVOS HAS_SERVOS +// ------------------------ +// Serial ports +// ------------------------ extern MSerialT usb_serial; #define MYSERIAL1 usb_serial -#define CPU_ST7920_DELAY_1 600 -#define CPU_ST7920_DELAY_2 750 -#define CPU_ST7920_DELAY_3 750 - // // Interrupts // #define CRITICAL_SECTION_START() #define CRITICAL_SECTION_END() -#define ISRS_ENABLED() -#define ENABLE_ISRS() -#define DISABLE_ISRS() -inline void HAL_init() {} +// ADC +#define HAL_ADC_VREF 5.0 +#define HAL_ADC_RESOLUTION 10 + +// ------------------------ +// Class Utilities +// ------------------------ -// Utility functions #pragma GCC diagnostic push #if GCC_VERSION <= 50000 #pragma GCC diagnostic ignored "-Wunused-function" @@ -88,29 +96,66 @@ int freeMemory(); #pragma GCC diagnostic pop -// ADC -#define HAL_ADC_VREF 5.0 -#define HAL_ADC_RESOLUTION 10 -#define HAL_ANALOG_SELECT(ch) HAL_adc_enable_channel(ch) -#define HAL_START_ADC(ch) HAL_adc_start_conversion(ch) -#define HAL_READ_ADC() HAL_adc_get_result() -#define HAL_ADC_READY() true +// ------------------------ +// MarlinHAL Class +// ------------------------ + +class MarlinHAL { +public: + + // Earliest possible init, before setup() + MarlinHAL() {} + + static void init() {} // Called early in setup() + static void init_board() {} // Called less early in setup() + static void reboot(); // Reset the application state and GPIO + + // Interrupts + static bool isr_state() { return true; } + static void isr_on() {} + static void isr_off() {} + + static void delay_ms(const int ms) { _delay_ms(ms); } + + // Tasks, called from idle() + static void idletask() {} + + // Reset + static constexpr uint8_t reset_reason = RST_POWER_ON; + static uint8_t get_reset_source() { return reset_reason; } + static void clear_reset_source() {} + + // Free SRAM + static int freeMemory() { return ::freeMemory(); } + + // + // ADC Methods + // + + static uint8_t active_ch; + + // Called by Temperature::init once at startup + static void adc_init() {} + + // Called by Temperature::init for each sensor at startup + static void adc_enable(const uint8_t) {} -void HAL_adc_init(); -void HAL_adc_enable_channel(const uint8_t ch); -void HAL_adc_start_conversion(const uint8_t ch); -uint16_t HAL_adc_get_result(); + // Begin ADC sampling on the given channel + static void adc_start(const uint8_t ch) { active_ch = ch; } -// PWM -inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } + // Is the ADC ready for reading? + static bool adc_ready() { return true; } -// Reset source -inline void HAL_clear_reset_source(void) {} -inline uint8_t HAL_get_reset_source(void) { return RST_POWER_ON; } + // The current value of the ADC register + static uint16_t adc_value(); -void HAL_reboot(); // Reset the application state and GPIO + /** + * Set the PWM duty cycle for the pin to the given value. + * No option to change the resolution or invert the duty cycle. + */ + static void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { + analogWrite(pin, v); + } -/* ---------------- Delay in cycles */ -FORCE_INLINE static void DELAY_CYCLES(uint64_t x) { - Clock::delayCycles(x); -} + static void set_pwm_frequency(const pin_t, int) {} +}; diff --git a/Marlin/src/HAL/LINUX/arduino.cpp b/Marlin/src/HAL/LINUX/arduino.cpp index 4b56d02a389c2..075b4ccde2f4d 100644 --- a/Marlin/src/HAL/LINUX/arduino.cpp +++ b/Marlin/src/HAL/LINUX/arduino.cpp @@ -31,9 +31,7 @@ void cli() { } // Disable void sei() { } // Enable // Time functions -void _delay_ms(const int delay_ms) { - delay(delay_ms); -} +void _delay_ms(const int ms) { delay(ms); } uint32_t millis() { return (uint32_t)Clock::millis(); diff --git a/Marlin/src/HAL/LINUX/include/Arduino.h b/Marlin/src/HAL/LINUX/include/Arduino.h index d4086e259a2f1..f05aaed88083e 100644 --- a/Marlin/src/HAL/LINUX/include/Arduino.h +++ b/Marlin/src/HAL/LINUX/include/Arduino.h @@ -59,10 +59,9 @@ typedef uint8_t byte; #endif #define sq(v) ((v) * (v)) -#define square(v) sq(v) #define constrain(value, arg_min, arg_max) ((value) < (arg_min) ? (arg_min) :((value) > (arg_max) ? (arg_max) : (value))) -//Interrupts +// Interrupts void cli(); // Disable void sei(); // Enable void attachInterrupt(uint32_t pin, void (*callback)(), uint32_t mode); @@ -74,8 +73,8 @@ extern "C" { } // Time functions -extern "C" void delay(const int milis); -void _delay_ms(const int delay); +extern "C" void delay(const int ms); +void _delay_ms(const int ms); void delayMicroseconds(unsigned long); uint32_t millis(); diff --git a/Marlin/src/HAL/LINUX/timers.h b/Marlin/src/HAL/LINUX/timers.h index a98ceb6f391d9..2d2a95774c1b0 100644 --- a/Marlin/src/HAL/LINUX/timers.h +++ b/Marlin/src/HAL/LINUX/timers.h @@ -92,5 +92,5 @@ void HAL_timer_enable_interrupt(const uint8_t timer_num); void HAL_timer_disable_interrupt(const uint8_t timer_num); bool HAL_timer_interrupt_enabled(const uint8_t timer_num); -#define HAL_timer_isr_prologue(T) -#define HAL_timer_isr_epilogue(T) +#define HAL_timer_isr_prologue(T) NOOP +#define HAL_timer_isr_epilogue(T) NOOP diff --git a/Marlin/src/HAL/LPC1768/HAL.cpp b/Marlin/src/HAL/LPC1768/HAL.cpp index cee9cfc5f744c..541848b08acc3 100644 --- a/Marlin/src/HAL/LPC1768/HAL.cpp +++ b/Marlin/src/HAL/LPC1768/HAL.cpp @@ -31,7 +31,7 @@ DefaultSerial1 USBSerial(false, UsbSerial); -uint32_t HAL_adc_reading = 0; +uint32_t MarlinHAL::adc_result = 0; // U8glib required functions extern "C" { @@ -41,8 +41,6 @@ extern "C" { void u8g_Delay(uint16_t val) { delay(val); } } -//************************// - // return free heap space int freeMemory() { char stack_end; @@ -54,33 +52,33 @@ int freeMemory() { return result; } -// scan command line for code -// return index into pin map array if found and the pin is valid. -// return dval if not found or not a valid pin. -int16_t PARSED_PIN_INDEX(const char code, const int16_t dval) { - const uint16_t val = (uint16_t)parser.intval(code, -1), port = val / 100, pin = val % 100; - const int16_t ind = (port < ((NUM_DIGITAL_PINS) >> 5) && pin < 32) ? ((port << 5) | pin) : -2; - return ind > -1 ? ind : dval; +void MarlinHAL::reboot() { NVIC_SystemReset(); } + +uint8_t MarlinHAL::get_reset_source() { + #if ENABLED(USE_WATCHDOG) + if (watchdog_timed_out()) return RST_WATCHDOG; + #endif + return RST_POWER_ON; +} + +void MarlinHAL::clear_reset_source() { + TERN_(USE_WATCHDOG, watchdog_clear_timeout_flag()); } void flashFirmware(const int16_t) { delay(500); // Give OS time to disconnect USB_Connect(false); // USB clear connection delay(1000); // Give OS time to notice - HAL_reboot(); + hal.reboot(); } -void HAL_clear_reset_source(void) { - TERN_(USE_WATCHDOG, watchdog_clear_timeout_flag()); -} - -uint8_t HAL_get_reset_source(void) { - #if ENABLED(USE_WATCHDOG) - if (watchdog_timed_out()) return RST_WATCHDOG; - #endif - return RST_POWER_ON; +// For M42/M43, scan command line for pin code +// return index into pin map array if found and the pin is valid. +// return dval if not found or not a valid pin. +int16_t PARSED_PIN_INDEX(const char code, const int16_t dval) { + const uint16_t val = (uint16_t)parser.intval(code, -1), port = val / 100, pin = val % 100; + const int16_t ind = (port < ((NUM_DIGITAL_PINS) >> 5) && pin < 32) ? ((port << 5) | pin) : -2; + return ind > -1 ? ind : dval; } -void HAL_reboot() { NVIC_SystemReset(); } - #endif // TARGET_LPC1768 diff --git a/Marlin/src/HAL/LPC1768/HAL.h b/Marlin/src/HAL/LPC1768/HAL.h index f5e4326983175..eefacae995492 100644 --- a/Marlin/src/HAL/LPC1768/HAL.h +++ b/Marlin/src/HAL/LPC1768/HAL.h @@ -28,8 +28,6 @@ #define CPU_32_BIT -void HAL_init(); - #include #include #include @@ -47,12 +45,9 @@ extern "C" volatile uint32_t _millis; #include #include -// -// Default graphical display delays -// -#define CPU_ST7920_DELAY_1 600 -#define CPU_ST7920_DELAY_2 750 -#define CPU_ST7920_DELAY_3 750 +// ------------------------ +// Serial ports +// ------------------------ typedef ForwardSerial1Class< decltype(UsbSerial) > DefaultSerial1; extern DefaultSerial1 USBSerial; @@ -114,26 +109,12 @@ extern DefaultSerial1 USBSerial; // // Interrupts // -#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() - -// -// Utility functions -// -#pragma GCC diagnostic push -#if GCC_VERSION <= 50000 - #pragma GCC diagnostic ignored "-Wunused-function" -#endif -int freeMemory(); - -#pragma GCC diagnostic pop +#define CRITICAL_SECTION_START() const bool irqon = !__get_PRIMASK(); __disable_irq() +#define CRITICAL_SECTION_END() if (irqon) __enable_irq() // -// ADC API +// ADC // #define ADC_MEDIAN_FILTER_SIZE (23) // Higher values increase step delay (phase shift), @@ -152,20 +133,9 @@ int freeMemory(); #define HAL_ADC_RESOLUTION 12 // 15 bit maximum, raw temperature is stored as int16_t #define HAL_ADC_FILTERED // Disable oversampling done in Marlin as ADC values already filtered in HAL -using FilteredADC = LPC176x::ADC; -extern uint32_t HAL_adc_reading; -[[gnu::always_inline]] inline void HAL_adc_start_conversion(const pin_t pin) { - HAL_adc_reading = FilteredADC::read(pin) >> (16 - HAL_ADC_RESOLUTION); // returns 16bit value, reduce to required bits -} -[[gnu::always_inline]] inline uint16_t HAL_adc_get_result() { - return HAL_adc_reading; -} - -#define HAL_adc_init() -#define HAL_ANALOG_SELECT(pin) FilteredADC::enable_channel(pin) -#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) -#define HAL_READ_ADC() HAL_adc_get_result() -#define HAL_ADC_READY() (true) +// +// Pin Mapping for M42, M43, M226 +// // Test whether the pin is valid constexpr bool VALID_PIN(const pin_t pin) { @@ -192,32 +162,101 @@ int16_t PARSED_PIN_INDEX(const char code, const int16_t dval); // P0.6 thru P0.9 are for the onboard SD card #define HAL_SENSITIVE_PINS P0_06, P0_07, P0_08, P0_09, -#define HAL_IDLETASK 1 -void HAL_idletask(); +// ------------------------ +// Defines +// ------------------------ #define PLATFORM_M997_SUPPORT void flashFirmware(const int16_t); #define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment -/** - * set_pwm_frequency - * Set the frequency of the timer corresponding to the provided pin - * All Hardware PWM pins run at the same frequency and all - * Software PWM pins run at the same frequency - */ -void set_pwm_frequency(const pin_t pin, const uint16_t f_desired); +// Default graphical display delays +#define CPU_ST7920_DELAY_1 600 +#define CPU_ST7920_DELAY_2 750 +#define CPU_ST7920_DELAY_3 750 -/** - * set_pwm_duty - * Set the PWM duty cycle of the provided pin to the provided value - * Optionally allows inverting the duty cycle [default = false] - * Optionally allows changing the maximum size of the provided value to enable finer PWM duty control [default = 255] - */ -void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false); +// ------------------------ +// Class Utilities +// ------------------------ + +#pragma GCC diagnostic push +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic ignored "-Wunused-function" +#endif + +int freeMemory(); + +#pragma GCC diagnostic pop + +// ------------------------ +// MarlinHAL Class +// ------------------------ + +class MarlinHAL { +public: + + // Earliest possible init, before setup() + MarlinHAL() {} + + static void init(); // Called early in setup() + static void init_board() {} // Called less early in setup() + static void reboot(); // Restart the firmware from 0x0 + + // Interrupts + static bool isr_state() { return !__get_PRIMASK(); } + static void isr_on() { __enable_irq(); } + static void isr_off() { __disable_irq(); } + + static void delay_ms(const int ms) { _delay_ms(ms); } + + // Tasks, called from idle() + static void idletask(); + + // Reset + static uint8_t get_reset_source(); + static void clear_reset_source(); + + // Free SRAM + static int freeMemory() { return ::freeMemory(); } + + // + // ADC Methods + // + + using FilteredADC = LPC176x::ADC; + + // Called by Temperature::init once at startup + static void adc_init() {} + + // Called by Temperature::init for each sensor at startup + static void adc_enable(const pin_t pin) { + FilteredADC::enable_channel(pin); + } + + // Begin ADC sampling on the given pin + static uint32_t adc_result; + static void adc_start(const pin_t pin) { + adc_result = FilteredADC::read(pin) >> (16 - HAL_ADC_RESOLUTION); // returns 16bit value, reduce to required bits + } + + // Is the ADC ready for reading? + static bool adc_ready() { return true; } + + // The current value of the ADC register + static uint16_t adc_value() { return uint16_t(adc_result); } -// Reset source -void HAL_clear_reset_source(void); -uint8_t HAL_get_reset_source(void); + /** + * Set the PWM duty cycle for the pin to the given value. + * Optionally invert the duty cycle [default = false] + * Optionally change the scale of the provided value to enable finer PWM duty control [default = 255] + */ + static void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false); -void HAL_reboot(); + /** + * Set the frequency of the timer corresponding to the provided pin + * All Hardware PWM pins will run at the same frequency and + * All Software PWM pins will run at the same frequency + */ + static void set_pwm_frequency(const pin_t pin, const uint16_t f_desired); +}; diff --git a/Marlin/src/HAL/LPC1768/Servo.h b/Marlin/src/HAL/LPC1768/Servo.h index eb12fd20f4d87..f02f503a67daa 100644 --- a/Marlin/src/HAL/LPC1768/Servo.h +++ b/Marlin/src/HAL/LPC1768/Servo.h @@ -65,4 +65,5 @@ class libServo: public Servo { } }; -#define HAL_SERVO_LIB libServo +class libServo; +typedef libServo hal_servo_t; diff --git a/Marlin/src/HAL/LPC1768/fast_pwm.cpp b/Marlin/src/HAL/LPC1768/fast_pwm.cpp index ece115aa01aea..6d2b1a9002c10 100644 --- a/Marlin/src/HAL/LPC1768/fast_pwm.cpp +++ b/Marlin/src/HAL/LPC1768/fast_pwm.cpp @@ -21,16 +21,16 @@ */ #ifdef TARGET_LPC1768 -#include "../../inc/MarlinConfigPre.h" +#include "../../inc/MarlinConfig.h" #include -void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { +void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { if (!LPC176x::pin_is_valid(pin)) return; if (LPC176x::pwm_attach_pin(pin)) LPC176x::pwm_write_ratio(pin, invert ? 1.0f - (float)v / v_size : (float)v / v_size); // map 1-254 onto PWM range } -void set_pwm_frequency(const pin_t pin, const uint16_t f_desired) { +void MarlinHAL::set_pwm_frequency(const pin_t pin, const uint16_t f_desired) { LPC176x::pwm_set_frequency(pin, f_desired); } diff --git a/Marlin/src/HAL/LPC1768/main.cpp b/Marlin/src/HAL/LPC1768/main.cpp index ef0dc42c78cad..419c99793fb8a 100644 --- a/Marlin/src/HAL/LPC1768/main.cpp +++ b/Marlin/src/HAL/LPC1768/main.cpp @@ -48,7 +48,7 @@ void SysTick_Callback() { disk_timerproc(); } TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial()); -void HAL_init() { +void MarlinHAL::init() { // Init LEDs #if PIN_EXISTS(LED) @@ -130,7 +130,7 @@ void HAL_init() { const millis_t usb_timeout = millis() + 2000; while (!USB_Configuration && PENDING(millis(), usb_timeout)) { delay(50); - HAL_idletask(); + idletask(); #if PIN_EXISTS(LED) TOGGLE(LED_PIN); // Flash quickly during USB initialization #endif @@ -142,7 +142,7 @@ void HAL_init() { } // HAL idle task -void HAL_idletask() { +void MarlinHAL::idletask() { #if HAS_SHARED_MEDIA // If Marlin is using the SD card we need to lock it to prevent access from // a PC via USB. diff --git a/Marlin/src/HAL/LPC1768/timers.h b/Marlin/src/HAL/LPC1768/timers.h index 78e856db28578..c6d7bc632e2ed 100644 --- a/Marlin/src/HAL/LPC1768/timers.h +++ b/Marlin/src/HAL/LPC1768/timers.h @@ -170,4 +170,4 @@ FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) { } } -#define HAL_timer_isr_epilogue(T) +#define HAL_timer_isr_epilogue(T) NOOP diff --git a/Marlin/src/HAL/NATIVE_SIM/HAL.h b/Marlin/src/HAL/NATIVE_SIM/HAL.h index 436b4b4daa265..ee2e31fc7fa47 100644 --- a/Marlin/src/HAL/NATIVE_SIM/HAL.h +++ b/Marlin/src/HAL/NATIVE_SIM/HAL.h @@ -21,18 +21,10 @@ */ #pragma once -#define CPU_32_BIT -#define HAL_IDLETASK -void HAL_idletask(); - -#define F_CPU 100000000 -#define SystemCoreClock F_CPU #include #include - #undef min #undef max - #include #include "pinmapping.h" @@ -40,8 +32,6 @@ void _printf (const char *format, ...); void _putc(uint8_t c); uint8_t _getc(); -//extern "C" volatile uint32_t _millis; - //arduino: Print.h #define DEC 10 #define HEX 16 @@ -58,7 +48,23 @@ uint8_t _getc(); #include "watchdog.h" #include "serial.h" -#define SHARED_SERVOS HAS_SERVOS +// ------------------------ +// Defines +// ------------------------ + +#define CPU_32_BIT +#define SHARED_SERVOS HAS_SERVOS // Use shared/servos.cpp + +#define F_CPU 100000000 +#define SystemCoreClock F_CPU + +#define CPU_ST7920_DELAY_1 600 +#define CPU_ST7920_DELAY_2 750 +#define CPU_ST7920_DELAY_3 750 + +// ------------------------ +// Serial ports +// ------------------------ extern MSerialT serial_stream_0; extern MSerialT serial_stream_1; @@ -98,49 +104,19 @@ extern MSerialT serial_stream_3; #endif #endif - -#define CPU_ST7920_DELAY_1 600 -#define CPU_ST7920_DELAY_2 750 -#define CPU_ST7920_DELAY_3 750 - -// +// ------------------------ // Interrupts -// +// ------------------------ + #define CRITICAL_SECTION_START() #define CRITICAL_SECTION_END() -#define ISRS_ENABLED() -#define ENABLE_ISRS() -#define DISABLE_ISRS() - -inline void HAL_init() {} - -// Utility functions -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wunused-function" -int freeMemory(); -#pragma GCC diagnostic pop +// ------------------------ // ADC +// ------------------------ + #define HAL_ADC_VREF 5.0 #define HAL_ADC_RESOLUTION 10 -#define HAL_ANALOG_SELECT(ch) HAL_adc_enable_channel(ch) -#define HAL_START_ADC(ch) HAL_adc_start_conversion(ch) -#define HAL_READ_ADC() HAL_adc_get_result() -#define HAL_ADC_READY() true - -void HAL_adc_init(); -void HAL_adc_enable_channel(const uint8_t ch); -void HAL_adc_start_conversion(const uint8_t ch); -uint16_t HAL_adc_get_result(); - -// PWM -inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } - -// Reset source -inline void HAL_clear_reset_source(void) {} -inline uint8_t HAL_get_reset_source(void) { return RST_POWER_ON; } - -void HAL_reboot(); /* ---------------- Delay in cycles */ @@ -159,29 +135,22 @@ constexpr inline std::size_t strlen_constexpr(const char* str) { // https://github.com/gcc-mirror/gcc/blob/5c7634a0e5f202935aa6c11b6ea953b8bf80a00a/libstdc%2B%2B-v3/include/bits/char_traits.h#L329 if (str != nullptr) { std::size_t i = 0; - while (str[i] != '\0') { - ++i; - } - + while (str[i] != '\0') ++i; return i; } - return 0; } constexpr inline int strncmp_constexpr(const char* lhs, const char* rhs, std::size_t count) { // https://github.com/gcc-mirror/gcc/blob/13b9cbfc32fe3ac4c81c4dd9c42d141c8fb95db4/libstdc%2B%2B-v3/include/bits/char_traits.h#L655 - if (lhs == nullptr || rhs == nullptr) { + if (lhs == nullptr || rhs == nullptr) return rhs != nullptr ? -1 : 1; - } - for (std::size_t i = 0; i < count; ++i) { - if (lhs[i] != rhs[i]) { + for (std::size_t i = 0; i < count; ++i) + if (lhs[i] != rhs[i]) return lhs[i] < rhs[i] ? -1 : 1; - } else if (lhs[i] == '\0') { + else if (lhs[i] == '\0') return 0; - } - } return 0; } @@ -193,14 +162,11 @@ constexpr inline const char* strstr_constexpr(const char* str, const char* targe do { char sc = {}; do { - if ((sc = *str++) == '\0') { - return nullptr; - } + if ((sc = *str++) == '\0') return nullptr; } while (sc != c); } while (strncmp_constexpr(str, target, len) != 0); --str; } - return str; } @@ -211,12 +177,87 @@ constexpr inline char* strstr_constexpr(char* str, const char* target) { do { char sc = {}; do { - if ((sc = *str++) == '\0') { - return nullptr; - } + if ((sc = *str++) == '\0') return nullptr; } while (sc != c); } while (strncmp_constexpr(str, target, len) != 0); --str; } return str; } + +// ------------------------ +// Class Utilities +// ------------------------ + +#pragma GCC diagnostic push +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic ignored "-Wunused-function" +#endif + +int freeMemory(); + +#pragma GCC diagnostic pop + +// ------------------------ +// MarlinHAL Class +// ------------------------ + +class MarlinHAL { +public: + + // Earliest possible init, before setup() + MarlinHAL() {} + + static void init() {} // Called early in setup() + static void init_board() {} // Called less early in setup() + static void reboot(); // Restart the firmware from 0x0 + + // Interrupts + static bool isr_state() { return true; } + static void isr_on() {} + static void isr_off() {} + + static void delay_ms(const int ms) { _delay_ms(ms); } + + // Tasks, called from idle() + static void idletask(); + + // Reset + static constexpr uint8_t reset_reason = RST_POWER_ON; + static uint8_t get_reset_source() { return reset_reason; } + static void clear_reset_source() {} + + // Free SRAM + static int freeMemory() { return ::freeMemory(); } + + // + // ADC Methods + // + + static uint8_t active_ch; + + // Called by Temperature::init once at startup + static void adc_init(); + + // Called by Temperature::init for each sensor at startup + static void adc_enable(const uint8_t ch); + + // Begin ADC sampling on the given channel + static void adc_start(const uint8_t ch); + + // Is the ADC ready for reading? + static bool adc_ready(); + + // The current value of the ADC register + static uint16_t adc_value(); + + /** + * Set the PWM duty cycle for the pin to the given value. + * No option to invert the duty cycle [default = false] + * No option to change the scale of the provided value to enable finer PWM duty control [default = 255] + */ + static void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { + analogWrite(pin, v); + } + +}; diff --git a/Marlin/src/HAL/NATIVE_SIM/timers.h b/Marlin/src/HAL/NATIVE_SIM/timers.h index cedfdb62d631f..be38d583b6861 100644 --- a/Marlin/src/HAL/NATIVE_SIM/timers.h +++ b/Marlin/src/HAL/NATIVE_SIM/timers.h @@ -87,5 +87,5 @@ void HAL_timer_enable_interrupt(const uint8_t timer_num); void HAL_timer_disable_interrupt(const uint8_t timer_num); bool HAL_timer_interrupt_enabled(const uint8_t timer_num); -#define HAL_timer_isr_prologue(T) -#define HAL_timer_isr_epilogue(T) +#define HAL_timer_isr_prologue(T) NOOP +#define HAL_timer_isr_epilogue(T) NOOP diff --git a/Marlin/src/HAL/SAMD51/HAL.cpp b/Marlin/src/HAL/SAMD51/HAL.cpp index a5febad83be1d..14b6a437dccc9 100644 --- a/Marlin/src/HAL/SAMD51/HAL.cpp +++ b/Marlin/src/HAL/SAMD51/HAL.cpp @@ -42,10 +42,6 @@ #endif #endif -// ------------------------ -// Local defines -// ------------------------ - #define GET_TEMP_0_ADC() TERN(HAS_TEMP_ADC_0, PIN_TO_ADC(TEMP_0_PIN), -1) #define GET_TEMP_1_ADC() TERN(HAS_TEMP_ADC_1, PIN_TO_ADC(TEMP_1_PIN), -1) #define GET_TEMP_2_ADC() TERN(HAS_TEMP_ADC_2, PIN_TO_ADC(TEMP_2_PIN), -1) @@ -61,17 +57,21 @@ #define GET_BOARD_ADC() TERN(HAS_TEMP_ADC_BOARD, PIN_TO_ADC(TEMP_BOARD_PIN), -1) #define GET_FILAMENT_WIDTH_ADC() TERN(FILAMENT_WIDTH_SENSOR, PIN_TO_ADC(FILWIDTH_PIN), -1) #define GET_BUTTONS_ADC() TERN(HAS_ADC_BUTTONS, PIN_TO_ADC(ADC_KEYPAD_PIN), -1) +#define GET_JOY_ADC_X() TERN(HAS_JOY_ADC_X, PIN_TO_ADC(JOY_X_PIN), -1) +#define GET_JOY_ADC_Y() TERN(HAS_JOY_ADC_Y, PIN_TO_ADC(JOY_Y_PIN), -1) +#define GET_JOY_ADC_Z() TERN(HAS_JOY_ADC_Z, PIN_TO_ADC(JOY_Z_PIN), -1) #define IS_ADC_REQUIRED(n) ( \ GET_TEMP_0_ADC() == n || GET_TEMP_1_ADC() == n || GET_TEMP_2_ADC() == n || GET_TEMP_3_ADC() == n \ || GET_TEMP_4_ADC() == n || GET_TEMP_5_ADC() == n || GET_TEMP_6_ADC() == n || GET_TEMP_7_ADC() == n \ - || GET_BED_ADC() == n \ - || GET_CHAMBER_ADC() == n \ - || GET_PROBE_ADC() == n \ - || GET_COOLER_ADC() == n \ - || GET_BOARD_ADC() == n \ + || GET_BED_ADC() == n \ + || GET_CHAMBER_ADC() == n \ + || GET_PROBE_ADC() == n \ + || GET_COOLER_ADC() == n \ + || GET_BOARD_ADC() == n \ || GET_FILAMENT_WIDTH_ADC() == n \ - || GET_BUTTONS_ADC() == n \ + || GET_BUTTONS_ADC() == n \ + || GET_JOY_ADC_X() == n || GET_JOY_ADC_Y() == n || GET_JOY_ADC_Z() == n \ ) #if IS_ADC_REQUIRED(0) @@ -91,6 +91,118 @@ #define DMA_IS_REQUIRED 1 #endif +enum ADCIndex { + #if GET_TEMP_0_ADC() == 0 + TEMP_0, + #endif + #if GET_TEMP_1_ADC() == 0 + TEMP_1, + #endif + #if GET_TEMP_2_ADC() == 0 + TEMP_2, + #endif + #if GET_TEMP_3_ADC() == 0 + TEMP_3, + #endif + #if GET_TEMP_4_ADC() == 0 + TEMP_4, + #endif + #if GET_TEMP_5_ADC() == 0 + TEMP_5, + #endif + #if GET_TEMP_6_ADC() == 0 + TEMP_6, + #endif + #if GET_TEMP_7_ADC() == 0 + TEMP_7, + #endif + #if GET_BED_ADC() == 0 + TEMP_BED, + #endif + #if GET_CHAMBER_ADC() == 0 + TEMP_CHAMBER, + #endif + #if GET_PROBE_ADC() == 0 + TEMP_PROBE, + #endif + #if GET_COOLER_ADC() == 0 + TEMP_COOLER, + #endif + #if GET_BOARD_ADC() == 0 + TEMP_BOARD, + #endif + #if GET_FILAMENT_WIDTH_ADC() == 0 + FILWIDTH, + #endif + #if GET_BUTTONS_ADC() == 0 + ADC_KEY, + #endif + #if GET_JOY_ADC_X() == 0 + JOY_X, + #endif + #if GET_JOY_ADC_Y() == 0 + JOY_Y, + #endif + #if GET_JOY_ADC_Z() == 0 + JOY_Z, + #endif + #if GET_TEMP_0_ADC() == 1 + TEMP_0, + #endif + #if GET_TEMP_1_ADC() == 1 + TEMP_1, + #endif + #if GET_TEMP_2_ADC() == 1 + TEMP_2, + #endif + #if GET_TEMP_3_ADC() == 1 + TEMP_3, + #endif + #if GET_TEMP_4_ADC() == 1 + TEMP_4, + #endif + #if GET_TEMP_5_ADC() == 1 + TEMP_5, + #endif + #if GET_TEMP_6_ADC() == 1 + TEMP_6, + #endif + #if GET_TEMP_7_ADC() == 1 + TEMP_7, + #endif + #if GET_BED_ADC() == 1 + TEMP_BED, + #endif + #if GET_CHAMBER_ADC() == 1 + TEMP_CHAMBER, + #endif + #if GET_PROBE_ADC() == 1 + TEMP_PROBE, + #endif + #if GET_COOLER_ADC() == 1 + TEMP_COOLER, + #endif + #if GET_BOARD_ADC() == 1 + TEMP_BOARD, + #endif + #if GET_FILAMENT_WIDTH_ADC() == 1 + FILWIDTH, + #endif + #if GET_BUTTONS_ADC() == 1 + ADC_KEY, + #endif + #if GET_JOY_ADC_X() == 1 + JOY_X, + #endif + #if GET_JOY_ADC_Y() == 1 + JOY_Y, + #endif + #if GET_JOY_ADC_Z() == 1 + JOY_Z, + #endif + ADC_COUNT +}; + // ------------------------ // Types // ------------------------ @@ -108,12 +220,10 @@ // Private Variables // ------------------------ -uint16_t HAL_adc_result; - #if ADC_IS_REQUIRED // Pins used by ADC inputs. Order must be ADC0 inputs first then ADC1 - const uint8_t adc_pins[] = { + static constexpr uint8_t adc_pins[ADC_COUNT] = { // ADC0 pins #if GET_TEMP_0_ADC() == 0 TEMP_0_PIN, @@ -160,6 +270,15 @@ uint16_t HAL_adc_result; #if GET_BUTTONS_ADC() == 0 ADC_KEYPAD_PIN, #endif + #if GET_JOY_ADC_X() == 0 + JOY_X_PIN, + #endif + #if GET_JOY_ADC_Y() == 0 + JOY_Y_PIN, + #endif + #if GET_JOY_ADC_Z() == 0 + JOY_Z_PIN, + #endif // ADC1 pins #if GET_TEMP_0_ADC() == 1 TEMP_0_PIN, @@ -206,15 +325,23 @@ uint16_t HAL_adc_result; #if GET_BUTTONS_ADC() == 1 ADC_KEYPAD_PIN, #endif + #if GET_JOY_ADC_X() == 1 + JOY_X_PIN, + #endif + #if GET_JOY_ADC_Y() == 1 + JOY_Y_PIN, + #endif + #if GET_JOY_ADC_Z() == 1 + JOY_Z_PIN, + #endif }; - uint16_t HAL_adc_results[COUNT(adc_pins)]; + static uint16_t adc_results[ADC_COUNT]; #if ADC0_IS_REQUIRED - Adafruit_ZeroDMA adc0DMAProgram, - adc0DMARead; + Adafruit_ZeroDMA adc0DMAProgram, adc0DMARead; - const HAL_DMA_DAC_Registers adc0_dma_regs_list[] = { + static constexpr HAL_DMA_DAC_Registers adc0_dma_regs_list[ADC_COUNT] = { #if GET_TEMP_0_ADC() == 0 { PIN_TO_INPUTCTRL(TEMP_0_PIN) }, #endif @@ -260,16 +387,24 @@ uint16_t HAL_adc_result; #if GET_BUTTONS_ADC() == 0 { PIN_TO_INPUTCTRL(ADC_KEYPAD_PIN) }, #endif + #if GET_JOY_ADC_X() == 0 + { PIN_TO_INPUTCTRL(JOY_X_PIN) }, + #endif + #if GET_JOY_ADC_Y() == 0 + { PIN_TO_INPUTCTRL(JOY_Y_PIN) }, + #endif + #if GET_JOY_ADC_Z() == 0 + { PIN_TO_INPUTCTRL(JOY_Z_PIN) }, + #endif }; #define ADC0_AINCOUNT COUNT(adc0_dma_regs_list) #endif // ADC0_IS_REQUIRED #if ADC1_IS_REQUIRED - Adafruit_ZeroDMA adc1DMAProgram, - adc1DMARead; + Adafruit_ZeroDMA adc1DMAProgram, adc1DMARead; - const HAL_DMA_DAC_Registers adc1_dma_regs_list[] = { + static constexpr HAL_DMA_DAC_Registers adc1_dma_regs_list[ADC_COUNT] = { #if GET_TEMP_0_ADC() == 1 { PIN_TO_INPUTCTRL(TEMP_0_PIN) }, #endif @@ -315,6 +450,15 @@ uint16_t HAL_adc_result; #if GET_BUTTONS_ADC() == 1 { PIN_TO_INPUTCTRL(ADC_KEYPAD_PIN) }, #endif + #if GET_JOY_ADC_X() == 1 + { PIN_TO_INPUTCTRL(JOY_X_PIN) }, + #endif + #if GET_JOY_ADC_Y() == 1 + { PIN_TO_INPUTCTRL(JOY_Y_PIN) }, + #endif + #if GET_JOY_ADC_Z() == 1 + { PIN_TO_INPUTCTRL(JOY_Z_PIN) }, + #endif }; #define ADC1_AINCOUNT COUNT(adc1_dma_regs_list) @@ -326,9 +470,10 @@ uint16_t HAL_adc_result; // Private functions // ------------------------ -#if DMA_IS_REQUIRED +void MarlinHAL::dma_init() { + + #if DMA_IS_REQUIRED - void dma_init() { DmacDescriptor *descriptor; #if ADC0_IS_REQUIRED @@ -357,7 +502,7 @@ uint16_t HAL_adc_result; if (adc0DMARead.allocate() == DMA_STATUS_OK) { adc0DMARead.addDescriptor( (void *)&ADC0->RESULT.reg, // SRC - &HAL_adc_results, // DEST + &adc_results, // DEST ADC0_AINCOUNT, // CNT DMA_BEAT_SIZE_HWORD, false, // SRCINC @@ -394,7 +539,7 @@ uint16_t HAL_adc_result; if (adc1DMARead.allocate() == DMA_STATUS_OK) { adc1DMARead.addDescriptor( (void *)&ADC1->RESULT.reg, // SRC - &HAL_adc_results[ADC0_AINCOUNT], // DEST + &adc_results[ADC0_AINCOUNT], // DEST ADC1_AINCOUNT, // CNT DMA_BEAT_SIZE_HWORD, false, // SRCINC @@ -407,16 +552,16 @@ uint16_t HAL_adc_result; #endif DMAC->PRICTRL0.bit.RRLVLEN0 = true; // Activate round robin for DMA channels required by ADCs - } -#endif // DMA_IS_REQUIRED + #endif // DMA_IS_REQUIRED +} // ------------------------ // Public functions // ------------------------ // HAL initialization task -void HAL_init() { +void MarlinHAL::init() { TERN_(DMA_IS_REQUIRED, dma_init()); #if ENABLED(SDSUPPORT) #if SD_CONNECTION_IS(ONBOARD) && PIN_EXISTS(SD_DETECT) @@ -426,17 +571,9 @@ void HAL_init() { #endif } -// HAL idle task -/* -void HAL_idletask() { -} -*/ - -void HAL_clear_reset_source() { } - #pragma push_macro("WDT") #undef WDT // Required to be able to use '.bit.WDT'. Compiler wrongly replace struct field with WDT define -uint8_t HAL_get_reset_source() { +uint8_t MarlinHAL::get_reset_source() { RSTC_RCAUSE_Type resetCause; resetCause.reg = REG_RSTC_RCAUSE; @@ -450,7 +587,7 @@ uint8_t HAL_get_reset_source() { } #pragma pop_macro("WDT") -void HAL_reboot() { NVIC_SystemReset(); } +void MarlinHAL::reboot() { NVIC_SystemReset(); } extern "C" { void * _sbrk(int incr); @@ -468,9 +605,11 @@ int freeMemory() { // ADC // ------------------------ -void HAL_adc_init() { +uint16_t MarlinHAL::adc_result; + +void MarlinHAL::adc_init() { #if ADC_IS_REQUIRED - memset(HAL_adc_results, 0xFF, sizeof(HAL_adc_results)); // Fill result with invalid values + memset(adc_results, 0xFF, sizeof(adc_results)); // Fill result with invalid values LOOP_L_N(pi, COUNT(adc_pins)) pinPeripheral(adc_pins[pi], PIO_ANALOG); @@ -505,17 +644,13 @@ void HAL_adc_init() { #endif // ADC_IS_REQUIRED } -void HAL_adc_start_conversion(const uint8_t adc_pin) { +void MarlinHAL::adc_start(const pin_t pin) { #if ADC_IS_REQUIRED - LOOP_L_N(pi, COUNT(adc_pins)) { - if (adc_pin == adc_pins[pi]) { - HAL_adc_result = HAL_adc_results[pi]; - return; - } - } + LOOP_L_N(pi, COUNT(adc_pins)) + if (pin == adc_pins[pi]) { adc_result = adc_results[pi]; return; } #endif - HAL_adc_result = 0xFFFF; + adc_result = 0xFFFF; } #endif // __SAMD51__ diff --git a/Marlin/src/HAL/SAMD51/HAL.h b/Marlin/src/HAL/SAMD51/HAL.h index c262752a8d66a..3b09a885a53bb 100644 --- a/Marlin/src/HAL/SAMD51/HAL.h +++ b/Marlin/src/HAL/SAMD51/HAL.h @@ -89,51 +89,30 @@ typedef int8_t pin_t; -#define SHARED_SERVOS HAS_SERVOS -#define HAL_SERVO_LIB Servo +#define SHARED_SERVOS HAS_SERVOS // Use shared/servos.cpp + +class Servo; +typedef Servo hal_servo_t; // // Interrupts // -#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() - -#define cli() __disable_irq() // Disable interrupts -#define sei() __enable_irq() // Enable interrupts - -void HAL_clear_reset_source(); // clear reset reason -uint8_t HAL_get_reset_source(); // get reset reason +#define CRITICAL_SECTION_START() const bool irqon = !__get_PRIMASK(); __disable_irq() +#define CRITICAL_SECTION_END() if (irqon) __enable_irq() -void HAL_reboot(); +#define cli() __disable_irq() // Disable interrupts +#define sei() __enable_irq() // Enable interrupts // // ADC // -extern uint16_t HAL_adc_result; // Most recent ADC conversion - -#define HAL_ANALOG_SELECT(pin) - -void HAL_adc_init(); //#define HAL_ADC_FILTERED // Disable Marlin's oversampling. The HAL filters ADC values. #define HAL_ADC_VREF 3.3 #define HAL_ADC_RESOLUTION 10 // ... 12 -#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) -#define HAL_READ_ADC() HAL_adc_result -#define HAL_ADC_READY() true -void HAL_adc_start_conversion(const uint8_t adc_pin); - -// -// PWM // -inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } - -// -// Pin Map +// Pin Mapping for M42, M43, M226 // #define GET_PIN_MAP_PIN(index) index #define GET_PIN_MAP_INDEX(pin) pin @@ -142,35 +121,93 @@ inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, // // Tone // -void toneInit(); void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration=0); void noTone(const pin_t _pin); -// Enable hooks into idle and setup for HAL -void HAL_init(); -/* -#define HAL_IDLETASK 1 -void HAL_idletask(); -*/ - -// -// Utility functions -// -FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); } +// ------------------------ +// Class Utilities +// ------------------------ #pragma GCC diagnostic push #if GCC_VERSION <= 50000 #pragma GCC diagnostic ignored "-Wunused-function" #endif -int freeMemory(); - -#pragma GCC diagnostic pop - #ifdef __cplusplus extern "C" { #endif + char *dtostrf(double __val, signed char __width, unsigned char __prec, char *__s); + +extern "C" int freeMemory(); + #ifdef __cplusplus } #endif + +#pragma GCC diagnostic pop + +// ------------------------ +// MarlinHAL Class +// ------------------------ + +class MarlinHAL { +public: + + // Earliest possible init, before setup() + MarlinHAL() {} + + static void init(); // Called early in setup() + static void init_board() {} // Called less early in setup() + static void reboot(); // Restart the firmware from 0x0 + + // Interrupts + static bool isr_state() { return !__get_PRIMASK(); } + static void isr_on() { sei(); } + static void isr_off() { cli(); } + + static void delay_ms(const int ms) { delay(ms); } + + // Tasks, called from idle() + static void idletask() {} + + // Reset + static uint8_t get_reset_source(); + static void clear_reset_source() {} + + // Free SRAM + static int freeMemory() { return ::freeMemory(); } + + // + // ADC Methods + // + + static uint16_t adc_result; + + // Called by Temperature::init once at startup + static void adc_init(); + + // Called by Temperature::init for each sensor at startup + static void adc_enable(const uint8_t ch) {} + + // Begin ADC sampling on the given channel + static void adc_start(const pin_t pin); + + // Is the ADC ready for reading? + static bool adc_ready() { return true; } + + // The current value of the ADC register + static uint16_t adc_value() { return adc_result; } + + /** + * Set the PWM duty cycle for the pin to the given value. + * No option to invert the duty cycle [default = false] + * No option to change the scale of the provided value to enable finer PWM duty control [default = 255] + */ + static void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { + analogWrite(pin, v); + } + +private: + static void dma_init(); +}; diff --git a/Marlin/src/HAL/STM32/HAL.cpp b/Marlin/src/HAL/STM32/HAL.cpp index 0920a72ec1bcd..d28f506db9d3b 100644 --- a/Marlin/src/HAL/STM32/HAL.cpp +++ b/Marlin/src/HAL/STM32/HAL.cpp @@ -53,16 +53,18 @@ // Public Variables // ------------------------ -uint16_t HAL_adc_result; +uint16_t MarlinHAL::adc_result; // ------------------------ // Public functions // ------------------------ -TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial()); +#if ENABLED(POSTMORTEM_DEBUGGING) + extern void install_min_serial(); +#endif // HAL initialization task -void HAL_init() { +void MarlinHAL::init() { // Ensure F_CPU is a constant expression. // If the compiler breaks here, it means that delay code that should compute at compile time will not work. // So better safe than sorry here. @@ -87,7 +89,7 @@ void HAL_init() { SetTimerInterruptPriorities(); - #if ENABLED(EMERGENCY_PARSER) && USBD_USE_CDC + #if ENABLED(EMERGENCY_PARSER) && (USBD_USE_CDC || USBD_USE_CDC_MSC) USB_Hook_init(); #endif @@ -103,7 +105,7 @@ void HAL_init() { } // HAL idle task -void HAL_idletask() { +void MarlinHAL::idletask() { #if HAS_SHARED_MEDIA // Stm32duino currently doesn't have a "loop/idle" method CDC_resume_receive(); @@ -111,9 +113,9 @@ void HAL_idletask() { #endif } -void HAL_clear_reset_source() { __HAL_RCC_CLEAR_RESET_FLAGS(); } +void MarlinHAL::reboot() { NVIC_SystemReset(); } -uint8_t HAL_get_reset_source() { +uint8_t MarlinHAL::get_reset_source() { return #ifdef RCC_FLAG_IWDGRST // Some sources may not exist... RESET != __HAL_RCC_GET_FLAG(RCC_FLAG_IWDGRST) ? RST_WATCHDOG : @@ -137,24 +139,14 @@ uint8_t HAL_get_reset_source() { ; } -void HAL_reboot() { NVIC_SystemReset(); } - -void _delay_ms(const int delay_ms) { delay(delay_ms); } +void MarlinHAL::clear_reset_source() { __HAL_RCC_CLEAR_RESET_FLAGS(); } extern "C" { extern unsigned int _ebss; // end of bss section } -// ------------------------ -// ADC -// ------------------------ - -// TODO: Make sure this doesn't cause any delay -void HAL_adc_start_conversion(const uint8_t adc_pin) { HAL_adc_result = analogRead(adc_pin); } -uint16_t HAL_adc_get_result() { return HAL_adc_result; } - // Reset the system to initiate a firmware flash -WEAK void flashFirmware(const int16_t) { HAL_reboot(); } +WEAK void flashFirmware(const int16_t) { hal.reboot(); } // Maple Compatibility volatile uint32_t systick_uptime_millis = 0; diff --git a/Marlin/src/HAL/STM32/HAL.h b/Marlin/src/HAL/STM32/HAL.h index 9429bb7e7ca70..f5e8c1187da7e 100644 --- a/Marlin/src/HAL/STM32/HAL.h +++ b/Marlin/src/HAL/STM32/HAL.h @@ -44,9 +44,9 @@ #define CPU_ST7920_DELAY_2 40 #define CPU_ST7920_DELAY_3 340 -// -// Serial Ports -// +// ------------------------ +// Serial ports +// ------------------------ #ifdef USBCON #include #include "../../core/serial_hook.h" @@ -115,17 +115,14 @@ #define analogInputToDigitalPin(p) (p) #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() +// +// Interrupts +// +#define CRITICAL_SECTION_START() const bool irqon = !__get_PRIMASK(); __disable_irq() +#define CRITICAL_SECTION_END() if (irqon) __enable_irq() #define cli() __disable_irq() #define sei() __enable_irq() -// On AVR this is in math.h? -#define square(x) ((x)*(x)) - // ------------------------ // Types // ------------------------ @@ -136,43 +133,61 @@ typedef int16_t pin_t; #endif -#define HAL_SERVO_LIB libServo +class libServo; +typedef libServo hal_servo_t; #define PAUSE_SERVO_OUTPUT() libServo::pause_all_servos() #define RESUME_SERVO_OUTPUT() libServo::resume_all_servos() // ------------------------ -// Public Variables +// ADC // ------------------------ -// result of last ADC conversion -extern uint16_t HAL_adc_result; +#ifdef ADC_RESOLUTION + #define HAL_ADC_RESOLUTION ADC_RESOLUTION +#else + #define HAL_ADC_RESOLUTION 12 +#endif -// ------------------------ -// Public functions -// ------------------------ +#define HAL_ADC_VREF 3.3 -// Memory related -#define __bss_end __bss_end__ +// +// Pin Mapping for M42, M43, M226 +// +#define GET_PIN_MAP_PIN(index) index +#define GET_PIN_MAP_INDEX(pin) pin +#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) -// Enable hooks into setup for HAL -void HAL_init(); -#define HAL_IDLETASK 1 -void HAL_idletask(); +#ifdef STM32F1xx + #define JTAG_DISABLE() AFIO_DBGAFR_CONFIG(AFIO_MAPR_SWJ_CFG_JTAGDISABLE) + #define JTAGSWD_DISABLE() AFIO_DBGAFR_CONFIG(AFIO_MAPR_SWJ_CFG_DISABLE) + #define JTAGSWD_RESET() AFIO_DBGAFR_CONFIG(AFIO_MAPR_SWJ_CFG_RESET); // Reset: FULL SWD+JTAG +#endif -// Clear reset reason -void HAL_clear_reset_source(); +#define PLATFORM_M997_SUPPORT +void flashFirmware(const int16_t); -// Reset reason -uint8_t HAL_get_reset_source(); +// Maple Compatibility +typedef void (*systickCallback_t)(void); +void systick_attach_callback(systickCallback_t cb); +void HAL_SYSTICK_Callback(); -void HAL_reboot(); +extern volatile uint32_t systick_uptime_millis; + +#define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment + +// ------------------------ +// Class Utilities +// ------------------------ -void _delay_ms(const int delay); +// Memory related +#define __bss_end __bss_end__ extern "C" char* _sbrk(int incr); #pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wunused-function" +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic ignored "-Wunused-function" +#endif static inline int freeMemory() { volatile char top; @@ -181,62 +196,71 @@ static inline int freeMemory() { #pragma GCC diagnostic pop -// -// ADC -// +// ------------------------ +// MarlinHAL Class +// ------------------------ -#define HAL_ANALOG_SELECT(pin) pinMode(pin, INPUT) +class MarlinHAL { +public: -#ifdef ADC_RESOLUTION - #define HAL_ADC_RESOLUTION ADC_RESOLUTION -#else - #define HAL_ADC_RESOLUTION 12 -#endif + // Earliest possible init, before setup() + MarlinHAL() {} -#define HAL_ADC_VREF 3.3 -#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) -#define HAL_READ_ADC() HAL_adc_result -#define HAL_ADC_READY() true + static void init(); // Called early in setup() + static void init_board() {} // Called less early in setup() + static void reboot(); // Restart the firmware from 0x0 -inline void HAL_adc_init() { analogReadResolution(HAL_ADC_RESOLUTION); } + // Interrupts + static bool isr_state() { return !__get_PRIMASK(); } + static void isr_on() { sei(); } + static void isr_off() { cli(); } -void HAL_adc_start_conversion(const uint8_t adc_pin); + static void delay_ms(const int ms) { delay(ms); } -uint16_t HAL_adc_get_result(); + // Tasks, called from idle() + static void idletask(); -#define GET_PIN_MAP_PIN(index) index -#define GET_PIN_MAP_INDEX(pin) pin -#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) + // Reset + static uint8_t get_reset_source(); + static void clear_reset_source(); -#ifdef STM32F1xx - #define JTAG_DISABLE() AFIO_DBGAFR_CONFIG(AFIO_MAPR_SWJ_CFG_JTAGDISABLE) - #define JTAGSWD_DISABLE() AFIO_DBGAFR_CONFIG(AFIO_MAPR_SWJ_CFG_DISABLE) - #define JTAGSWD_RESET() AFIO_DBGAFR_CONFIG(AFIO_MAPR_SWJ_CFG_RESET); // Reset: FULL SWD+JTAG -#endif + // Free SRAM + static int freeMemory() { return ::freeMemory(); } -#define PLATFORM_M997_SUPPORT -void flashFirmware(const int16_t); + // + // ADC Methods + // -// Maple Compatibility -typedef void (*systickCallback_t)(void); -void systick_attach_callback(systickCallback_t cb); -void HAL_SYSTICK_Callback(); + static uint16_t adc_result; -extern volatile uint32_t systick_uptime_millis; + // Called by Temperature::init once at startup + static void adc_init() { + analogReadResolution(HAL_ADC_RESOLUTION); + } -#define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment + // Called by Temperature::init for each sensor at startup + static void adc_enable(const pin_t pin) { pinMode(pin, INPUT); } -/** - * set_pwm_frequency - * Set the frequency of the timer corresponding to the provided pin - * All Timer PWM pins run at the same frequency - */ -void set_pwm_frequency(const pin_t pin, const uint16_t f_desired); + // Begin ADC sampling on the given channel + static void adc_start(const pin_t pin) { adc_result = analogRead(pin); } -/** - * set_pwm_duty - * Set the PWM duty cycle of the provided pin to the provided value - * Optionally allows inverting the duty cycle [default = false] - * Optionally allows changing the maximum size of the provided value to enable finer PWM duty control [default = 255] - */ -void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false); + // Is the ADC ready for reading? + static bool adc_ready() { return true; } + + // The current value of the ADC register + static uint16_t adc_value() { return adc_result; } + + /** + * Set the PWM duty cycle for the pin to the given value. + * Optionally invert the duty cycle [default = false] + * Optionally change the maximum size of the provided value to enable finer PWM duty control [default = 255] + */ + static void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false); + + /** + * Set the frequency of the timer for the given pin. + * All Timer PWM pins run at the same frequency. + */ + static void set_pwm_frequency(const pin_t pin, const uint16_t f_desired); + +}; diff --git a/Marlin/src/HAL/STM32/HAL_SPI.cpp b/Marlin/src/HAL/STM32/HAL_SPI.cpp index 8ee4761647856..40d320d5e8220 100644 --- a/Marlin/src/HAL/STM32/HAL_SPI.cpp +++ b/Marlin/src/HAL/STM32/HAL_SPI.cpp @@ -102,9 +102,9 @@ static SPISettings spiConfig; // Soft SPI receive byte uint8_t spiRec() { - DISABLE_ISRS(); // No interrupts during byte receive + hal.isr_off(); // No interrupts during byte receive const uint8_t data = HAL_SPI_STM32_SpiTransfer_Mode_3(0xFF); - ENABLE_ISRS(); // Enable interrupts + hal.isr_on(); // Enable interrupts return data; } @@ -116,9 +116,9 @@ static SPISettings spiConfig; // Soft SPI send byte void spiSend(uint8_t data) { - DISABLE_ISRS(); // No interrupts during byte send + hal.isr_off(); // No interrupts during byte send HAL_SPI_STM32_SpiTransfer_Mode_3(data); // Don't care what is received - ENABLE_ISRS(); // Enable interrupts + hal.isr_on(); // Enable interrupts } // Soft SPI send block diff --git a/Marlin/src/HAL/STM32/eeprom_flash.cpp b/Marlin/src/HAL/STM32/eeprom_flash.cpp index 252b057362c99..7c8cc8dd21e18 100644 --- a/Marlin/src/HAL/STM32/eeprom_flash.cpp +++ b/Marlin/src/HAL/STM32/eeprom_flash.cpp @@ -174,9 +174,9 @@ bool PersistentStore::access_finish() { UNLOCK_FLASH(); TERN_(HAS_PAUSE_SERVO_OUTPUT, PAUSE_SERVO_OUTPUT()); - DISABLE_ISRS(); + hal.isr_off(); status = HAL_FLASHEx_Erase(&EraseInitStruct, &SectorError); - ENABLE_ISRS(); + hal.isr_on(); TERN_(HAS_PAUSE_SERVO_OUTPUT, RESUME_SERVO_OUTPUT()); if (status != HAL_OK) { DEBUG_ECHOLNPGM("HAL_FLASHEx_Erase=", status); @@ -229,9 +229,9 @@ bool PersistentStore::access_finish() { // output. Servo output still glitches with interrupts disabled, but recovers after the // erase. TERN_(HAS_PAUSE_SERVO_OUTPUT, PAUSE_SERVO_OUTPUT()); - DISABLE_ISRS(); + hal.isr_off(); eeprom_buffer_flush(); - ENABLE_ISRS(); + hal.isr_on(); TERN_(HAS_PAUSE_SERVO_OUTPUT, RESUME_SERVO_OUTPUT()); eeprom_data_written = false; diff --git a/Marlin/src/HAL/STM32/fast_pwm.cpp b/Marlin/src/HAL/STM32/fast_pwm.cpp index 590c9dbe3da66..a0d8ecc612c2d 100644 --- a/Marlin/src/HAL/STM32/fast_pwm.cpp +++ b/Marlin/src/HAL/STM32/fast_pwm.cpp @@ -29,7 +29,7 @@ // Array to support sticky frequency sets per timer static uint16_t timer_freq[TIMER_NUM]; -void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { +void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { const uint16_t duty = invert ? v_size - v : v; if (PWM_PIN(pin)) { const PinName pin_name = digitalPinToPinName(pin); @@ -61,7 +61,7 @@ void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255 } } -void set_pwm_frequency(const pin_t pin, const uint16_t f_desired) { +void MarlinHAL::set_pwm_frequency(const pin_t pin, const uint16_t f_desired) { if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer const PinName pin_name = digitalPinToPinName(pin); TIM_TypeDef * const Instance = (TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM); // Get HAL timer instance diff --git a/Marlin/src/HAL/STM32/pinsDebug.h b/Marlin/src/HAL/STM32/pinsDebug.h index 73d850fc43132..a7f022a0b62dd 100644 --- a/Marlin/src/HAL/STM32/pinsDebug.h +++ b/Marlin/src/HAL/STM32/pinsDebug.h @@ -115,7 +115,6 @@ const XrefInfo pin_xref[] PROGMEM = { #define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0) #define PRINT_PORT(ANUM) port_print(ANUM) #define DIGITAL_PIN_TO_ANALOG_PIN(ANUM) -1 // will report analog pin number in the print port routine -#define GET_PIN_MAP_PIN_M43(Index) pin_xref[Index].Ard_num // x is a variable used to search pin_array #define GET_ARRAY_IS_DIGITAL(x) ((bool) pin_array[x].is_digital) @@ -123,6 +122,11 @@ const XrefInfo pin_xref[] PROGMEM = { #define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) #define MULTI_NAME_PAD 33 // space needed to be pretty if not first name assigned to a pin +// +// Pin Mapping for M43 +// +#define GET_PIN_MAP_PIN_M43(Index) pin_xref[Index].Ard_num + #ifndef M43_NEVER_TOUCH #define _M43_NEVER_TOUCH(Index) (Index >= 9 && Index <= 12) // SERIAL/USB pins: PA9(TX) PA10(RX) PA11(USB_DM) PA12(USB_DP) #ifdef KILL_PIN diff --git a/Marlin/src/HAL/STM32/timers.h b/Marlin/src/HAL/STM32/timers.h index aad543229e164..6828998198af1 100644 --- a/Marlin/src/HAL/STM32/timers.h +++ b/Marlin/src/HAL/STM32/timers.h @@ -116,5 +116,5 @@ FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const ha } } -#define HAL_timer_isr_prologue(T) -#define HAL_timer_isr_epilogue(T) +#define HAL_timer_isr_prologue(T) NOOP +#define HAL_timer_isr_epilogue(T) NOOP diff --git a/Marlin/src/HAL/STM32/usb_serial.cpp b/Marlin/src/HAL/STM32/usb_serial.cpp index b607275db5bb3..0b2372f3a79d3 100644 --- a/Marlin/src/HAL/STM32/usb_serial.cpp +++ b/Marlin/src/HAL/STM32/usb_serial.cpp @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfigPre.h" -#if ENABLED(EMERGENCY_PARSER) && USBD_USE_CDC +#if ENABLED(EMERGENCY_PARSER) && (USBD_USE_CDC || USBD_USE_CDC_MSC) #include "usb_serial.h" #include "../../feature/e_parser.h" diff --git a/Marlin/src/HAL/STM32F1/HAL.cpp b/Marlin/src/HAL/STM32F1/HAL.cpp index a0486da5b0b8b..636dc742fcf59 100644 --- a/Marlin/src/HAL/STM32F1/HAL.cpp +++ b/Marlin/src/HAL/STM32F1/HAL.cpp @@ -79,7 +79,7 @@ #define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */ // ------------------------ -// Public Variables +// Serial ports // ------------------------ #if defined(SERIAL_USB) && !HAS_SD_HOST_DRIVE @@ -112,74 +112,37 @@ #endif #endif -uint16_t HAL_adc_result; - // ------------------------ -// Private Variables +// ADC // ------------------------ -STM32ADC adc(ADC1); - -const uint8_t adc_pins[] = { - OPTITEM(HAS_TEMP_ADC_0, TEMP_0_PIN) - OPTITEM(HAS_TEMP_ADC_1, TEMP_1_PIN) - OPTITEM(HAS_TEMP_ADC_2, TEMP_2_PIN) - OPTITEM(HAS_TEMP_ADC_3, TEMP_3_PIN) - OPTITEM(HAS_TEMP_ADC_4, TEMP_4_PIN) - OPTITEM(HAS_TEMP_ADC_5, TEMP_5_PIN) - OPTITEM(HAS_TEMP_ADC_6, TEMP_6_PIN) - OPTITEM(HAS_TEMP_ADC_7, TEMP_7_PIN) - OPTITEM(HAS_HEATED_BED, TEMP_BED_PIN) - OPTITEM(HAS_TEMP_CHAMBER, TEMP_CHAMBER_PIN) - OPTITEM(HAS_TEMP_ADC_PROBE, TEMP_PROBE_PIN) - OPTITEM(HAS_TEMP_COOLER, TEMP_COOLER_PIN) - OPTITEM(HAS_TEMP_BOARD, TEMP_BOARD_PIN) - OPTITEM(FILAMENT_WIDTH_SENSOR, FILWIDTH_PIN) - OPTITEM(HAS_ADC_BUTTONS, ADC_KEYPAD_PIN) - OPTITEM(HAS_JOY_ADC_X, JOY_X_PIN) - OPTITEM(HAS_JOY_ADC_Y, JOY_Y_PIN) - OPTITEM(HAS_JOY_ADC_Z, JOY_Z_PIN) - OPTITEM(POWER_MONITOR_CURRENT, POWER_MONITOR_CURRENT_PIN) - OPTITEM(POWER_MONITOR_VOLTAGE, POWER_MONITOR_VOLTAGE_PIN) -}; -enum TempPinIndex : char { - OPTITEM(HAS_TEMP_ADC_0, TEMP_0) - OPTITEM(HAS_TEMP_ADC_1, TEMP_1) - OPTITEM(HAS_TEMP_ADC_2, TEMP_2) - OPTITEM(HAS_TEMP_ADC_3, TEMP_3) - OPTITEM(HAS_TEMP_ADC_4, TEMP_4) - OPTITEM(HAS_TEMP_ADC_5, TEMP_5) - OPTITEM(HAS_TEMP_ADC_6, TEMP_6) - OPTITEM(HAS_TEMP_ADC_7, TEMP_7) - OPTITEM(HAS_HEATED_BED, TEMP_BED) - OPTITEM(HAS_TEMP_CHAMBER, TEMP_CHAMBER) - OPTITEM(HAS_TEMP_ADC_PROBE, TEMP_PROBE) - OPTITEM(HAS_TEMP_COOLER, TEMP_COOLER) - OPTITEM(HAS_TEMP_BOARD, TEMP_BOARD) - OPTITEM(FILAMENT_WIDTH_SENSOR, FILWIDTH) - OPTITEM(HAS_ADC_BUTTONS, ADC_KEY) - OPTITEM(HAS_JOY_ADC_X, JOY_X) - OPTITEM(HAS_JOY_ADC_Y, JOY_Y) - OPTITEM(HAS_JOY_ADC_Z, JOY_Z) - OPTITEM(POWER_MONITOR_CURRENT, POWERMON_CURRENT) - OPTITEM(POWER_MONITOR_VOLTAGE, POWERMON_VOLTS) - ADC_PIN_COUNT -}; +// Watch out for recursion here! Our pin_t is signed, so pass through to Arduino -> analogRead(uint8_t) + +uint16_t analogRead(const pin_t pin) { + const bool is_analog = _GET_MODE(pin) == GPIO_INPUT_ANALOG; + return is_analog ? analogRead(uint8_t(pin)) : 0; +} + +// Wrapper to maple unprotected analogWrite +void analogWrite(const pin_t pin, int pwm_val8) { + if (PWM_PIN(pin)) analogWrite(uint8_t(pin), pwm_val8); +} -uint16_t HAL_adc_results[ADC_PIN_COUNT]; +uint16_t MarlinHAL::adc_result; // ------------------------ // Private functions // ------------------------ + static void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) { uint32_t reg_value; - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07); /* only values 0..7 are used */ + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07); // only values 0..7 are used - reg_value = SCB->AIRCR; /* read old register configuration */ - reg_value &= ~(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk); /* clear bits to change */ + reg_value = SCB->AIRCR; // read old register configuration + reg_value &= ~(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk); // clear bits to change reg_value = (reg_value | ((uint32_t)0x5FA << SCB_AIRCR_VECTKEY_Pos) | - (PriorityGroupTmp << 8)); /* Insert write key & priority group */ + (PriorityGroupTmp << 8)); // Insert write key & priority group SCB->AIRCR = reg_value; } @@ -187,6 +150,8 @@ static void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) { // Public functions // ------------------------ +void flashFirmware(const int16_t) { hal.reboot(); } + // // Leave PA11/PA12 intact if USBSerial is not used // @@ -206,7 +171,11 @@ static void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) { TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial()); -void HAL_init() { +// ------------------------ +// MarlinHAL class +// ------------------------ + +void MarlinHAL::init() { NVIC_SetPriorityGrouping(0x3); #if PIN_EXISTS(LED) OUT_WRITE(LED_PIN, LOW); @@ -225,7 +194,7 @@ void HAL_init() { } // HAL idle task -void HAL_idletask() { +void MarlinHAL::idletask() { #if HAS_SHARED_MEDIA // If Marlin is using the SD card we need to lock it to prevent access from // a PC via USB. @@ -240,14 +209,7 @@ void HAL_idletask() { #endif } -void HAL_clear_reset_source() { } - -/** - * TODO: Check this and change or remove. - */ -uint8_t HAL_get_reset_source() { return RST_POWER_ON; } - -void _delay_ms(const int delay_ms) { delay(delay_ms); } +void MarlinHAL::reboot() { nvic_sys_reset(); } extern "C" { extern unsigned int _ebss; // end of bss section @@ -281,31 +243,76 @@ extern "C" { } */ -// ------------------------ +// // ADC -// ------------------------ +// + +enum ADCIndex : uint8_t { + OPTITEM(HAS_TEMP_ADC_0, TEMP_0) + OPTITEM(HAS_TEMP_ADC_1, TEMP_1) + OPTITEM(HAS_TEMP_ADC_2, TEMP_2) + OPTITEM(HAS_TEMP_ADC_3, TEMP_3) + OPTITEM(HAS_TEMP_ADC_4, TEMP_4) + OPTITEM(HAS_TEMP_ADC_5, TEMP_5) + OPTITEM(HAS_TEMP_ADC_6, TEMP_6) + OPTITEM(HAS_TEMP_ADC_7, TEMP_7) + OPTITEM(HAS_HEATED_BED, TEMP_BED) + OPTITEM(HAS_TEMP_CHAMBER, TEMP_CHAMBER) + OPTITEM(HAS_TEMP_ADC_PROBE, TEMP_PROBE) + OPTITEM(HAS_TEMP_COOLER, TEMP_COOLER) + OPTITEM(HAS_TEMP_BOARD, TEMP_BOARD) + OPTITEM(FILAMENT_WIDTH_SENSOR, FILWIDTH) + OPTITEM(HAS_ADC_BUTTONS, ADC_KEY) + OPTITEM(HAS_JOY_ADC_X, JOY_X) + OPTITEM(HAS_JOY_ADC_Y, JOY_Y) + OPTITEM(HAS_JOY_ADC_Z, JOY_Z) + OPTITEM(POWER_MONITOR_CURRENT, POWERMON_CURRENT) + OPTITEM(POWER_MONITOR_VOLTAGE, POWERMON_VOLTS) + ADC_COUNT +}; + +static uint16_t adc_results[ADC_COUNT]; + // Init the AD in continuous capture mode -void HAL_adc_init() { +void MarlinHAL::adc_init() { + static const uint8_t adc_pins[] = { + OPTITEM(HAS_TEMP_ADC_0, TEMP_0_PIN) + OPTITEM(HAS_TEMP_ADC_1, TEMP_1_PIN) + OPTITEM(HAS_TEMP_ADC_2, TEMP_2_PIN) + OPTITEM(HAS_TEMP_ADC_3, TEMP_3_PIN) + OPTITEM(HAS_TEMP_ADC_4, TEMP_4_PIN) + OPTITEM(HAS_TEMP_ADC_5, TEMP_5_PIN) + OPTITEM(HAS_TEMP_ADC_6, TEMP_6_PIN) + OPTITEM(HAS_TEMP_ADC_7, TEMP_7_PIN) + OPTITEM(HAS_HEATED_BED, TEMP_BED_PIN) + OPTITEM(HAS_TEMP_CHAMBER, TEMP_CHAMBER_PIN) + OPTITEM(HAS_TEMP_ADC_PROBE, TEMP_PROBE_PIN) + OPTITEM(HAS_TEMP_COOLER, TEMP_COOLER_PIN) + OPTITEM(HAS_TEMP_BOARD, TEMP_BOARD_PIN) + OPTITEM(FILAMENT_WIDTH_SENSOR, FILWIDTH_PIN) + OPTITEM(HAS_ADC_BUTTONS, ADC_KEYPAD_PIN) + OPTITEM(HAS_JOY_ADC_X, JOY_X_PIN) + OPTITEM(HAS_JOY_ADC_Y, JOY_Y_PIN) + OPTITEM(HAS_JOY_ADC_Z, JOY_Z_PIN) + OPTITEM(POWER_MONITOR_CURRENT, POWER_MONITOR_CURRENT_PIN) + OPTITEM(POWER_MONITOR_VOLTAGE, POWER_MONITOR_VOLTAGE_PIN) + }; + static STM32ADC adc(ADC1); // configure the ADC adc.calibrate(); - #if F_CPU > 72000000 - adc.setSampleRate(ADC_SMPR_71_5); // 71.5 ADC cycles - #else - adc.setSampleRate(ADC_SMPR_41_5); // 41.5 ADC cycles - #endif - adc.setPins((uint8_t *)adc_pins, ADC_PIN_COUNT); - adc.setDMA(HAL_adc_results, (uint16_t)ADC_PIN_COUNT, (uint32_t)(DMA_MINC_MODE | DMA_CIRC_MODE), nullptr); + adc.setSampleRate((F_CPU > 72000000) ? ADC_SMPR_71_5 : ADC_SMPR_41_5); // 71.5 or 41.5 ADC cycles + adc.setPins((uint8_t *)adc_pins, ADC_COUNT); + adc.setDMA(adc_results, uint16_t(ADC_COUNT), uint32_t(DMA_MINC_MODE | DMA_CIRC_MODE), nullptr); adc.setScanMode(); adc.setContinuous(); adc.startConversion(); } -void HAL_adc_start_conversion(const uint8_t adc_pin) { +void MarlinHAL::adc_start(const pin_t pin) { #define __TCASE(N,I) case N: pin_index = I; break; #define _TCASE(C,N,I) TERN_(C, __TCASE(N, I)) - //TEMP_PINS pin_index; - TempPinIndex pin_index; - switch (adc_pin) { + ADCIndex pin_index; + switch (pin) { default: return; _TCASE(HAS_TEMP_ADC_0, TEMP_0_PIN, TEMP_0) _TCASE(HAS_TEMP_ADC_1, TEMP_1_PIN, TEMP_1) @@ -328,23 +335,7 @@ void HAL_adc_start_conversion(const uint8_t adc_pin) { _TCASE(POWER_MONITOR_CURRENT, POWER_MONITOR_CURRENT_PIN, POWERMON_CURRENT) _TCASE(POWER_MONITOR_VOLTAGE, POWER_MONITOR_VOLTAGE_PIN, POWERMON_VOLTS) } - HAL_adc_result = HAL_adc_results[(int)pin_index] >> (12 - HAL_ADC_RESOLUTION); // shift out unused bits -} - -uint16_t HAL_adc_get_result() { return HAL_adc_result; } - -uint16_t analogRead(pin_t pin) { - const bool is_analog = _GET_MODE(pin) == GPIO_INPUT_ANALOG; - return is_analog ? analogRead(uint8_t(pin)) : 0; -} - -// Wrapper to maple unprotected analogWrite -void analogWrite(pin_t pin, int pwm_val8) { - if (PWM_PIN(pin)) analogWrite(uint8_t(pin), pwm_val8); + adc_result = (adc_results[(int)pin_index] & 0xFFF) >> (12 - HAL_ADC_RESOLUTION); // shift out unused bits } -void HAL_reboot() { nvic_sys_reset(); } - -void flashFirmware(const int16_t) { HAL_reboot(); } - #endif // __STM32F1__ diff --git a/Marlin/src/HAL/STM32F1/HAL.h b/Marlin/src/HAL/STM32F1/HAL.h index a766babe155b9..8fbb43c6022b4 100644 --- a/Marlin/src/HAL/STM32F1/HAL.h +++ b/Marlin/src/HAL/STM32F1/HAL.h @@ -66,6 +66,10 @@ #endif #endif +// ------------------------ +// Serial ports +// ------------------------ + #ifdef SERIAL_USB typedef ForwardSerial1Class< USBSerial > DefaultSerial1; extern DefaultSerial1 MSerial0; @@ -141,11 +145,6 @@ #endif #endif -// Set interrupt grouping for this MCU -void HAL_init(); -#define HAL_IDLETASK 1 -void HAL_idletask(); - /** * TODO: review this to return 1 for pins that are not analog input */ @@ -158,15 +157,7 @@ void HAL_idletask(); #define NO_COMPILE_TIME_PWM #endif -#define CRITICAL_SECTION_START() uint32_t primask = __get_primask(); (void)__iCliRetVal() -#define CRITICAL_SECTION_END() if (!primask) (void)__iSeiRetVal() -#define ISRS_ENABLED() (!__get_primask()) -#define ENABLE_ISRS() ((void)__iSeiRetVal()) -#define DISABLE_ISRS() ((void)__iCliRetVal()) - -// On AVR this is in math.h? -#define square(x) ((x)*(x)) - +// Reset Reason #define RST_POWER_ON 1 #define RST_EXTERNAL 2 #define RST_BROWN_OUT 4 @@ -182,46 +173,63 @@ void HAL_idletask(); typedef int8_t pin_t; // ------------------------ -// Public Variables +// Interrupts // ------------------------ -// Result of last ADC conversion -extern uint16_t HAL_adc_result; +#define CRITICAL_SECTION_START() const bool irqon = !__get_primask(); (void)__iCliRetVal() +#define CRITICAL_SECTION_END() if (!primask) (void)__iSeiRetVal() +#define cli() noInterrupts() +#define sei() interrupts() // ------------------------ -// Public functions +// ADC // ------------------------ -// Disable interrupts -#define cli() noInterrupts() +#ifdef ADC_RESOLUTION + #define HAL_ADC_RESOLUTION ADC_RESOLUTION +#else + #define HAL_ADC_RESOLUTION 12 +#endif -// Enable interrupts -#define sei() interrupts() +#define HAL_ADC_VREF 3.3 -// Memory related -#define __bss_end __bss_end__ +uint16_t analogRead(const pin_t pin); // need hal.adc_enable() first +void analogWrite(const pin_t pin, int pwm_val8); // PWM only! mul by 257 in maple!? -// Clear reset reason -void HAL_clear_reset_source(); +// +// Pin Mapping for M42, M43, M226 +// +#define GET_PIN_MAP_PIN(index) index +#define GET_PIN_MAP_INDEX(pin) pin +#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) -// Reset reason -uint8_t HAL_get_reset_source(); +#define JTAG_DISABLE() afio_cfg_debug_ports(AFIO_DEBUG_SW_ONLY) +#define JTAGSWD_DISABLE() afio_cfg_debug_ports(AFIO_DEBUG_NONE) -void HAL_reboot(); +#define PLATFORM_M997_SUPPORT +void flashFirmware(const int16_t); -void _delay_ms(const int delay); +#define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment +#ifndef PWM_FREQUENCY + #define PWM_FREQUENCY 1000 // Default PWM Frequency +#endif -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wunused-function" +// ------------------------ +// Class Utilities +// ------------------------ -/* -extern "C" { - int freeMemory(); -} -*/ +// Memory related +#define __bss_end __bss_end__ + +void _delay_ms(const int ms); extern "C" char* _sbrk(int incr); +#pragma GCC diagnostic push +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic ignored "-Wunused-function" +#endif + static inline int freeMemory() { volatile char top; return &top - _sbrk(0); @@ -229,58 +237,70 @@ static inline int freeMemory() { #pragma GCC diagnostic pop -// -// ADC -// +// ------------------------ +// MarlinHAL Class +// ------------------------ -#define HAL_ANALOG_SELECT(pin) pinMode(pin, INPUT_ANALOG); +class MarlinHAL { +public: -void HAL_adc_init(); + // Earliest possible init, before setup() + MarlinHAL() {} -#ifdef ADC_RESOLUTION - #define HAL_ADC_RESOLUTION ADC_RESOLUTION -#else - #define HAL_ADC_RESOLUTION 12 -#endif + static void init(); // Called early in setup() + static void init_board() {} // Called less early in setup() + static void reboot(); // Restart the firmware from 0x0 -#define HAL_ADC_VREF 3.3 -#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) -#define HAL_READ_ADC() HAL_adc_result -#define HAL_ADC_READY() true + // Interrupts + static bool isr_state() { return !__get_primask(); } + static void isr_on() { ((void)__iSeiRetVal()); } + static void isr_off() { ((void)__iCliRetVal()); } -void HAL_adc_start_conversion(const uint8_t adc_pin); -uint16_t HAL_adc_get_result(); + static void delay_ms(const int ms) { delay(ms); } -uint16_t analogRead(pin_t pin); // need HAL_ANALOG_SELECT() first -void analogWrite(pin_t pin, int pwm_val8); // PWM only! mul by 257 in maple!? + // Tasks, called from idle() + static void idletask(); -#define GET_PIN_MAP_PIN(index) index -#define GET_PIN_MAP_INDEX(pin) pin -#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) + // Reset + static uint8_t get_reset_source() { return RST_POWER_ON; } + static void clear_reset_source() {} -#define JTAG_DISABLE() afio_cfg_debug_ports(AFIO_DEBUG_SW_ONLY) -#define JTAGSWD_DISABLE() afio_cfg_debug_ports(AFIO_DEBUG_NONE) + // Free SRAM + static int freeMemory() { return ::freeMemory(); } -#define PLATFORM_M997_SUPPORT -void flashFirmware(const int16_t); + // + // ADC Methods + // -#ifndef PWM_FREQUENCY - #define PWM_FREQUENCY 1000 // Default PWM Frequency -#endif -#define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment + static uint16_t adc_result; -/** - * set_pwm_frequency - * Set the frequency of the timer corresponding to the provided pin - * All Timer PWM pins run at the same frequency - */ -void set_pwm_frequency(const pin_t pin, const uint16_t f_desired); + // Called by Temperature::init once at startup + static void adc_init(); -/** - * set_pwm_duty - * Set the PWM duty cycle of the provided pin to the provided value - * Optionally allows inverting the duty cycle [default = false] - * Optionally allows changing the maximum size of the provided value to enable finer PWM duty control [default = 255] - * The timer must be pre-configured with set_pwm_frequency() if the default frequency is not desired. - */ -void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false); + // Called by Temperature::init for each sensor at startup + static void adc_enable(const pin_t pin) { pinMode(pin, INPUT_ANALOG); } + + // Begin ADC sampling on the given channel + static void adc_start(const pin_t pin); + + // Is the ADC ready for reading? + static bool adc_ready() { return true; } + + // The current value of the ADC register + static uint16_t adc_value() { return adc_result; } + + /** + * Set the PWM duty cycle for the pin to the given value. + * Optionally invert the duty cycle [default = false] + * Optionally change the maximum size of the provided value to enable finer PWM duty control [default = 255] + * The timer must be pre-configured with set_pwm_frequency() if the default frequency is not desired. + */ + static void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false); + + /** + * Set the frequency of the timer for the given pin. + * All Timer PWM pins run at the same frequency. + */ + static void set_pwm_frequency(const pin_t pin, const uint16_t f_desired); + +}; diff --git a/Marlin/src/HAL/STM32F1/SPI.cpp b/Marlin/src/HAL/STM32F1/SPI.cpp index 8bfa3d236a7cf..1ce2c7d3fd5dc 100644 --- a/Marlin/src/HAL/STM32F1/SPI.cpp +++ b/Marlin/src/HAL/STM32F1/SPI.cpp @@ -91,6 +91,14 @@ static const spi_pins board_spi_pins[] __FLASH__ = { static void *_spi3_this; #endif +/** + * @brief Wait until TXE (tx empty) flag is set and BSY (busy) flag unset. + */ +static inline void waitSpiTxEnd(spi_dev *spi_d) { + while (spi_is_tx_empty(spi_d) == 0) { /* nada */ } // wait until TXE=1 + while (spi_is_busy(spi_d) != 0) { /* nada */ } // wait until BSY=0 +} + /** * Constructor */ diff --git a/Marlin/src/HAL/STM32F1/SPI.h b/Marlin/src/HAL/STM32F1/SPI.h index 92f42263014a6..13f4d5ed6cfe4 100644 --- a/Marlin/src/HAL/STM32F1/SPI.h +++ b/Marlin/src/HAL/STM32F1/SPI.h @@ -414,12 +414,4 @@ class SPIClass { */ }; -/** - * @brief Wait until TXE (tx empty) flag is set and BSY (busy) flag unset. - */ -static void waitSpiTxEnd(spi_dev *spi_d) { - while (spi_is_tx_empty(spi_d) == 0) { /* nada */ } // wait until TXE=1 - while (spi_is_busy(spi_d) != 0) { /* nada */ } // wait until BSY=0 -} - extern SPIClass SPI; diff --git a/Marlin/src/HAL/STM32F1/Servo.h b/Marlin/src/HAL/STM32F1/Servo.h index b6143de81d62a..745a1c93f07d4 100644 --- a/Marlin/src/HAL/STM32F1/Servo.h +++ b/Marlin/src/HAL/STM32F1/Servo.h @@ -35,7 +35,8 @@ #define SERVO_DEFAULT_MIN_ANGLE 0 #define SERVO_DEFAULT_MAX_ANGLE 180 -#define HAL_SERVO_LIB libServo +class libServo; +typedef libServo hal_servo_t; class libServo { public: diff --git a/Marlin/src/HAL/STM32F1/fast_pwm.cpp b/Marlin/src/HAL/STM32F1/fast_pwm.cpp index 13411d9af0843..297804a3ac42a 100644 --- a/Marlin/src/HAL/STM32F1/fast_pwm.cpp +++ b/Marlin/src/HAL/STM32F1/fast_pwm.cpp @@ -21,11 +21,9 @@ */ #ifdef __STM32F1__ -#include "../../inc/MarlinConfigPre.h" +#include "../../inc/MarlinConfig.h" #include -#include "HAL.h" -#include "timers.h" #define NR_TIMERS TERN(STM32_XL_DENSITY, 14, 8) // Maple timers, 14 for STM32_XL_DENSITY (F/G chips), 8 for HIGH density (C D E) @@ -38,7 +36,7 @@ inline uint8_t timer_and_index_for_pin(const pin_t pin, timer_dev **timer_ptr) { return 0; } -void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { +void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) { const uint16_t duty = invert ? v_size - v : v; if (PWM_PIN(pin)) { timer_dev *timer; UNUSED(timer); @@ -54,7 +52,7 @@ void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255 } } -void set_pwm_frequency(const pin_t pin, const uint16_t f_desired) { +void MarlinHAL::set_pwm_frequency(const pin_t pin, const uint16_t f_desired) { if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer timer_dev *timer; UNUSED(timer); diff --git a/Marlin/src/HAL/STM32F1/timers.h b/Marlin/src/HAL/STM32F1/timers.h index f9ab6d13d3741..0cd807fc84799 100644 --- a/Marlin/src/HAL/STM32F1/timers.h +++ b/Marlin/src/HAL/STM32F1/timers.h @@ -188,7 +188,7 @@ FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) { } } -#define HAL_timer_isr_epilogue(T) +#define HAL_timer_isr_epilogue(T) NOOP // No command is available in framework to turn off ARPE bit, which is turned on by default in libmaple. // Needed here to reset ARPE=0 for stepper timer diff --git a/Marlin/src/HAL/TEENSY31_32/HAL.cpp b/Marlin/src/HAL/TEENSY31_32/HAL.cpp index f08cf799e9e8b..b923ab77b1f12 100644 --- a/Marlin/src/HAL/TEENSY31_32/HAL.cpp +++ b/Marlin/src/HAL/TEENSY31_32/HAL.cpp @@ -31,6 +31,10 @@ #include +// ------------------------ +// Serial ports +// ------------------------ + #define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X) #define IMPLEMENT_SERIAL(X) _IMPLEMENT_SERIAL(X) #if WITHIN(SERIAL_PORT, 0, 3) @@ -40,33 +44,32 @@ #endif USBSerialType USBSerial(false, SerialUSB); -uint16_t HAL_adc_result; - -static const uint8_t pin2sc1a[] = { - 5, 14, 8, 9, 13, 12, 6, 7, 15, 4, 0, 19, 3, 31, // 0-13, we treat them as A0-A13 - 5, 14, 8, 9, 13, 12, 6, 7, 15, 4, // 14-23 (A0-A9) - 31, 31, 31, 31, 31, 31, 31, 31, 31, 31, // 24-33 - 0+64, 19+64, 3+64, 31+64, // 34-37 (A10-A13) - 26, 22, 23, 27, 29, 30 // 38-43: temp. sensor, VREF_OUT, A14, bandgap, VREFH, VREFL. A14 isn't connected to anything in Teensy 3.0. -}; - -/* - // disable interrupts - void cli() { noInterrupts(); } +// ------------------------ +// Class Utilities +// ------------------------ - // enable interrupts - void sei() { interrupts(); } -*/ +extern "C" { + extern char __bss_end; + extern char __heap_start; + extern void* __brkval; -void HAL_adc_init() { - analog_init(); - while (ADC0_SC3 & ADC_SC3_CAL) {}; // Wait for calibration to finish - NVIC_ENABLE_IRQ(IRQ_FTM1); + int freeMemory() { + int free_memory; + if ((int)__brkval == 0) + free_memory = ((int)&free_memory) - ((int)&__bss_end); + else + free_memory = ((int)&free_memory) - ((int)__brkval); + return free_memory; + } } -void HAL_clear_reset_source() { } +// ------------------------ +// MarlinHAL Class +// ------------------------ -uint8_t HAL_get_reset_source() { +void MarlinHAL::reboot() { _reboot_Teensyduino_(); } + +uint8_t MarlinHAL::get_reset_source() { switch (RCM_SRS0) { case 128: return RST_POWER_ON; break; case 64: return RST_EXTERNAL; break; @@ -78,25 +81,25 @@ uint8_t HAL_get_reset_source() { return 0; } -void HAL_reboot() { _reboot_Teensyduino_(); } +// ADC -extern "C" { - extern char __bss_end; - extern char __heap_start; - extern void* __brkval; - - int freeMemory() { - int free_memory; - if ((int)__brkval == 0) - free_memory = ((int)&free_memory) - ((int)&__bss_end); - else - free_memory = ((int)&free_memory) - ((int)__brkval); - return free_memory; - } +void MarlinHAL::adc_init() { + analog_init(); + while (ADC0_SC3 & ADC_SC3_CAL) {}; // Wait for calibration to finish + NVIC_ENABLE_IRQ(IRQ_FTM1); } -void HAL_adc_start_conversion(const uint8_t adc_pin) { ADC0_SC1A = pin2sc1a[adc_pin]; } +void MarlinHAL::adc_start(const pin_t pin) { + static const uint8_t pin2sc1a[] = { + 5, 14, 8, 9, 13, 12, 6, 7, 15, 4, 0, 19, 3, 31, // 0-13, we treat them as A0-A13 + 5, 14, 8, 9, 13, 12, 6, 7, 15, 4, // 14-23 (A0-A9) + 31, 31, 31, 31, 31, 31, 31, 31, 31, 31, // 24-33 + 0+64, 19+64, 3+64, 31+64, // 34-37 (A10-A13) + 26, 22, 23, 27, 29, 30 // 38-43: temp. sensor, VREF_OUT, A14, bandgap, VREFH, VREFL. A14 isn't connected to anything in Teensy 3.0. + }; + ADC0_SC1A = pin2sc1a[pin]; +} -uint16_t HAL_adc_get_result() { return ADC0_RA; } +uint16_t MarlinHAL::adc_value() { return ADC0_RA; } #endif // __MK20DX256__ diff --git a/Marlin/src/HAL/TEENSY31_32/HAL.h b/Marlin/src/HAL/TEENSY31_32/HAL.h index 61d8b34604c52..50c0f411cf92b 100644 --- a/Marlin/src/HAL/TEENSY31_32/HAL.h +++ b/Marlin/src/HAL/TEENSY31_32/HAL.h @@ -36,12 +36,9 @@ #include -#define CPU_ST7920_DELAY_1 600 -#define CPU_ST7920_DELAY_2 750 -#define CPU_ST7920_DELAY_3 750 - -//#undef MOTHERBOARD -//#define MOTHERBOARD BOARD_TEENSY31_32 +// ------------------------ +// Defines +// ------------------------ #define IS_32BIT_TEENSY 1 #define IS_TEENSY_31_32 1 @@ -49,6 +46,14 @@ #define IS_TEENSY32 1 #endif +#define CPU_ST7920_DELAY_1 600 +#define CPU_ST7920_DELAY_2 750 +#define CPU_ST7920_DELAY_3 750 + +// ------------------------ +// Serial ports +// ------------------------ + #include "../../core/serial_hook.h" #define Serial0 Serial @@ -72,31 +77,44 @@ extern USBSerialType USBSerial; #error "The required SERIAL_PORT must be from 0 to 3, or -1 for Native USB." #endif -#define HAL_SERVO_LIB libServo +// ------------------------ +// Types +// ------------------------ + +class libServo; +typedef libServo hal_servo_t; typedef int8_t pin_t; -#ifndef analogInputToDigitalPin - #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1) -#endif +// ------------------------ +// Interrupts +// ------------------------ -#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() +uint32_t __get_PRIMASK(void); // CMSIS +#define CRITICAL_SECTION_START() const bool irqon = !__get_PRIMASK(); __disable_irq() +#define CRITICAL_SECTION_END() if (irqon) __enable_irq() -inline void HAL_init() {} +// ------------------------ +// ADC +// ------------------------ -// Clear the reset reason -void HAL_clear_reset_source(); +#ifndef analogInputToDigitalPin + #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1) +#endif -// Get the reason for the reset -uint8_t HAL_get_reset_source(); +#define HAL_ADC_VREF 3.3 +#define HAL_ADC_RESOLUTION 10 -void HAL_reboot(); +// +// Pin Mapping for M42, M43, M226 +// +#define GET_PIN_MAP_PIN(index) index +#define GET_PIN_MAP_INDEX(pin) pin +#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) -FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); } +// ------------------------ +// Class Utilities +// ------------------------ #pragma GCC diagnostic push #if GCC_VERSION <= 50000 @@ -107,27 +125,63 @@ extern "C" int freeMemory(); #pragma GCC diagnostic pop -// ADC +// ------------------------ +// MarlinHAL Class +// ------------------------ -void HAL_adc_init(); +class MarlinHAL { +public: -#define HAL_ADC_VREF 3.3 -#define HAL_ADC_RESOLUTION 10 -#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) -#define HAL_READ_ADC() HAL_adc_get_result() -#define HAL_ADC_READY() true + // Earliest possible init, before setup() + MarlinHAL() {} -#define HAL_ANALOG_SELECT(pin) + static void init() {} // Called early in setup() + static void init_board() {} // Called less early in setup() + static void reboot(); // Restart the firmware from 0x0 -void HAL_adc_start_conversion(const uint8_t adc_pin); -uint16_t HAL_adc_get_result(); + // Interrupts + static bool isr_state() { return !__get_PRIMASK(); } + static void isr_on() { __enable_irq(); } + static void isr_off() { __disable_irq(); } -// PWM + static void delay_ms(const int ms) { delay(ms); } -inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } + // Tasks, called from idle() + static void idletask() {} -// Pin Map + // Reset + static uint8_t get_reset_source(); + static void clear_reset_source() {} -#define GET_PIN_MAP_PIN(index) index -#define GET_PIN_MAP_INDEX(pin) pin -#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) + // Free SRAM + static int freeMemory() { return ::freeMemory(); } + + // + // ADC Methods + // + + // Called by Temperature::init once at startup + static void adc_init(); + + // Called by Temperature::init for each sensor at startup + static void adc_enable(const pin_t ch) {} + + // Begin ADC sampling on the given channel + static void adc_start(const pin_t ch); + + // Is the ADC ready for reading? + static bool adc_ready() { return true; } + + // The current value of the ADC register + static uint16_t adc_value(); + + /** + * Set the PWM duty cycle for the pin to the given value. + * No option to invert the duty cycle [default = false] + * No option to change the scale of the provided value to enable finer PWM duty control [default = 255] + */ + static void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { + analogWrite(pin, v); + } + +}; diff --git a/Marlin/src/HAL/TEENSY31_32/timers.h b/Marlin/src/HAL/TEENSY31_32/timers.h index 3b073d63ab293..9fcbb6f232c93 100644 --- a/Marlin/src/HAL/TEENSY31_32/timers.h +++ b/Marlin/src/HAL/TEENSY31_32/timers.h @@ -110,4 +110,4 @@ 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); -#define HAL_timer_isr_epilogue(T) +#define HAL_timer_isr_epilogue(T) NOOP diff --git a/Marlin/src/HAL/TEENSY35_36/HAL.cpp b/Marlin/src/HAL/TEENSY35_36/HAL.cpp index 046c00b56ed53..54a5ad3855361 100644 --- a/Marlin/src/HAL/TEENSY35_36/HAL.cpp +++ b/Marlin/src/HAL/TEENSY35_36/HAL.cpp @@ -31,6 +31,10 @@ #include +// ------------------------ +// Serial ports +// ------------------------ + #define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X) #define IMPLEMENT_SERIAL(X) _IMPLEMENT_SERIAL(X) #if WITHIN(SERIAL_PORT, 0, 3) @@ -39,42 +43,34 @@ USBSerialType USBSerial(false, SerialUSB); -uint16_t HAL_adc_result, HAL_adc_select; - -static const uint8_t pin2sc1a[] = { - 5, 14, 8, 9, 13, 12, 6, 7, 15, 4, 3, 19+128, 14+128, 15+128, // 0-13 -> A0-A13 - 5, 14, 8, 9, 13, 12, 6, 7, 15, 4, // 14-23 are A0-A9 - 255, 255, 255, 255, 255, 255, 255, // 24-30 are digital only - 14+128, 15+128, 17, 18, 4+128, 5+128, 6+128, 7+128, 17+128, // 31-39 are A12-A20 - 255, 255, 255, 255, 255, 255, 255, 255, 255, // 40-48 are digital only - 10+128, 11+128, // 49-50 are A23-A24 - 255, 255, 255, 255, 255, 255, 255, // 51-57 are digital only - 255, 255, 255, 255, 255, 255, // 58-63 (sd card pins) are digital only - 3, 19+128, // 64-65 are A10-A11 - 23, 23+128,// 66-67 are A21-A22 (DAC pins) - 1, 1+128, // 68-69 are A25-A26 (unused USB host port on Teensy 3.5) - 26, // 70 is Temperature Sensor - 18+128 // 71 is Vref -}; - -/* - // disable interrupts - void cli() { noInterrupts(); } - - // enable interrupts - void sei() { interrupts(); } -*/ - -void HAL_adc_init() { - analog_init(); - while (ADC0_SC3 & ADC_SC3_CAL) {}; // Wait for calibration to finish - while (ADC1_SC3 & ADC_SC3_CAL) {}; // Wait for calibration to finish - NVIC_ENABLE_IRQ(IRQ_FTM1); +// ------------------------ +// Class Utilities +// ------------------------ + +extern "C" { + extern char __bss_end; + extern char __heap_start; + extern void* __brkval; + + int freeMemory() { + int free_memory; + if ((int)__brkval == 0) + free_memory = ((int)&free_memory) - ((int)&__bss_end); + else + free_memory = ((int)&free_memory) - ((int)__brkval); + return free_memory; + } } -void HAL_clear_reset_source() { } +// ------------------------ +// MarlinHAL Class +// ------------------------ -uint8_t HAL_get_reset_source() { +void MarlinHAL::reboot() { _reboot_Teensyduino_(); } + +// Reset + +uint8_t MarlinHAL::get_reset_source() { switch (RCM_SRS0) { case 128: return RST_POWER_ON; break; case 64: return RST_EXTERNAL; break; @@ -86,41 +82,49 @@ uint8_t HAL_get_reset_source() { return 0; } -void HAL_reboot() { _reboot_Teensyduino_(); } +// ADC -extern "C" { - extern char __bss_end; - extern char __heap_start; - extern void* __brkval; +int8_t MarlinHAL::adc_select; - int freeMemory() { - int free_memory; - if ((int)__brkval == 0) - free_memory = ((int)&free_memory) - ((int)&__bss_end); - else - free_memory = ((int)&free_memory) - ((int)__brkval); - return free_memory; - } +void MarlinHAL::adc_init() { + analog_init(); + while (ADC0_SC3 & ADC_SC3_CAL) { /* Wait for calibration to finish */ } + while (ADC1_SC3 & ADC_SC3_CAL) { /* Wait for calibration to finish */ } + NVIC_ENABLE_IRQ(IRQ_FTM1); } -void HAL_adc_start_conversion(const uint8_t adc_pin) { +void MarlinHAL::adc_start(const pin_t adc_pin) { + static const uint8_t pin2sc1a[] = { + 5, 14, 8, 9, 13, 12, 6, 7, 15, 4, 3, 19+128, 14+128, 15+128, // 0-13 -> A0-A13 + 5, 14, 8, 9, 13, 12, 6, 7, 15, 4, // 14-23 are A0-A9 + 255, 255, 255, 255, 255, 255, 255, // 24-30 are digital only + 14+128, 15+128, 17, 18, 4+128, 5+128, 6+128, 7+128, 17+128, // 31-39 are A12-A20 + 255, 255, 255, 255, 255, 255, 255, 255, 255, // 40-48 are digital only + 10+128, 11+128, // 49-50 are A23-A24 + 255, 255, 255, 255, 255, 255, 255, // 51-57 are digital only + 255, 255, 255, 255, 255, 255, // 58-63 (sd card pins) are digital only + 3, 19+128, // 64-65 are A10-A11 + 23, 23+128,// 66-67 are A21-A22 (DAC pins) + 1, 1+128, // 68-69 are A25-A26 (unused USB host port on Teensy 3.5) + 26, // 70 is Temperature Sensor + 18+128 // 71 is Vref + }; const uint16_t pin = pin2sc1a[adc_pin]; if (pin == 0xFF) { - // Digital only - HAL_adc_select = -1; + adc_select = -1; // Digital only } else if (pin & 0x80) { - HAL_adc_select = 1; + adc_select = 1; ADC1_SC1A = pin & 0x7F; } else { - HAL_adc_select = 0; + adc_select = 0; ADC0_SC1A = pin; } } -uint16_t HAL_adc_get_result() { - switch (HAL_adc_select) { +uint16_t MarlinHAL::adc_value() { + switch (adc_select) { case 0: return ADC0_RA; case 1: return ADC1_RA; } diff --git a/Marlin/src/HAL/TEENSY35_36/HAL.h b/Marlin/src/HAL/TEENSY35_36/HAL.h index 892eb2d3c5b8f..e4c57f8d1e108 100644 --- a/Marlin/src/HAL/TEENSY35_36/HAL.h +++ b/Marlin/src/HAL/TEENSY35_36/HAL.h @@ -37,10 +37,6 @@ #include #include -#define CPU_ST7920_DELAY_1 600 -#define CPU_ST7920_DELAY_2 750 -#define CPU_ST7920_DELAY_3 750 - // ------------------------ // Defines // ------------------------ @@ -53,6 +49,17 @@ #define IS_TEENSY35 1 #endif +#define CPU_ST7920_DELAY_1 600 +#define CPU_ST7920_DELAY_2 750 +#define CPU_ST7920_DELAY_3 750 + +#undef sq +#define sq(x) ((x)*(x)) + +// ------------------------ +// Serial ports +// ------------------------ + #include "../../core/serial_hook.h" #define Serial0 Serial @@ -76,34 +83,43 @@ extern USBSerialType USBSerial; #error "SERIAL_PORT must be from 0 to 3, or -1 for Native USB." #endif -#define HAL_SERVO_LIB libServo +// ------------------------ +// Types +// ------------------------ -typedef int8_t pin_t; +class libServo; +typedef libServo hal_servo_t; -#ifndef analogInputToDigitalPin - #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1) -#endif +typedef int8_t pin_t; -#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() +// ------------------------ +// Interrupts +// ------------------------ -#undef sq -#define sq(x) ((x)*(x)) +#define CRITICAL_SECTION_START() const bool irqon = !__get_primask(); __disable_irq() +#define CRITICAL_SECTION_END() if (irqon) __enable_irq() -inline void HAL_init() {} +// ------------------------ +// ADC +// ------------------------ -// Clear reset reason -void HAL_clear_reset_source(); +#ifndef analogInputToDigitalPin + #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1) +#endif -// Reset reason -uint8_t HAL_get_reset_source(); +#define HAL_ADC_VREF 3.3 +#define HAL_ADC_RESOLUTION 10 -void HAL_reboot(); +// +// Pin Mapping for M42, M43, M226 +// +#define GET_PIN_MAP_PIN(index) index +#define GET_PIN_MAP_INDEX(pin) pin +#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) -FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); } +// ------------------------ +// Class Utilities +// ------------------------ #pragma GCC diagnostic push #if GCC_VERSION <= 50000 @@ -114,27 +130,65 @@ extern "C" int freeMemory(); #pragma GCC diagnostic pop -// ADC +// ------------------------ +// MarlinHAL Class +// ------------------------ -void HAL_adc_init(); +class MarlinHAL { +public: -#define HAL_ADC_VREF 3.3 -#define HAL_ADC_RESOLUTION 10 -#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin) -#define HAL_READ_ADC() HAL_adc_get_result() -#define HAL_ADC_READY() true + // Earliest possible init, before setup() + MarlinHAL() {} -#define HAL_ANALOG_SELECT(pin) + static void init() {} // Called early in setup() + static void init_board() {} // Called less early in setup() + static void reboot(); // Restart the firmware from 0x0 -void HAL_adc_start_conversion(const uint8_t adc_pin); -uint16_t HAL_adc_get_result(); + // Interrupts + static bool isr_state() { return true; } + static void isr_on() { __enable_irq(); } + static void isr_off() { __disable_irq(); } -// PWM + static void delay_ms(const int ms) { delay(ms); } -inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } + // Tasks, called from idle() + static void idletask() {} -// Pin Map + // Reset + static uint8_t get_reset_source(); + static void clear_reset_source() {} -#define GET_PIN_MAP_PIN(index) index -#define GET_PIN_MAP_INDEX(pin) pin -#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) + // Free SRAM + static int freeMemory() { return ::freeMemory(); } + + // + // ADC Methods + // + + static int8_t adc_select; + + // Called by Temperature::init once at startup + static void adc_init(); + + // Called by Temperature::init for each sensor at startup + static void adc_enable(const pin_t) {} + + // Begin ADC sampling on the given channel + static void adc_start(const pin_t pin); + + // Is the ADC ready for reading? + static bool adc_ready() { return true; } + + // The current value of the ADC register + static uint16_t adc_value(); + + /** + * Set the PWM duty cycle for the pin to the given value. + * No option to invert the duty cycle [default = false] + * No option to change the scale of the provided value to enable finer PWM duty control [default = 255] + */ + static void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { + analogWrite(pin, v); + } + +}; diff --git a/Marlin/src/HAL/TEENSY35_36/timers.h b/Marlin/src/HAL/TEENSY35_36/timers.h index 6c342bbe0d252..8af79d73928e5 100644 --- a/Marlin/src/HAL/TEENSY35_36/timers.h +++ b/Marlin/src/HAL/TEENSY35_36/timers.h @@ -109,4 +109,4 @@ 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); -#define HAL_timer_isr_epilogue(T) +#define HAL_timer_isr_epilogue(T) NOOP diff --git a/Marlin/src/HAL/TEENSY40_41/HAL.cpp b/Marlin/src/HAL/TEENSY40_41/HAL.cpp index 270bee0dc9d45..68bd38f72ff89 100644 --- a/Marlin/src/HAL/TEENSY40_41/HAL.cpp +++ b/Marlin/src/HAL/TEENSY40_41/HAL.cpp @@ -33,6 +33,10 @@ #include "timers.h" #include +// ------------------------ +// Serial ports +// ------------------------ + #define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X) #define IMPLEMENT_SERIAL(X) _IMPLEMENT_SERIAL(X) #if WITHIN(SERIAL_PORT, 0, 3) @@ -40,75 +44,42 @@ #endif USBSerialType USBSerial(false, SerialUSB); -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) ; +// ------------------------ +// Class Utilities +// ------------------------ + +#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; + free_memory = ((uint32_t)&free_memory) - (((uint32_t)__brkval) ?: ((uint32_t)&__bss_end)); + return free_memory; + } } -void HAL_clear_reset_source() { - uint32_t reset_source = SRC_SRSR; - SRC_SRSR = reset_source; +// ------------------------ +// FastIO +// ------------------------ + +bool is_output(pin_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); } -uint8_t HAL_get_reset_source() { +// ------------------------ +// MarlinHAL Class +// ------------------------ + +void MarlinHAL::reboot() { _reboot_Teensyduino_(); } + +uint8_t MarlinHAL::get_reset_source() { switch (SRC_SRSR & 0xFF) { case 1: return RST_POWER_ON; break; case 2: return RST_SOFTWARE; break; @@ -121,57 +92,92 @@ uint8_t HAL_get_reset_source() { return 0; } -void HAL_reboot() { _reboot_Teensyduino_(); } +void MarlinHAL::clear_reset_source() { + uint32_t reset_source = SRC_SRSR; + SRC_SRSR = reset_source; +} -#define __bss_end _ebss +// ADC -extern "C" { - extern char __bss_end; - extern char __heap_start; - extern void* __brkval; +int8_t MarlinHAL::adc_select; - // 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 MarlinHAL::adc_init() { + analog_init(); + while (ADC1_GC & ADC_GC_CAL) { /* wait */ } + while (ADC2_GC & ADC_GC_CAL) { /* wait */ } } -void HAL_adc_start_conversion(const uint8_t adc_pin) { +void MarlinHAL::adc_start(const pin_t adc_pin) { + 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 + }; const uint16_t pin = pin2sc1a[adc_pin]; if (pin == 0xFF) { - HAL_adc_select = -1; // Digital only + adc_select = -1; // Digital only } else if (pin & 0x80) { - HAL_adc_select = 1; + adc_select = 1; ADC2_HC0 = pin & 0x7F; } else { - HAL_adc_select = 0; + adc_select = 0; ADC1_HC0 = pin; } } -uint16_t HAL_adc_get_result() { - switch (HAL_adc_select) { +uint16_t MarlinHAL::adc_value() { + switch (adc_select) { case 0: - while (!(ADC1_HS & ADC_HS_COCO0)) ; // wait + while (!(ADC1_HS & ADC_HS_COCO0)) { /* wait */ } return ADC1_R0; case 1: - while (!(ADC2_HS & ADC_HS_COCO0)) ; // wait + while (!(ADC2_HS & ADC_HS_COCO0)) { /* wait */ } return ADC2_R0; } return 0; } -bool is_output(pin_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 index 2b730768a8025..a21e652854090 100644 --- a/Marlin/src/HAL/TEENSY40_41/HAL.h +++ b/Marlin/src/HAL/TEENSY40_41/HAL.h @@ -41,10 +41,6 @@ #include "../../feature/ethernet.h" #endif -#define CPU_ST7920_DELAY_1 600 -#define CPU_ST7920_DELAY_2 750 -#define CPU_ST7920_DELAY_3 750 - // ------------------------ // Defines // ------------------------ @@ -55,7 +51,23 @@ #define IS_TEENSY41 1 #endif +#define CPU_ST7920_DELAY_1 600 +#define CPU_ST7920_DELAY_2 750 +#define CPU_ST7920_DELAY_3 750 + +#undef sq +#define sq(x) ((x)*(x)) + +// Don't place string constants in PROGMEM +#undef PSTR +#define PSTR(str) ({static const char *data = (str); &data[0];}) + +// ------------------------ +// Serial ports +// ------------------------ + #include "../../core/serial_hook.h" + #define Serial0 Serial #define _DECLARE_SERIAL(X) \ typedef ForwardSerial1Class DefaultSerial##X; \ @@ -89,41 +101,47 @@ extern USBSerialType USBSerial; #endif #endif -#define HAL_SERVO_LIB libServo +// ------------------------ +// Types +// ------------------------ -typedef int8_t pin_t; +class libServo; +typedef libServo hal_servo_t; -#ifndef analogInputToDigitalPin - #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1) -#endif +typedef int8_t pin_t; -#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() +// ------------------------ +// Interrupts +// ------------------------ -#undef sq -#define sq(x) ((x)*(x)) +#define CRITICAL_SECTION_START() const bool irqon = !__get_primask(); __disable_irq() +#define CRITICAL_SECTION_END() if (irqon) __enable_irq() -// Don't place string constants in PROGMEM -#undef PSTR -#define PSTR(str) ({static const char *data = (str); &data[0];}) +// ------------------------ +// ADC +// ------------------------ -// Enable hooks into idle and setup for HAL -#define HAL_IDLETASK 1 -FORCE_INLINE void HAL_idletask() {} -FORCE_INLINE void HAL_init() {} +#ifndef analogInputToDigitalPin + #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1) +#endif -// Clear reset reason -void HAL_clear_reset_source(); +#define HAL_ADC_VREF 3.3 +#define HAL_ADC_RESOLUTION 10 +#define HAL_ADC_FILTERED // turn off ADC oversampling -// Reset reason -uint8_t HAL_get_reset_source(); +// +// Pin Mapping for M42, M43, M226 +// +#define GET_PIN_MAP_PIN(index) index +#define GET_PIN_MAP_INDEX(pin) pin +#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) -void HAL_reboot(); +// FastIO +bool is_output(pin_t pin); -FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); } +// ------------------------ +// Class Utilities +// ------------------------ #pragma GCC diagnostic push #if GCC_VERSION <= 50000 @@ -134,30 +152,65 @@ extern "C" uint32_t freeMemory(); #pragma GCC diagnostic pop -// ADC +// ------------------------ +// MarlinHAL Class +// ------------------------ -void HAL_adc_init(); +class MarlinHAL { +public: -#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 + // Earliest possible init, before setup() + MarlinHAL() {} -#define HAL_ANALOG_SELECT(pin) + static void init() {} // Called early in setup() + static void init_board() {} // Called less early in setup() + static void reboot(); // Restart the firmware from 0x0 -void HAL_adc_start_conversion(const uint8_t adc_pin); -uint16_t HAL_adc_get_result(); + // Interrupts + static bool isr_state() { return !__get_primask(); } + static void isr_on() { __enable_irq(); } + static void isr_off() { __disable_irq(); } -// PWM + static void delay_ms(const int ms) { delay(ms); } -inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); } + // Tasks, called from idle() + static void idletask() {} -// Pin Map + // Reset + static uint8_t get_reset_source(); + static void clear_reset_source(); -#define GET_PIN_MAP_PIN(index) index -#define GET_PIN_MAP_INDEX(pin) pin -#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) + // Free SRAM + static int freeMemory() { return ::freeMemory(); } -bool is_output(pin_t pin); + // + // ADC Methods + // + + static int8_t adc_select; + + // Called by Temperature::init once at startup + static void adc_init(); + + // Called by Temperature::init for each sensor at startup + static void adc_enable(const pin_t pin) {} + + // Begin ADC sampling on the given channel + static void adc_start(const pin_t pin); + + // Is the ADC ready for reading? + static bool adc_ready() { return true; } + + // The current value of the ADC register + static uint16_t adc_value(); + + /** + * Set the PWM duty cycle for the pin to the given value. + * No option to invert the duty cycle [default = false] + * No option to change the scale of the provided value to enable finer PWM duty control [default = 255] + */ + static void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { + analogWrite(pin, v); + } + +}; diff --git a/Marlin/src/HAL/TEENSY40_41/timers.h b/Marlin/src/HAL/TEENSY40_41/timers.h index 81cf67f7bc08a..77fe0953d3bd5 100644 --- a/Marlin/src/HAL/TEENSY40_41/timers.h +++ b/Marlin/src/HAL/TEENSY40_41/timers.h @@ -114,4 +114,4 @@ 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(T) +#define HAL_timer_isr_epilogue(T) NOOP diff --git a/Marlin/src/HAL/shared/HAL.cpp b/Marlin/src/HAL/shared/HAL.cpp new file mode 100644 index 0000000000000..4d92aedd9a1f5 --- /dev/null +++ b/Marlin/src/HAL/shared/HAL.cpp @@ -0,0 +1,36 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2022 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 . + * + */ + +/** + * HAL/shared/HAL.cpp + */ + +#include "../../inc/MarlinConfig.h" + +MarlinHAL hal; + +#if ENABLED(SOFT_RESET_VIA_SERIAL) + + // Global for use by e_parser.h + void HAL_reboot() { hal.reboot(); } + +#endif diff --git a/Marlin/src/HAL/shared/HAL_spi_L6470.cpp b/Marlin/src/HAL/shared/HAL_spi_L6470.cpp index bd85dbe7bd7ef..5d4ce89b2748e 100644 --- a/Marlin/src/HAL/shared/HAL_spi_L6470.cpp +++ b/Marlin/src/HAL/shared/HAL_spi_L6470.cpp @@ -92,9 +92,9 @@ uint8_t L64XX_Marlin::transfer_single(uint8_t data, int16_t ss_pin) { // First device in chain has data sent last extDigitalWrite(ss_pin, LOW); - DISABLE_ISRS(); // Disable interrupts during SPI transfer (can't allow partial command to chips) + hal.isr_off(); // Disable interrupts during SPI transfer (can't allow partial command to chips) const uint8_t data_out = L6470_SpiTransfer_Mode_3(data); - ENABLE_ISRS(); // Enable interrupts + hal.isr_on(); // Enable interrupts extDigitalWrite(ss_pin, HIGH); return data_out; @@ -107,9 +107,9 @@ uint8_t L64XX_Marlin::transfer_chain(uint8_t data, int16_t ss_pin, uint8_t chain extDigitalWrite(ss_pin, LOW); for (uint8_t i = L64XX::chain[0]; !L64xxManager.spi_abort && i >= 1; i--) { // Send data unless aborted - DISABLE_ISRS(); // Disable interrupts during SPI transfer (can't allow partial command to chips) + hal.isr_off(); // Disable interrupts during SPI transfer (can't allow partial command to chips) const uint8_t temp = L6470_SpiTransfer_Mode_3(uint8_t(i == chain_position ? data : dSPIN_NOP)); - ENABLE_ISRS(); // Enable interrupts + hal.isr_on(); // Enable interrupts if (i == chain_position) data_out = temp; } diff --git a/Marlin/src/HAL/shared/math_32bit.h b/Marlin/src/HAL/shared/math_32bit.h index 87e9e6406ee45..1fb233e3e8963 100644 --- a/Marlin/src/HAL/shared/math_32bit.h +++ b/Marlin/src/HAL/shared/math_32bit.h @@ -26,6 +26,6 @@ /** * Math helper functions for 32 bit CPUs */ -static FORCE_INLINE uint32_t MultiU32X24toH32(uint32_t longIn1, uint32_t longIn2) { +FORCE_INLINE static uint32_t MultiU32X24toH32(uint32_t longIn1, uint32_t longIn2) { return ((uint64_t)longIn1 * longIn2 + 0x00800000) >> 24; } diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 02cf6d28d3110..4117d3f382a16 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -74,7 +74,7 @@ #include "lcd/e3v2/common/encoder.h" #if ENABLED(DWIN_CREALITY_LCD) #include "lcd/e3v2/creality/dwin.h" - #elif ENABLED(DWIN_CREALITY_LCD_ENHANCED) + #elif ENABLED(DWIN_LCD_PROUI) #include "lcd/e3v2/proui/dwin.h" #elif ENABLED(DWIN_CREALITY_LCD_JYERSUI) #include "lcd/e3v2/jyersui/dwin.h" @@ -145,7 +145,7 @@ #include "feature/encoder_i2c.h" #endif -#if HAS_TRINAMIC_CONFIG && DISABLED(PSU_DEFAULT_OFF) +#if (HAS_TRINAMIC_CONFIG || HAS_TMC_SPI) && DISABLED(PSU_DEFAULT_OFF) #include "feature/tmc_util.h" #endif @@ -790,7 +790,7 @@ void idle(bool no_stepper_sleep/*=false*/) { #endif // Run HAL idle tasks - TERN_(HAL_IDLETASK, HAL_idletask()); + hal.idletask(); // Check network connection TERN_(HAS_ETHERNET, ethernet.check()); @@ -822,7 +822,7 @@ void idle(bool no_stepper_sleep/*=false*/) { TERN_(USE_BEEPER, buzzer.tick()); // Handle UI input / draw events - TERN(HAS_DWIN_E3V2_BASIC, DWIN_Update(), ui.update()); + TERN(DWIN_CREALITY_LCD, DWIN_Update(), ui.update()); // Run i2c Position Encoders #if ENABLED(I2C_POSITION_ENCODERS) @@ -878,7 +878,7 @@ void kill(FSTR_P const lcd_error/*=nullptr*/, FSTR_P const lcd_component/*=nullp // Echo the LCD message to serial for extra context if (lcd_error) { SERIAL_ECHO_START(); SERIAL_ECHOLNF(lcd_error); } - #if EITHER(HAS_DISPLAY, DWIN_CREALITY_LCD_ENHANCED) + #if EITHER(HAS_DISPLAY, DWIN_LCD_PROUI) ui.kill_screen(lcd_error ?: GET_TEXT_F(MSG_KILLED), lcd_component ?: FPSTR(NUL_STR)); #else UNUSED(lcd_error); UNUSED(lcd_component); @@ -929,7 +929,7 @@ void minkill(const bool steppers_off/*=false*/) { watchdog_refresh(); // Reboot the board - HAL_reboot(); + hal.reboot(); #else @@ -1041,7 +1041,7 @@ inline void tmc_standby_setup() { * • L64XX Stepper Drivers (SPI) * • Stepper Driver Reset: DISABLE * • TMC Stepper Drivers (SPI) - * • Run BOARD_INIT if defined + * • Run hal.init_board() for additional pins setup * • ESP WiFi * - Get the Reset Reason and report it * - Print startup messages and diagnostics @@ -1119,8 +1119,8 @@ void setup() { tmc_standby_setup(); // TMC Low Power Standby pins must be set early or they're not usable // Check startup - does nothing if bootloader sets MCUSR to 0 - const byte mcu = HAL_get_reset_source(); - HAL_clear_reset_source(); + const byte mcu = hal.get_reset_source(); + hal.clear_reset_source(); #if ENABLED(MARLIN_DEV_MODE) auto log_current_ms = [&](PGM_P const msg) { @@ -1181,23 +1181,20 @@ void setup() { JTAGSWD_RESET(); #endif - #if EITHER(DISABLE_DEBUG, DISABLE_JTAG) + // Disable any hardware debug to free up pins for IO + #if ENABLED(DISABLE_DEBUG) && defined(JTAGSWD_DISABLE) delay(10); - // Disable any hardware debug to free up pins for IO - #if ENABLED(DISABLE_DEBUG) && defined(JTAGSWD_DISABLE) - SETUP_LOG("JTAGSWD_DISABLE"); - JTAGSWD_DISABLE(); - #elif defined(JTAG_DISABLE) - SETUP_LOG("JTAG_DISABLE"); - JTAG_DISABLE(); - #else - #error "DISABLE_(DEBUG|JTAG) is not supported for the selected MCU/Board." - #endif + SETUP_LOG("JTAGSWD_DISABLE"); + JTAGSWD_DISABLE(); + #elif ENABLED(DISABLE_JTAG) && defined(JTAG_DISABLE) + delay(10); + SETUP_LOG("JTAG_DISABLE"); + JTAG_DISABLE(); #endif TERN_(DYNAMIC_VECTORTABLE, hook_cpu_exceptions()); // If supported, install Marlin exception handlers at runtime - SETUP_RUN(HAL_init()); + SETUP_RUN(hal.init()); // Init and disable SPI thermocouples; this is still needed #if TEMP_SENSOR_0_IS_MAX_TC || (TEMP_SENSOR_REDUNDANT_IS_MAX_TC && REDUNDANT_TEMP_MATCH(SOURCE, E0)) @@ -1243,19 +1240,16 @@ void setup() { SETUP_RUN(tmc_init_cs_pins()); #endif - #ifdef BOARD_INIT - SETUP_LOG("BOARD_INIT"); - BOARD_INIT(); - #endif + SETUP_RUN(hal.init_board()); SETUP_RUN(esp_wifi_init()); // Report Reset Reason - if (mcu & RST_POWER_ON) SERIAL_ECHOLNPGM(STR_POWERUP); - if (mcu & RST_EXTERNAL) SERIAL_ECHOLNPGM(STR_EXTERNAL_RESET); + if (mcu & RST_POWER_ON) SERIAL_ECHOLNPGM(STR_POWERUP); + if (mcu & RST_EXTERNAL) SERIAL_ECHOLNPGM(STR_EXTERNAL_RESET); if (mcu & RST_BROWN_OUT) SERIAL_ECHOLNPGM(STR_BROWNOUT_RESET); - if (mcu & RST_WATCHDOG) SERIAL_ECHOLNPGM(STR_WATCHDOG_RESET); - if (mcu & RST_SOFTWARE) SERIAL_ECHOLNPGM(STR_SOFTWARE_RESET); + if (mcu & RST_WATCHDOG) SERIAL_ECHOLNPGM(STR_WATCHDOG_RESET); + if (mcu & RST_SOFTWARE) SERIAL_ECHOLNPGM(STR_SOFTWARE_RESET); // Identify myself as Marlin x.x.x SERIAL_ECHOLNPGM("Marlin " SHORT_BUILD_VERSION); @@ -1266,7 +1260,7 @@ void setup() { ); #endif SERIAL_ECHO_MSG(" Compiled: " __DATE__); - SERIAL_ECHO_MSG(STR_FREE_MEMORY, freeMemory(), STR_PLANNER_BUFFER_BYTES, sizeof(block_t) * (BLOCK_BUFFER_SIZE)); + SERIAL_ECHO_MSG(STR_FREE_MEMORY, hal.freeMemory(), STR_PLANNER_BUFFER_BYTES, sizeof(block_t) * (BLOCK_BUFFER_SIZE)); // Some HAL need precise delay adjustment calibrate_delay_loop(); @@ -1542,7 +1536,7 @@ void setup() { #endif #if ENABLED(USE_WATCHDOG) - SETUP_RUN(watchdog_init()); // Reinit watchdog after HAL_get_reset_source call + SETUP_RUN(watchdog_init()); // Reinit watchdog after hal.get_reset_source call #endif #if ENABLED(EXTERNAL_CLOSED_LOOP_CONTROLLER) @@ -1577,11 +1571,7 @@ void setup() { #endif #if HAS_DWIN_E3V2_BASIC - SETUP_LOG("E3V2 Init"); - Encoder_Configuration(); - HMI_Init(); - HMI_SetLanguageCache(); - HMI_StartFrame(true); + SETUP_RUN(DWIN_InitScreen()); #endif #if HAS_SERVICE_INTERVALS && !HAS_DWIN_E3V2_BASIC diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index 21c0eaaf30459..3ec24e7760229 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -116,6 +116,7 @@ #define BOARD_LONGER3D_LK1_PRO 1160 // Longer LK1 PRO / Alfawise U20 Pro (PRO version) #define BOARD_LONGER3D_LKx_PRO 1161 // Longer LKx PRO / Alfawise Uxx Pro (PRO version) #define BOARD_ZRIB_V53 1162 // Zonestar zrib V5.3 (Chinese RAMPS replica) +#define BOARD_PXMALION_CORE_I3 1163 // Pxmalion Core I3 // // RAMBo and derivatives @@ -163,6 +164,7 @@ #define BOARD_MALYAN_M180 1327 // Malyan M180 Mainboard Version 2 (no display function, direct gcode only) #define BOARD_GT2560_V4_A20 1328 // Geeetech GT2560 Rev B for A20(M/T/D) #define BOARD_PROTONEER_CNC_SHIELD_V3 1329 // Mega controller & Protoneer CNC Shield V3.00 +#define BOARD_WEEDO_62A 1330 // WEEDO 62A board (TINA2, Monoprice Cadet, etc.) // // ATmega1281, ATmega2561 @@ -403,16 +405,17 @@ #define BOARD_MKS_ROBIN2 4226 // MKS_ROBIN2 (STM32F407ZE) #define BOARD_MKS_ROBIN_PRO_V2 4227 // MKS Robin Pro V2 (STM32F407VE) #define BOARD_MKS_ROBIN_NANO_V3 4228 // MKS Robin Nano V3 (STM32F407VG) -#define BOARD_MKS_MONSTER8 4229 // MKS Monster8 (STM32F407VG) -#define BOARD_ANET_ET4 4230 // ANET ET4 V1.x (STM32F407VG) -#define BOARD_ANET_ET4P 4231 // ANET ET4P V1.x (STM32F407VG) -#define BOARD_FYSETC_CHEETAH_V20 4232 // FYSETC Cheetah V2.0 -#define BOARD_TH3D_EZBOARD_V2 4233 // TH3D EZBoard v2.0 -#define BOARD_INDEX_REV03 4234 // Index PnP Controller REV03 (STM32F407VE/VG) -#define BOARD_MKS_ROBIN_NANO_V1_3_F4 4235 // MKS Robin Nano V1.3 and MKS Robin Nano-S V1.3 (STM32F407VE) -#define BOARD_MKS_EAGLE 4236 // MKS Eagle (STM32F407VE) -#define BOARD_ARTILLERY_RUBY 4237 // Artillery Ruby (STM32F401RC) -#define BOARD_FYSETC_SPIDER_V2_2 4238 // FYSETC Spider V2.2 (STM32F446VE) +#define BOARD_MKS_ROBIN_NANO_V3_1 4229 // MKS Robin Nano V3.1 (STM32F407VE) +#define BOARD_MKS_MONSTER8 4230 // MKS Monster8 (STM32F407VG) +#define BOARD_ANET_ET4 4231 // ANET ET4 V1.x (STM32F407VG) +#define BOARD_ANET_ET4P 4232 // ANET ET4P V1.x (STM32F407VG) +#define BOARD_FYSETC_CHEETAH_V20 4233 // FYSETC Cheetah V2.0 +#define BOARD_TH3D_EZBOARD_V2 4234 // TH3D EZBoard v2.0 +#define BOARD_INDEX_REV03 4235 // Index PnP Controller REV03 (STM32F407VE/VG) +#define BOARD_MKS_ROBIN_NANO_V1_3_F4 4236 // MKS Robin Nano V1.3 and MKS Robin Nano-S V1.3 (STM32F407VE) +#define BOARD_MKS_EAGLE 4237 // MKS Eagle (STM32F407VE) +#define BOARD_ARTILLERY_RUBY 4238 // Artillery Ruby (STM32F401RC) +#define BOARD_FYSETC_SPIDER_V2_2 4239 // FYSETC Spider V2.2 (STM32F446VE) // // ARM Cortex M7 diff --git a/Marlin/src/core/drivers.h b/Marlin/src/core/drivers.h index 0a76410274bb7..2e66cc920119f 100644 --- a/Marlin/src/core/drivers.h +++ b/Marlin/src/core/drivers.h @@ -128,7 +128,7 @@ // Test for a driver that uses SPI - this allows checking whether a _CS_ pin // is considered sensitive #define AXIS_HAS_SPI(A) ( AXIS_DRIVER_TYPE(A,TMC2130) || AXIS_DRIVER_TYPE(A,TMC2160) \ - || AXIS_DRIVER_TYPE(A,TMC2660) \ + || AXIS_DRIVER_TYPE(A,TMC26X) || AXIS_DRIVER_TYPE(A,TMC2660) \ || AXIS_DRIVER_TYPE(A,TMC5130) || AXIS_DRIVER_TYPE(A,TMC5160) ) #define AXIS_HAS_UART(A) ( AXIS_DRIVER_TYPE(A,TMC2208) || AXIS_DRIVER_TYPE(A,TMC2209) ) diff --git a/Marlin/src/core/serial.cpp b/Marlin/src/core/serial.cpp index 2b1ae1f1fe006..562cddbaa07a5 100644 --- a/Marlin/src/core/serial.cpp +++ b/Marlin/src/core/serial.cpp @@ -78,6 +78,14 @@ void serial_error_start() { static PGMSTR(errormagic, "Error:"); serial_print_P( void serial_spaces(uint8_t count) { count *= (PROPORTIONAL_FONT_RATIO); while (count--) SERIAL_CHAR(' '); } +void serial_offset(const_float_t v, const uint8_t sp/*=0*/) { + if (v == 0 && sp == 1) + SERIAL_CHAR(' '); + else if (v > 0 || (v == 0 && sp == 2)) + SERIAL_CHAR('+'); + SERIAL_DECIMAL(v); +} + void serial_ternary(const bool onoff, FSTR_P const pre, FSTR_P const on, FSTR_P const off, FSTR_P const post/*=nullptr*/) { if (pre) serial_print(pre); serial_print(onoff ? on : off); diff --git a/Marlin/src/core/serial.h b/Marlin/src/core/serial.h index aee4d4d43db8f..98e82b6d7281b 100644 --- a/Marlin/src/core/serial.h +++ b/Marlin/src/core/serial.h @@ -345,6 +345,7 @@ void serialprint_onoff(const bool onoff); void serialprintln_onoff(const bool onoff); void serialprint_truefalse(const bool tf); void serial_spaces(uint8_t count); +void serial_offset(const_float_t v, const uint8_t sp=0); // For v==0 draw space (sp==1) or plus (sp==2) void print_bin(const uint16_t val); void print_pos(LINEAR_AXIS_ARGS(const_float_t), FSTR_P const prefix=nullptr, FSTR_P const suffix=nullptr); diff --git a/Marlin/src/core/types.h b/Marlin/src/core/types.h index aee25a0dfff44..b95b59565920e 100644 --- a/Marlin/src/core/types.h +++ b/Marlin/src/core/types.h @@ -536,19 +536,9 @@ struct XYZEval { // Reset all to 0 FI void reset() { LOGICAL_AXIS_GANG(e =, x =, y =, z =, i =, j =, k =) 0; } - // Setters taking struct types and arrays - FI void set(const T px) { x = px; } - FI void set(const T px, const T py) { x = px; y = py; } - FI void set(const XYval pxy) { x = pxy.x; y = pxy.y; } - FI void set(const XYZval pxyz) { set(LINEAR_AXIS_ELEM(pxyz)); } - #if HAS_Z_AXIS - FI void set(LINEAR_AXIS_ARGS(const T)) { LINEAR_AXIS_CODE(a = x, b = y, c = z, u = i, v = j, w = k); } - #endif - #if LOGICAL_AXES > LINEAR_AXES - FI void set(const XYval pxy, const T pe) { set(pxy); e = pe; } - FI void set(const XYZval pxyz, const T pe) { set(pxyz); e = pe; } - FI void set(LOGICAL_AXIS_ARGS(const T)) { LOGICAL_AXIS_CODE(_e = e, a = x, b = y, c = z, u = i, v = j, w = k); } - #endif + // Setters for some number of linear axes, not all + FI void set(const T px) { x = px; } + FI void set(const T px, const T py) { x = px; y = py; } #if HAS_I_AXIS FI void set(const T px, const T py, const T pz) { x = px; y = py; z = pz; } #endif @@ -558,6 +548,18 @@ struct XYZEval { #if HAS_K_AXIS FI void set(const T px, const T py, const T pz, const T pi, const T pj) { x = px; y = py; z = pz; i = pi; j = pj; } #endif + // Setters taking struct types and arrays + FI void set(const XYval pxy) { x = pxy.x; y = pxy.y; } + FI void set(const XYZval pxyz) { set(LINEAR_AXIS_ELEM(pxyz)); } + #if HAS_Z_AXIS + FI void set(LINEAR_AXIS_ARGS(const T)) { LINEAR_AXIS_CODE(a = x, b = y, c = z, u = i, v = j, w = k); } + #endif + FI void set(const XYval pxy, const T pz) { set(pxy); TERN_(HAS_Z_AXIS, z = pz); } + #if LOGICAL_AXES > LINEAR_AXES + FI void set(const XYval pxy, const T pz, const T pe) { set(pxy, pz); e = pe; } + FI void set(const XYZval pxyz, const T pe) { set(pxyz); e = pe; } + FI void set(LOGICAL_AXIS_ARGS(const T)) { LOGICAL_AXIS_CODE(_e = e, a = x, b = y, c = z, u = i, v = j, w = k); } + #endif // Length reduced to one dimension FI T magnitude() const { return (T)sqrtf(LOGICAL_AXIS_GANG(+ e*e, + x*x, + y*y, + z*z, + i*i, + j*j, + k*k)); } diff --git a/Marlin/src/core/utility.cpp b/Marlin/src/core/utility.cpp index 19e76267447d3..59e59d4cb7ff5 100644 --- a/Marlin/src/core/utility.cpp +++ b/Marlin/src/core/utility.cpp @@ -126,10 +126,8 @@ void safe_delay(millis_t ms) { #if ABL_PLANAR SERIAL_ECHOPGM("ABL Adjustment"); LOOP_LINEAR_AXES(a) { - const float v = planner.get_axis_position_mm(AxisEnum(a)) - current_position[a]; SERIAL_CHAR(' ', AXIS_CHAR(a)); - if (v > 0) SERIAL_CHAR('+'); - SERIAL_DECIMAL(v); + serial_offset(planner.get_axis_position_mm(AxisEnum(a)) - current_position[a]); } #else #if ENABLED(AUTO_BED_LEVELING_UBL) diff --git a/Marlin/src/feature/backlash.cpp b/Marlin/src/feature/backlash.cpp index 24c0f2ca0c159..84382cf85680b 100644 --- a/Marlin/src/feature/backlash.cpp +++ b/Marlin/src/feature/backlash.cpp @@ -29,6 +29,9 @@ #include "../module/motion.h" #include "../module/planner.h" +axis_bits_t Backlash::last_direction_bits; +xyz_long_t Backlash::residual_error{0}; + #ifdef BACKLASH_DISTANCE_MM #if ENABLED(BACKLASH_GCODE) xyz_float_t Backlash::distance_mm = BACKLASH_DISTANCE_MM; @@ -38,7 +41,7 @@ #endif #if ENABLED(BACKLASH_GCODE) - uint8_t Backlash::correction = (BACKLASH_CORRECTION) * 0xFF; + uint8_t Backlash::correction = (BACKLASH_CORRECTION) * all_on; #ifdef BACKLASH_SMOOTHING_MM float Backlash::smoothing_mm = BACKLASH_SMOOTHING_MM; #endif @@ -61,7 +64,6 @@ Backlash backlash; */ void Backlash::add_correction_steps(const int32_t &da, const int32_t &db, const int32_t &dc, const axis_bits_t dm, block_t * const block) { - static axis_bits_t last_direction_bits; axis_bits_t changed_dir = last_direction_bits ^ dm; // Ignore direction change unless steps are taken in that direction #if DISABLED(CORE_BACKLASH) || EITHER(MARKFORGED_XY, MARKFORGED_YX) @@ -83,7 +85,7 @@ void Backlash::add_correction_steps(const int32_t &da, const int32_t &db, const #endif last_direction_bits ^= changed_dir; - if (correction == 0) return; + if (!correction && !residual_error) return; #ifdef BACKLASH_SMOOTHING_MM // The segment proportion is a value greater than 0.0 indicating how much residual_error @@ -91,39 +93,28 @@ void Backlash::add_correction_steps(const int32_t &da, const int32_t &db, const // smoothing distance. Since the computation of this proportion involves a floating point // division, defer computation until needed. float segment_proportion = 0; - - // Residual error carried forward across multiple segments, so correction can be applied - // to segments where there is no direction change. - static xyz_long_t residual_error{0}; - #else - // No direction change, no correction. - if (!changed_dir) return; - // No leftover residual error from segment to segment - xyz_long_t residual_error{0}; #endif - const float f_corr = float(correction) / 255.0f; + const float f_corr = float(correction) / all_on; LOOP_LINEAR_AXES(axis) { if (distance_mm[axis]) { - const bool reversing = TEST(dm,axis); + const bool reverse = TEST(dm, axis); // When an axis changes direction, add axis backlash to the residual error if (TEST(changed_dir, axis)) - residual_error[axis] += (reversing ? -f_corr : f_corr) * distance_mm[axis] * planner.settings.axis_steps_per_mm[axis]; + residual_error[axis] += (reverse ? -f_corr : f_corr) * distance_mm[axis] * planner.settings.axis_steps_per_mm[axis]; // Decide how much of the residual error to correct in this segment int32_t error_correction = residual_error[axis]; + if (reverse != (error_correction < 0)) + error_correction = 0; // Don't take up any backlash in this segment, as it would subtract steps + #ifdef BACKLASH_SMOOTHING_MM if (error_correction && smoothing_mm != 0) { - // Take up a portion of the residual_error in this segment, but only when - // the current segment travels in the same direction as the correction - if (reversing == (error_correction < 0)) { - if (segment_proportion == 0) segment_proportion = _MIN(1.0f, block->millimeters / smoothing_mm); - error_correction = CEIL(segment_proportion * error_correction); - } - else - error_correction = 0; // Don't take up any backlash in this segment, as it would subtract steps + // Take up a portion of the residual_error in this segment + if (segment_proportion == 0) segment_proportion = _MIN(1.0f, block->millimeters / smoothing_mm); + error_correction = CEIL(segment_proportion * error_correction); } #endif @@ -153,6 +144,52 @@ void Backlash::add_correction_steps(const int32_t &da, const int32_t &db, const } } +int32_t Backlash::get_applied_steps(const AxisEnum axis) { + if (axis >= LINEAR_AXES) return 0; + + const bool reverse = TEST(last_direction_bits, axis); + + const int32_t residual_error_axis = residual_error[axis]; + + // At startup it is assumed the last move was forwards. So the applied + // steps will always be a non-positive number. + + if (!reverse) return -residual_error_axis; + + const float f_corr = float(correction) / all_on; + const int32_t full_error_axis = -f_corr * distance_mm[axis] * planner.settings.axis_steps_per_mm[axis]; + return full_error_axis - residual_error_axis; +} + +class Backlash::StepAdjuster { + xyz_long_t applied_steps; +public: + StepAdjuster() { + LOOP_LINEAR_AXES(axis) applied_steps[axis] = backlash.get_applied_steps((AxisEnum)axis); + } + ~StepAdjuster() { + // after backlash compensation parameter changes, ensure applied step count does not change + LOOP_LINEAR_AXES(axis) residual_error[axis] += backlash.get_applied_steps((AxisEnum)axis) - applied_steps[axis]; + } +}; + +void Backlash::set_correction_uint8(const uint8_t v) { + StepAdjuster adjuster; + correction = v; +} + +void Backlash::set_distance_mm(const AxisEnum axis, const float v) { + StepAdjuster adjuster; + distance_mm[axis] = v; +} + +#ifdef BACKLASH_SMOOTHING_MM + void Backlash::set_smoothing_mm(const float v) { + StepAdjuster adjuster; + smoothing_mm = v; + } +#endif + #if ENABLED(MEASURE_BACKLASH_WHEN_PROBING) #include "../module/probe.h" diff --git a/Marlin/src/feature/backlash.h b/Marlin/src/feature/backlash.h index 17504cc781819..0bace526e53f4 100644 --- a/Marlin/src/feature/backlash.h +++ b/Marlin/src/feature/backlash.h @@ -24,21 +24,22 @@ #include "../inc/MarlinConfigPre.h" #include "../module/planner.h" -constexpr uint8_t all_on = 0xFF, all_off = 0x00; - class Backlash { public: + static constexpr uint8_t all_on = 0xFF, all_off = 0x00; + +private: + static axis_bits_t last_direction_bits; + static xyz_long_t residual_error; + #if ENABLED(BACKLASH_GCODE) - static xyz_float_t distance_mm; static uint8_t correction; + static xyz_float_t distance_mm; #ifdef BACKLASH_SMOOTHING_MM static float smoothing_mm; #endif - - static void set_correction(const_float_t v) { correction = _MAX(0, _MIN(1.0, v)) * all_on; } - static float get_correction() { return float(ui8_to_percent(correction)) / 100.0f; } #else - static constexpr uint8_t correction = (BACKLASH_CORRECTION) * 0xFF; + static constexpr uint8_t correction = (BACKLASH_CORRECTION) * all_on; static const xyz_float_t distance_mm; #ifdef BACKLASH_SMOOTHING_MM static constexpr float smoothing_mm = BACKLASH_SMOOTHING_MM; @@ -46,13 +47,13 @@ class Backlash { #endif #if ENABLED(MEASURE_BACKLASH_WHEN_PROBING) - private: - static xyz_float_t measured_mm; - static xyz_uint8_t measured_count; - public: - static void measure_with_probe(); + static xyz_float_t measured_mm; + static xyz_uint8_t measured_count; #endif + class StepAdjuster; + +public: static float get_measurement(const AxisEnum a) { UNUSED(a); // Return the measurement averaged over all readings @@ -71,7 +72,25 @@ class Backlash { return has_measurement(X_AXIS) || has_measurement(Y_AXIS) || has_measurement(Z_AXIS); } - void add_correction_steps(const int32_t &da, const int32_t &db, const int32_t &dc, const axis_bits_t dm, block_t * const block); + static void add_correction_steps(const int32_t &da, const int32_t &db, const int32_t &dc, const axis_bits_t dm, block_t * const block); + static int32_t get_applied_steps(const AxisEnum axis); + + #if ENABLED(BACKLASH_GCODE) + static void set_correction_uint8(const uint8_t v); + static uint8_t get_correction_uint8() { return correction; } + static void set_correction(const float v) { set_correction_uint8(_MAX(0, _MIN(1.0, v)) * all_on + 0.5f); } + static float get_correction() { return float(get_correction_uint8()) / all_on; } + static void set_distance_mm(const AxisEnum axis, const float v); + static float get_distance_mm(const AxisEnum axis) {return distance_mm[axis];} + #ifdef BACKLASH_SMOOTHING_MM + static void set_smoothing_mm(const float v); + static float get_smoothing_mm() {return smoothing_mm;} + #endif + #endif + + #if ENABLED(MEASURE_BACKLASH_WHEN_PROBING) + static void measure_with_probe(); + #endif }; extern Backlash backlash; diff --git a/Marlin/src/feature/bedlevel/bedlevel.h b/Marlin/src/feature/bedlevel/bedlevel.h index c623c99b5c521..63f032eee87bc 100644 --- a/Marlin/src/feature/bedlevel/bedlevel.h +++ b/Marlin/src/feature/bedlevel/bedlevel.h @@ -63,9 +63,6 @@ class TemporaryBedLevelingState { #if ENABLED(AUTO_BED_LEVELING_BILINEAR) #include "abl/abl.h" - #if ENABLED(X_AXIS_TWIST_COMPENSATION) - #include "abl/x_twist.h" - #endif #elif ENABLED(AUTO_BED_LEVELING_UBL) #include "ubl/ubl.h" #elif ENABLED(MESH_BED_LEVELING) diff --git a/Marlin/src/feature/bedlevel/ubl/ubl.cpp b/Marlin/src/feature/bedlevel/ubl/ubl.cpp index 964f1123fe421..c162062f8609c 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl.cpp @@ -213,8 +213,8 @@ void unified_bed_leveling::display_map(const uint8_t map_type) { else if (isnan(f)) SERIAL_ECHOF(human ? F(" . ") : F("NAN")); else if (human || csv) { - if (human && f >= 0.0) SERIAL_CHAR(f > 0 ? '+' : ' '); // Display sign also for positive numbers (' ' for 0) - SERIAL_ECHO_F(f, 3); // Positive: 5 digits, Negative: 6 digits + if (human && f >= 0) SERIAL_CHAR(f > 0 ? '+' : ' '); // Display sign also for positive numbers (' ' for 0) + SERIAL_DECIMAL(f); // Positive: 5 digits, Negative: 6 digits } if (csv && i < (GRID_MAX_POINTS_X) - 1) SERIAL_CHAR('\t'); diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index 15395bcc8d587..0d00296b5b605 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -316,7 +316,7 @@ void unified_bed_leveling::G29() { planner.synchronize(); // Send 'N' to force homing before G29 (internal only) if (axes_should_home() || parser.seen_test('N')) gcode.home_all_axes(); - TERN_(HAS_MULTI_HOTEND, if (active_extruder) tool_change(0)); + TERN_(HAS_MULTI_HOTEND, if (active_extruder != 0) tool_change(0, true)); } // Invalidate one or more nearby mesh points, possibly all. @@ -367,13 +367,13 @@ void unified_bed_leveling::G29() { case 1: LOOP_L_N(x, GRID_MAX_POINTS_X) { // Create a diagonal line several Mesh cells thick that is raised + const uint8_t x2 = x + (x < (GRID_MAX_POINTS_Y) - 1 ? 1 : -1); z_values[x][x] += 9.999f; - z_values[x][x + (x < (GRID_MAX_POINTS_Y) - 1) ? 1 : -1] += 9.999f; // We want the altered line several mesh points thick + z_values[x][x2] += 9.999f; // We want the altered line several mesh points thick #if ENABLED(EXTENSIBLE_UI) ExtUI::onMeshUpdate(x, x, z_values[x][x]); - ExtUI::onMeshUpdate(x, (x + (x < (GRID_MAX_POINTS_Y) - 1) ? 1 : -1), z_values[x][x + (x < (GRID_MAX_POINTS_Y) - 1) ? 1 : -1]); + ExtUI::onMeshUpdate(x, (x2), z_values[x][x2]); #endif - } break; @@ -663,7 +663,7 @@ void unified_bed_leveling::G29() { UNUSED(probe_deployed); #endif - TERN_(HAS_MULTI_HOTEND, tool_change(old_tool_index)); + TERN_(HAS_MULTI_HOTEND, if (old_tool_index != 0) tool_change(old_tool_index)); return; } @@ -1219,6 +1219,7 @@ void unified_bed_leveling::restore_ubl_active_state_and_leave() { } #endif set_bed_leveling_enabled(ubl_state_at_invocation); + TERN_(EXTENSIBLE_UI, ExtUI::onLevelingDone()); } mesh_index_pair unified_bed_leveling::find_furthest_invalid_mesh_point() { diff --git a/Marlin/src/feature/caselight.cpp b/Marlin/src/feature/caselight.cpp index 57b2d0f83c617..eb580a6d62697 100644 --- a/Marlin/src/feature/caselight.cpp +++ b/Marlin/src/feature/caselight.cpp @@ -79,7 +79,7 @@ void CaseLight::update(const bool sflag) { #if CASELIGHT_USES_BRIGHTNESS if (pin_is_pwm()) - set_pwm_duty(pin_t(CASE_LIGHT_PIN), ( + hal.set_pwm_duty(pin_t(CASE_LIGHT_PIN), ( #if CASE_LIGHT_MAX_PWM == 255 n10ct #else diff --git a/Marlin/src/feature/controllerfan.cpp b/Marlin/src/feature/controllerfan.cpp index 59ba665e11144..f42bf52ae40a0 100644 --- a/Marlin/src/feature/controllerfan.cpp +++ b/Marlin/src/feature/controllerfan.cpp @@ -76,7 +76,7 @@ void ControllerFan::update() { thermalManager.soft_pwm_controller_speed = speed; #else if (PWM_PIN(CONTROLLER_FAN_PIN)) - set_pwm_duty(pin_t(CONTROLLER_FAN_PIN), speed); + hal.set_pwm_duty(pin_t(CONTROLLER_FAN_PIN), speed); else WRITE(CONTROLLER_FAN_PIN, speed > 0); #endif diff --git a/Marlin/src/feature/e_parser.h b/Marlin/src/feature/e_parser.h index 1dee0cf7550c1..fda1ba144bc4d 100644 --- a/Marlin/src/feature/e_parser.h +++ b/Marlin/src/feature/e_parser.h @@ -41,7 +41,9 @@ extern bool wait_for_user, wait_for_heatup; void quickresume_stepper(); #endif -void HAL_reboot(); +#if ENABLED(SOFT_RESET_VIA_SERIAL) + void HAL_reboot(); +#endif class EmergencyParser { diff --git a/Marlin/src/feature/host_actions.cpp b/Marlin/src/feature/host_actions.cpp index be7b055b55f7e..c03a6bc5976e6 100644 --- a/Marlin/src/feature/host_actions.cpp +++ b/Marlin/src/feature/host_actions.cpp @@ -39,10 +39,7 @@ HostUI hostui; -flag_t HostUI::flag; - void HostUI::action(FSTR_P const fstr, const bool eol) { - if (!flag.bits) return; PORT_REDIRECT(SerialMask::All); SERIAL_ECHOPGM("//action:"); SERIAL_ECHOF(fstr); @@ -96,21 +93,18 @@ void HostUI::action(FSTR_P const fstr, const bool eol) { #endif void HostUI::notify(const char * const cstr) { - if (!flag.bits) return; PORT_REDIRECT(SerialMask::All); action(F("notification "), false); SERIAL_ECHOLN(cstr); } void HostUI::notify_P(PGM_P const pstr) { - if (!flag.bits) return; PORT_REDIRECT(SerialMask::All); action(F("notification "), false); SERIAL_ECHOLNPGM_P(pstr); } void HostUI::prompt(FSTR_P const ptype, const bool eol/*=true*/) { - if (!flag.bits) return; PORT_REDIRECT(SerialMask::All); action(F("prompt_"), false); SERIAL_ECHOF(ptype); @@ -118,7 +112,6 @@ void HostUI::action(FSTR_P const fstr, const bool eol) { } void HostUI::prompt_plus(FSTR_P const ptype, FSTR_P const fstr, const char extra_char/*='\0'*/) { - if (!flag.bits) return; prompt(ptype, false); PORT_REDIRECT(SerialMask::All); SERIAL_CHAR(' '); @@ -127,7 +120,6 @@ void HostUI::action(FSTR_P const fstr, const bool eol) { SERIAL_EOL(); } void HostUI::prompt_begin(const PromptReason reason, FSTR_P const fstr, const char extra_char/*='\0'*/) { - if (!flag.bits) return; prompt_end(); host_prompt_reason = reason; prompt_plus(F("begin"), fstr, extra_char); diff --git a/Marlin/src/feature/host_actions.h b/Marlin/src/feature/host_actions.h index 78a7821eba856..41d66b82ec9ba 100644 --- a/Marlin/src/feature/host_actions.h +++ b/Marlin/src/feature/host_actions.h @@ -24,11 +24,6 @@ #include "../inc/MarlinConfigPre.h" #include "../HAL/shared/Marduino.h" -typedef union { - uint8_t bits; - struct { bool info:1, errors:1, debug:1; }; -} flag_t; - #if ENABLED(HOST_PROMPT_SUPPORT) enum PromptReason : uint8_t { @@ -45,9 +40,6 @@ typedef union { class HostUI { public: - static flag_t flag; - HostUI() { flag.bits = 0xFF; } - static void action(FSTR_P const fstr, const bool eol=true); #ifdef ACTION_ON_KILL diff --git a/Marlin/src/feature/leds/leds.cpp b/Marlin/src/feature/leds/leds.cpp index 715f51f442c8f..2a53a7c884e64 100644 --- a/Marlin/src/feature/leds/leds.cpp +++ b/Marlin/src/feature/leds/leds.cpp @@ -129,11 +129,11 @@ void LEDLights::set_color(const LEDColor &incol // This variant uses 3-4 separate pins for the RGB(W) components. // If the pins can do PWM then their intensity will be set. - #define _UPDATE_RGBW(C,c) do { \ - if (PWM_PIN(RGB_LED_##C##_PIN)) \ - set_pwm_duty(pin_t(RGB_LED_##C##_PIN), c); \ - else \ - WRITE(RGB_LED_##C##_PIN, c ? HIGH : LOW); \ + #define _UPDATE_RGBW(C,c) do { \ + if (PWM_PIN(RGB_LED_##C##_PIN)) \ + hal.set_pwm_duty(pin_t(RGB_LED_##C##_PIN), c); \ + else \ + WRITE(RGB_LED_##C##_PIN, c ? HIGH : LOW); \ }while(0) #define UPDATE_RGBW(C,c) _UPDATE_RGBW(C, TERN1(CASE_LIGHT_USE_RGB_LED, caselight.on) ? incol.c : 0) UPDATE_RGBW(R,r); UPDATE_RGBW(G,g); UPDATE_RGBW(B,b); diff --git a/Marlin/src/feature/mixing.cpp b/Marlin/src/feature/mixing.cpp index 9ebc90127f43f..b1a069e3205e4 100644 --- a/Marlin/src/feature/mixing.cpp +++ b/Marlin/src/feature/mixing.cpp @@ -63,7 +63,7 @@ void Mixer::normalize(const uint8_t tool_index) { #ifdef MIXER_NORMALIZER_DEBUG SERIAL_ECHOPGM("Mixer: Old relation : [ "); MIXER_STEPPER_LOOP(i) { - SERIAL_ECHO_F(collector[i] / csum, 3); + SERIAL_DECIMAL(collector[i] / csum); SERIAL_CHAR(' '); } SERIAL_ECHOLNPGM("]"); diff --git a/Marlin/src/feature/mmu/mmu2.cpp b/Marlin/src/feature/mmu/mmu2.cpp index 2813337c635b8..28dea681ef473 100644 --- a/Marlin/src/feature/mmu/mmu2.cpp +++ b/Marlin/src/feature/mmu/mmu2.cpp @@ -143,6 +143,8 @@ uint8_t MMU2::get_current_tool() { #define FILAMENT_PRESENT() (READ(FIL_RUNOUT1_PIN) != FIL_RUNOUT1_STATE) #endif +inline void ATTN_BUZZ(const bool two=false) { BUZZ(200, 404); if (two) { BUZZ(10, 0); BUZZ(200, 404); } } + void MMU2::mmu_loop() { switch (state) { @@ -525,7 +527,7 @@ static void mmu2_not_responding() { while (!thermalManager.wait_for_hotend(active_extruder, false)) safe_delay(100); load_filament_to_nozzle(index); #else - BUZZ(400, 40); + ERR_BUZZ(); #endif } break; @@ -544,7 +546,7 @@ static void mmu2_not_responding() { active_extruder = 0; } #else - BUZZ(400, 40); + ERR_BUZZ(); #endif } break; @@ -613,7 +615,7 @@ static void mmu2_not_responding() { while (!thermalManager.wait_for_hotend(active_extruder, false)) safe_delay(100); load_filament_to_nozzle(index); #else - BUZZ(400, 40); + ERR_BUZZ(); #endif } break; @@ -633,7 +635,7 @@ static void mmu2_not_responding() { extruder = index; active_extruder = 0; #else - BUZZ(400, 40); + ERR_BUZZ(); #endif } break; @@ -707,7 +709,7 @@ static void mmu2_not_responding() { while (!thermalManager.wait_for_hotend(active_extruder, false)) safe_delay(100); load_filament_to_nozzle(index); #else - BUZZ(400, 40); + ERR_BUZZ(); #endif } break; @@ -726,7 +728,7 @@ static void mmu2_not_responding() { extruder = index; active_extruder = 0; #else - BUZZ(400, 40); + ERR_BUZZ(); #endif } break; @@ -811,25 +813,21 @@ void MMU2::manage_response(const bool move_axes, const bool turn_off_nozzle) { if (turn_off_nozzle && resume_hotend_temp) { thermalManager.setTargetHotend(resume_hotend_temp, active_extruder); LCD_MESSAGE(MSG_HEATING); - BUZZ(200, 40); + ERR_BUZZ(); while (!thermalManager.wait_for_hotend(active_extruder, false)) safe_delay(1000); } - if (move_axes && all_axes_homed()) { - LCD_MESSAGE(MSG_MMU2_RESUMING); - BUZZ(198, 404); BUZZ(4, 0); BUZZ(198, 404); + LCD_MESSAGE(MSG_MMU2_RESUMING); + ATTN_BUZZ(true); + if (move_axes && all_axes_homed()) { // Move XY to starting position, then Z do_blocking_move_to_xy(resume_position, feedRate_t(NOZZLE_PARK_XY_FEEDRATE)); // Move Z_AXIS to saved position do_blocking_move_to_z(resume_position.z, feedRate_t(NOZZLE_PARK_Z_FEEDRATE)); } - else { - BUZZ(198, 404); BUZZ(4, 0); BUZZ(198, 404); - LCD_MESSAGE(MSG_MMU2_RESUMING); - } } } } @@ -898,7 +896,7 @@ void MMU2::load_filament(const uint8_t index) { command(MMU_CMD_L0 + index); manage_response(false, false); - BUZZ(200, 404); + ATTN_BUZZ(); } /** @@ -909,7 +907,7 @@ bool MMU2::load_filament_to_nozzle(const uint8_t index) { if (!_enabled) return false; if (thermalManager.tooColdToExtrude(active_extruder)) { - BUZZ(200, 404); + ATTN_BUZZ(); LCD_ALERTMESSAGE(MSG_HOTEND_TOO_COLD); return false; } @@ -924,7 +922,7 @@ bool MMU2::load_filament_to_nozzle(const uint8_t index) { extruder = index; active_extruder = 0; load_to_nozzle(); - BUZZ(200, 404); + ATTN_BUZZ(); } return success; } @@ -945,7 +943,7 @@ bool MMU2::eject_filament(const uint8_t index, const bool recover) { if (!_enabled) return false; if (thermalManager.tooColdToExtrude(active_extruder)) { - BUZZ(200, 404); + ATTN_BUZZ(); LCD_ALERTMESSAGE(MSG_HOTEND_TOO_COLD); return false; } @@ -961,12 +959,11 @@ bool MMU2::eject_filament(const uint8_t index, const bool recover) { if (recover) { LCD_MESSAGE(MSG_MMU2_EJECT_RECOVER); - BUZZ(200, 404); + ATTN_BUZZ(); TERN_(HOST_PROMPT_SUPPORT, hostui.prompt_do(PROMPT_USER_CONTINUE, F("MMU2 Eject Recover"), FPSTR(CONTINUE_STR))); TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired(F("MMU2 Eject Recover"))); TERN_(HAS_RESUME_CONTINUE, wait_for_user_response()); - BUZZ(200, 404); - BUZZ(200, 404); + ATTN_BUZZ(true); command(MMU_CMD_R0); manage_response(false, false); @@ -979,7 +976,7 @@ bool MMU2::eject_filament(const uint8_t index, const bool recover) { set_runout_valid(false); - BUZZ(200, 404); + ATTN_BUZZ(); stepper.disable_extruder(); @@ -994,7 +991,7 @@ bool MMU2::unload() { if (!_enabled) return false; if (thermalManager.tooColdToExtrude(active_extruder)) { - BUZZ(200, 404); + ATTN_BUZZ(); LCD_ALERTMESSAGE(MSG_HOTEND_TOO_COLD); return false; } @@ -1005,7 +1002,7 @@ bool MMU2::unload() { command(MMU_CMD_U0); manage_response(false, true); - BUZZ(200, 404); + ATTN_BUZZ(); // no active tool extruder = MMU2_NO_TOOL; diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index 69c25cbe3319a..636ac32042b63 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -57,7 +57,7 @@ #if ENABLED(EXTENSIBLE_UI) #include "../lcd/extui/ui_api.h" -#elif ENABLED(DWIN_CREALITY_LCD_ENHANCED) +#elif ENABLED(DWIN_LCD_PROUI) #include "../lcd/e3v2/proui/dwin.h" #endif @@ -281,7 +281,7 @@ bool load_filament(const_float_t slow_load_length/*=0*/, const_float_t fast_load // Show "Purge More" / "Resume" menu and wait for reply KEEPALIVE_STATE(PAUSED_FOR_USER); wait_for_user = false; - #if EITHER(HAS_MARLINUI_MENU, DWIN_CREALITY_LCD_ENHANCED) + #if EITHER(HAS_MARLINUI_MENU, DWIN_LCD_PROUI) ui.pause_show_message(PAUSE_MESSAGE_OPTION); // Also sets PAUSE_RESPONSE_WAIT_FOR #else pause_menu_response = PAUSE_RESPONSE_WAIT_FOR; @@ -407,6 +407,7 @@ bool pause_print(const_float_t retract, const xyz_pos_t &park_point, const bool #endif TERN_(HOST_PROMPT_SUPPORT, hostui.prompt_open(PROMPT_INFO, F("Pause"), FPSTR(DISMISS_STR))); + TERN_(DWIN_LCD_PROUI, DWIN_Print_Pause()); // Indicate that the printer is paused ++did_pause_print; @@ -549,7 +550,7 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep TERN_(EXTENSIBLE_UI, ExtUI::onStatusChanged(GET_TEXT_F(MSG_REHEATING))); - TERN_(DWIN_CREALITY_LCD_ENHANCED, LCD_MESSAGE(MSG_REHEATING)); + TERN_(DWIN_LCD_PROUI, LCD_MESSAGE(MSG_REHEATING)); // Re-enable the heaters if they timed out HOTEND_LOOP() thermalManager.reset_hotend_idle_timer(e); @@ -567,7 +568,7 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep TERN_(HOST_PROMPT_SUPPORT, hostui.prompt_do(PROMPT_USER_CONTINUE, GET_TEXT_F(MSG_REHEATDONE), FPSTR(CONTINUE_STR))); TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_REHEATDONE))); - TERN_(DWIN_CREALITY_LCD_ENHANCED, LCD_MESSAGE(MSG_REHEATDONE)); + TERN_(DWIN_LCD_PROUI, LCD_MESSAGE(MSG_REHEATDONE)); IF_DISABLED(PAUSE_REHEAT_FAST_RESUME, wait_for_user = true); @@ -709,9 +710,9 @@ void resume_print(const_float_t slow_load_length/*=0*/, const_float_t fast_load_ TERN_(HAS_FILAMENT_SENSOR, runout.reset()); - TERN_(HAS_STATUS_MESSAGE, ui.reset_status()); + TERN(DWIN_LCD_PROUI, DWIN_Print_Resume(), ui.reset_status()); TERN_(HAS_MARLINUI_MENU, ui.return_to_status()); - TERN_(DWIN_CREALITY_LCD_ENHANCED, HMI_ReturnScreen()); + TERN_(DWIN_LCD_PROUI, HMI_ReturnScreen()); } #endif // ADVANCED_PAUSE_FEATURE diff --git a/Marlin/src/feature/powerloss.cpp b/Marlin/src/feature/powerloss.cpp index 723ec1903bc84..214c248d359c1 100644 --- a/Marlin/src/feature/powerloss.cpp +++ b/Marlin/src/feature/powerloss.cpp @@ -54,6 +54,10 @@ uint32_t PrintJobRecovery::cmd_sdpos, // = 0 #include "../module/temperature.h" #include "../core/serial.h" +#if HOMING_Z_WITH_PROBE + #include "../module/probe.h" +#endif + #if ENABLED(FWRETRACT) #include "fwretract.h" #endif @@ -178,7 +182,8 @@ void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=POW info.valid_foot = info.valid_head; // Machine state - info.current_position = current_position; + // info.sdpos and info.current_position are pre-filled from the Stepper ISR + info.feedrate = uint16_t(MMS_TO_MMM(feedrate_mm_s)); info.zraise = zraise; info.flag.raised = raised; // Was Z raised before power-off? @@ -265,6 +270,10 @@ void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=POW #endif +#endif // POWER_LOSS_PIN + +#if PIN_EXISTS(POWER_LOSS) || ENABLED(DEBUG_POWER_LOSS_RECOVERY) + /** * An outage was detected by a sensor pin. * - If not SD printing, let the machine turn off on its own with no "KILL" screen @@ -273,7 +282,7 @@ void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=POW * - If backup power is available Retract E and Raise Z * - Go to the KILL screen */ - void PrintJobRecovery::_outage() { + void PrintJobRecovery::_outage(TERN_(DEBUG_POWER_LOSS_RECOVERY, const bool simulated/*=false*/)) { #if ENABLED(BACKUP_POWER_SUPPLY) static bool lock = false; if (lock) return; // No re-entrance from idle() during retract_and_lift() @@ -301,10 +310,16 @@ void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=POW retract_and_lift(zraise); #endif - kill(GET_TEXT_F(MSG_OUTAGE_RECOVERY)); + if (TERN0(DEBUG_POWER_LOSS_RECOVERY, simulated)) { + card.fileHasFinished(); + current_position.reset(); + sync_plan_position(); + } + else + kill(GET_TEXT_F(MSG_OUTAGE_RECOVERY)); } -#endif +#endif // POWER_LOSS_PIN || DEBUG_POWER_LOSS_RECOVERY /** * Save the recovery info the recovery file @@ -390,14 +405,12 @@ void PrintJobRecovery::resume() { #if ENABLED(POWER_LOSS_RECOVER_ZHOME) && defined(POWER_LOSS_ZHOME_POS) #define HOMING_Z_DOWN 1 - #else - #define HOME_XY_ONLY 1 #endif float z_now = info.flag.raised ? z_raised : z_print; - // Reset E to 0 and set Z to the real position - #if HOME_XY_ONLY + #if !HOMING_Z_DOWN + // Set Z to the real position sprintf_P(cmd, PSTR("G92.9Z%s"), dtostrf(z_now, 1, 3, str_1)); gcode.process_subcommands_now(cmd); #endif @@ -409,15 +422,15 @@ void PrintJobRecovery::resume() { gcode.process_subcommands_now(cmd); } - // Home XY with no Z raise, and also home Z here if Z isn't homing down below. - gcode.process_subcommands_now(F("G28R0" TERN_(HOME_XY_ONLY, "XY"))); // No raise during G28 + // Home XY with no Z raise + gcode.process_subcommands_now(F("G28R0XY")); // No raise during G28 #endif #if HOMING_Z_DOWN // Move to a safe XY position and home Z while avoiding the print. - constexpr xy_pos_t p = POWER_LOSS_ZHOME_POS; - sprintf_P(cmd, PSTR("G1X%sY%sF1000\nG28Z"), dtostrf(p.x, 1, 3, str_1), dtostrf(p.y, 1, 3, str_2)); + const xy_pos_t p = xy_pos_t(POWER_LOSS_ZHOME_POS) TERN_(HOMING_Z_WITH_PROBE, - probe.offset_xy); + sprintf_P(cmd, PSTR("G1X%sY%sF1000\nG28HZ"), dtostrf(p.x, 1, 3, str_1), dtostrf(p.y, 1, 3, str_2)); gcode.process_subcommands_now(cmd); #endif @@ -431,7 +444,7 @@ void PrintJobRecovery::resume() { sprintf_P(cmd, PSTR("M420S%cZ%s"), '0' + (char)info.flag.leveling, dtostrf(info.fade, 1, 1, str_1)); gcode.process_subcommands_now(cmd); - #if HOME_XY_ONLY + #if !HOMING_Z_DOWN // The physical Z was adjusted at power-off so undo the M420S1 correction to Z with G92.9. sprintf_P(cmd, PSTR("G92.9Z%s"), dtostrf(z_now, 1, 1, str_1)); gcode.process_subcommands_now(cmd); @@ -513,12 +526,12 @@ void PrintJobRecovery::resume() { // Un-retract if there was a retract at outage #if ENABLED(BACKUP_POWER_SUPPLY) && POWER_LOSS_RETRACT_LEN > 0 - gcode.process_subcommands_now(F("G1E" STRINGIFY(POWER_LOSS_RETRACT_LEN) "F3000")); + gcode.process_subcommands_now(F("G1F3000E" STRINGIFY(POWER_LOSS_RETRACT_LEN))); #endif // Additional purge on resume if configured #if POWER_LOSS_PURGE_LEN - sprintf_P(cmd, PSTR("G1 E%d F3000"), (POWER_LOSS_PURGE_LEN) + (POWER_LOSS_RETRACT_LEN)); + sprintf_P(cmd, PSTR("G1F3000E%d"), (POWER_LOSS_PURGE_LEN) + (POWER_LOSS_RETRACT_LEN)); gcode.process_subcommands_now(cmd); #endif diff --git a/Marlin/src/feature/powerloss.h b/Marlin/src/feature/powerloss.h index 50abad92220f1..4e97109bb7b93 100644 --- a/Marlin/src/feature/powerloss.h +++ b/Marlin/src/feature/powerloss.h @@ -216,9 +216,9 @@ class PrintJobRecovery { static void retract_and_lift(const_float_t zraise); #endif - #if PIN_EXISTS(POWER_LOSS) + #if PIN_EXISTS(POWER_LOSS) || ENABLED(DEBUG_POWER_LOSS_RECOVERY) friend class GcodeSuite; - static void _outage(); + static void _outage(TERN_(DEBUG_POWER_LOSS_RECOVERY, const bool simulated=false)); #endif }; diff --git a/Marlin/src/feature/probe_temp_comp.cpp b/Marlin/src/feature/probe_temp_comp.cpp index 9a975d6763fae..b5f636e698c95 100644 --- a/Marlin/src/feature/probe_temp_comp.cpp +++ b/Marlin/src/feature/probe_temp_comp.cpp @@ -28,6 +28,7 @@ #include "probe_temp_comp.h" #include +#include "../module/temperature.h" ProbeTempComp ptc; @@ -62,6 +63,7 @@ constexpr temp_calib_t ProbeTempComp::cali_info[TSI_COUNT]; uint8_t ProbeTempComp::calib_idx; // = 0 float ProbeTempComp::init_measurement; // = 0.0 +bool ProbeTempComp::enabled = true; void ProbeTempComp::reset() { TERN_(PTC_PROBE, LOOP_L_N(i, PTC_PROBE_COUNT) z_offsets_probe[i] = z_offsets_probe_default[i]); @@ -169,6 +171,13 @@ bool ProbeTempComp::finish_calibration(const TempSensorID tsi) { return true; } +void ProbeTempComp::apply_compensation(float &meas_z) { + if (!enabled) return; + TERN_(PTC_BED, compensate_measurement(TSI_BED, thermalManager.degBed(), meas_z)); + TERN_(PTC_PROBE, compensate_measurement(TSI_PROBE, thermalManager.degProbe(), meas_z)); + TERN_(PTC_HOTEND, compensate_measurement(TSI_EXT, thermalManager.degHotend(0), meas_z)); +} + void ProbeTempComp::compensate_measurement(const TempSensorID tsi, const celsius_t temp, float &meas_z) { const uint8_t measurements = cali_info[tsi].measurements; const celsius_t start_temp = cali_info[tsi].start_temp, diff --git a/Marlin/src/feature/probe_temp_comp.h b/Marlin/src/feature/probe_temp_comp.h index 1db7d04e89dca..42348db684732 100644 --- a/Marlin/src/feature/probe_temp_comp.h +++ b/Marlin/src/feature/probe_temp_comp.h @@ -77,7 +77,6 @@ class ProbeTempComp { static void reset_index() { calib_idx = 0; }; static uint8_t get_index() { return calib_idx; } static void reset(); - static void clear_offsets(const TempSensorID tsi); static void clear_all_offsets() { TERN_(PTC_PROBE, clear_offsets(TSI_PROBE)); TERN_(PTC_BED, clear_offsets(TSI_BED)); @@ -88,10 +87,16 @@ class ProbeTempComp { static void prepare_new_calibration(const_float_t init_meas_z); static void push_back_new_measurement(const TempSensorID tsi, const_float_t meas_z); static bool finish_calibration(const TempSensorID tsi); - static void compensate_measurement(const TempSensorID tsi, const celsius_t temp, float &meas_z); + static void set_enabled(const bool ena) { enabled = ena; } + + // Apply all temperature compensation adjustments + static void apply_compensation(float &meas_z); private: static uint8_t calib_idx; + static bool enabled; + + static void clear_offsets(const TempSensorID tsi); /** * Base value. Temperature compensation values will be deltas @@ -104,6 +109,8 @@ class ProbeTempComp { * to allow generating values of higher temperatures. */ static bool linear_regression(const TempSensorID tsi, float &k, float &d); + + static void compensate_measurement(const TempSensorID tsi, const celsius_t temp, float &meas_z); }; extern ProbeTempComp ptc; diff --git a/Marlin/src/feature/runout.cpp b/Marlin/src/feature/runout.cpp index 8b78b53848f36..98b6bd051061b 100644 --- a/Marlin/src/feature/runout.cpp +++ b/Marlin/src/feature/runout.cpp @@ -68,7 +68,7 @@ bool FilamentMonitorBase::enabled = true, #if ENABLED(EXTENSIBLE_UI) #include "../lcd/extui/ui_api.h" -#elif ENABLED(DWIN_CREALITY_LCD_ENHANCED) +#elif ENABLED(DWIN_LCD_PROUI) #include "../lcd/e3v2/proui/dwin.h" #endif @@ -88,7 +88,7 @@ void event_filament_runout(const uint8_t extruder) { #endif TERN_(EXTENSIBLE_UI, ExtUI::onFilamentRunout(ExtUI::getTool(extruder))); - TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_FilamentRunout(extruder)); + TERN_(DWIN_LCD_PROUI, DWIN_FilamentRunout(extruder)); #if ANY(HOST_PROMPT_SUPPORT, HOST_ACTION_COMMANDS, MULTI_FILAMENT_SENSOR) const char tool = '0' + TERN0(MULTI_FILAMENT_SENSOR, extruder); diff --git a/Marlin/src/feature/spindle_laser.cpp b/Marlin/src/feature/spindle_laser.cpp index 9ca7cb948e69a..52bb471b0f7e8 100644 --- a/Marlin/src/feature/spindle_laser.cpp +++ b/Marlin/src/feature/spindle_laser.cpp @@ -66,10 +66,10 @@ void SpindleLaser::init() { #endif #if ENABLED(SPINDLE_LASER_USE_PWM) SET_PWM(SPINDLE_LASER_PWM_PIN); - set_pwm_duty(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_PWM_OFF); // Set to lowest speed + hal.set_pwm_duty(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_PWM_OFF); // Set to lowest speed #endif #if ENABLED(HAL_CAN_SET_PWM_FREQ) && SPINDLE_LASER_FREQUENCY - set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_FREQUENCY); + hal.set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_FREQUENCY); TERN_(MARLIN_DEV_MODE, frequency = SPINDLE_LASER_FREQUENCY); #endif #if ENABLED(AIR_EVACUATION) @@ -89,9 +89,9 @@ void SpindleLaser::init() { */ void SpindleLaser::_set_ocr(const uint8_t ocr) { #if ENABLED(HAL_CAN_SET_PWM_FREQ) && SPINDLE_LASER_FREQUENCY - set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), TERN(MARLIN_DEV_MODE, frequency, SPINDLE_LASER_FREQUENCY)); + hal.set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), TERN(MARLIN_DEV_MODE, frequency, SPINDLE_LASER_FREQUENCY)); #endif - set_pwm_duty(pin_t(SPINDLE_LASER_PWM_PIN), ocr ^ SPINDLE_LASER_PWM_OFF); + hal.set_pwm_duty(pin_t(SPINDLE_LASER_PWM_PIN), ocr ^ SPINDLE_LASER_PWM_OFF); } void SpindleLaser::set_ocr(const uint8_t ocr) { diff --git a/Marlin/src/feature/spindle_laser.h b/Marlin/src/feature/spindle_laser.h index 89e11fca0851d..e948d2d37b73c 100644 --- a/Marlin/src/feature/spindle_laser.h +++ b/Marlin/src/feature/spindle_laser.h @@ -103,7 +103,7 @@ class SpindleLaser { static void init(); #if ENABLED(MARLIN_DEV_MODE) - static void refresh_frequency() { set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), frequency); } + static void refresh_frequency() { hal.set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), frequency); } #endif // Modifying this function should update everywhere diff --git a/Marlin/src/feature/tmc_util.cpp b/Marlin/src/feature/tmc_util.cpp index cf3fa3b7b0b79..c69772bebcaf0 100644 --- a/Marlin/src/feature/tmc_util.cpp +++ b/Marlin/src/feature/tmc_util.cpp @@ -1178,69 +1178,6 @@ #endif // USE_SENSORLESS -#if HAS_TMC_SPI - #define SET_CS_PIN(st) OUT_WRITE(st##_CS_PIN, HIGH) - void tmc_init_cs_pins() { - #if AXIS_HAS_SPI(X) - SET_CS_PIN(X); - #endif - #if AXIS_HAS_SPI(Y) - SET_CS_PIN(Y); - #endif - #if AXIS_HAS_SPI(Z) - SET_CS_PIN(Z); - #endif - #if AXIS_HAS_SPI(X2) - SET_CS_PIN(X2); - #endif - #if AXIS_HAS_SPI(Y2) - SET_CS_PIN(Y2); - #endif - #if AXIS_HAS_SPI(Z2) - SET_CS_PIN(Z2); - #endif - #if AXIS_HAS_SPI(Z3) - SET_CS_PIN(Z3); - #endif - #if AXIS_HAS_SPI(Z4) - SET_CS_PIN(Z4); - #endif - #if AXIS_HAS_SPI(I) - SET_CS_PIN(I); - #endif - #if AXIS_HAS_SPI(J) - SET_CS_PIN(J); - #endif - #if AXIS_HAS_SPI(K) - SET_CS_PIN(K); - #endif - #if AXIS_HAS_SPI(E0) - SET_CS_PIN(E0); - #endif - #if AXIS_HAS_SPI(E1) - SET_CS_PIN(E1); - #endif - #if AXIS_HAS_SPI(E2) - SET_CS_PIN(E2); - #endif - #if AXIS_HAS_SPI(E3) - SET_CS_PIN(E3); - #endif - #if AXIS_HAS_SPI(E4) - SET_CS_PIN(E4); - #endif - #if AXIS_HAS_SPI(E5) - SET_CS_PIN(E5); - #endif - #if AXIS_HAS_SPI(E6) - SET_CS_PIN(E6); - #endif - #if AXIS_HAS_SPI(E7) - SET_CS_PIN(E7); - #endif - } -#endif // HAS_TMC_SPI - template static bool test_connection(TMC &st) { SERIAL_ECHOPGM("Testing "); @@ -1339,3 +1276,66 @@ void test_tmc_connection(LOGICAL_AXIS_ARGS(const bool)) { } #endif // HAS_TRINAMIC_CONFIG + +#if HAS_TMC_SPI + #define SET_CS_PIN(st) OUT_WRITE(st##_CS_PIN, HIGH) + void tmc_init_cs_pins() { + #if AXIS_HAS_SPI(X) + SET_CS_PIN(X); + #endif + #if AXIS_HAS_SPI(Y) + SET_CS_PIN(Y); + #endif + #if AXIS_HAS_SPI(Z) + SET_CS_PIN(Z); + #endif + #if AXIS_HAS_SPI(X2) + SET_CS_PIN(X2); + #endif + #if AXIS_HAS_SPI(Y2) + SET_CS_PIN(Y2); + #endif + #if AXIS_HAS_SPI(Z2) + SET_CS_PIN(Z2); + #endif + #if AXIS_HAS_SPI(Z3) + SET_CS_PIN(Z3); + #endif + #if AXIS_HAS_SPI(Z4) + SET_CS_PIN(Z4); + #endif + #if AXIS_HAS_SPI(I) + SET_CS_PIN(I); + #endif + #if AXIS_HAS_SPI(J) + SET_CS_PIN(J); + #endif + #if AXIS_HAS_SPI(K) + SET_CS_PIN(K); + #endif + #if AXIS_HAS_SPI(E0) + SET_CS_PIN(E0); + #endif + #if AXIS_HAS_SPI(E1) + SET_CS_PIN(E1); + #endif + #if AXIS_HAS_SPI(E2) + SET_CS_PIN(E2); + #endif + #if AXIS_HAS_SPI(E3) + SET_CS_PIN(E3); + #endif + #if AXIS_HAS_SPI(E4) + SET_CS_PIN(E4); + #endif + #if AXIS_HAS_SPI(E5) + SET_CS_PIN(E5); + #endif + #if AXIS_HAS_SPI(E6) + SET_CS_PIN(E6); + #endif + #if AXIS_HAS_SPI(E7) + SET_CS_PIN(E7); + #endif + } +#endif // HAS_TMC_SPI diff --git a/Marlin/src/feature/tmc_util.h b/Marlin/src/feature/tmc_util.h index 892d33768b6fe..fc333b09dd99f 100644 --- a/Marlin/src/feature/tmc_util.h +++ b/Marlin/src/feature/tmc_util.h @@ -382,8 +382,8 @@ void test_tmc_connection(LOGICAL_AXIS_DECL(const bool, true)); #endif // USE_SENSORLESS +#endif // HAS_TRINAMIC_CONFIG + #if HAS_TMC_SPI void tmc_init_cs_pins(); #endif - -#endif // HAS_TRINAMIC_CONFIG diff --git a/Marlin/src/feature/bedlevel/abl/x_twist.cpp b/Marlin/src/feature/x_twist.cpp similarity index 64% rename from Marlin/src/feature/bedlevel/abl/x_twist.cpp rename to Marlin/src/feature/x_twist.cpp index c4a62c35953f5..b5ad25cba87d7 100644 --- a/Marlin/src/feature/bedlevel/abl/x_twist.cpp +++ b/Marlin/src/feature/x_twist.cpp @@ -19,29 +19,36 @@ * along with this program. If not, see . * */ -#include "../../../inc/MarlinConfig.h" +#include "../inc/MarlinConfig.h" #if ENABLED(X_AXIS_TWIST_COMPENSATION) -#include "../bedlevel.h" +#include "x_twist.h" +#include "../module/probe.h" XATC xatc; +bool XATC::enabled; float XATC::spacing, XATC::start; -xatc_points_t XATC::z_values; +xatc_array_t XATC::z_offset; // Initialized by settings.load() + +void XATC::reset() { + constexpr float xzo[] = XATC_Z_OFFSETS; + static_assert(COUNT(xzo) == XATC_MAX_POINTS, "XATC_Z_OFFSETS is the wrong size."); + COPY(z_offset, xzo); + start = probe.min_x(); + spacing = (probe.max_x() - start) / (XATC_MAX_POINTS - 1); + enabled = true; +} void XATC::print_points() { SERIAL_ECHOLNPGM(" X-Twist Correction:"); LOOP_L_N(x, XATC_MAX_POINTS) { SERIAL_CHAR(' '); - if (!isnan(z_values[x])) { - if (z_values[x] >= 0) SERIAL_CHAR('+'); - SERIAL_ECHO_F(z_values[x], 3); - } - else { - LOOP_L_N(i, 6) - SERIAL_CHAR(i ? '=' : ' '); - } + if (!isnan(z_offset[x])) + serial_offset(z_offset[x]); + else + LOOP_L_N(i, 6) SERIAL_CHAR(i ? '=' : ' '); } SERIAL_EOL(); } @@ -49,11 +56,12 @@ void XATC::print_points() { float lerp(const_float_t t, const_float_t a, const_float_t b) { return a + t * (b - a); } float XATC::compensation(const xy_pos_t &raw) { + if (!enabled) return 0; + if (NEAR_ZERO(spacing)) return 0; float t = (raw.x - start) / spacing; - int i = FLOOR(t); - LIMIT(i, 0, XATC_MAX_POINTS - 2); + const int i = constrain(FLOOR(t), 0, XATC_MAX_POINTS - 2); t -= i; - return lerp(t, z_values[i], z_values[i + 1]); + return lerp(t, z_offset[i], z_offset[i + 1]); } #endif // X_AXIS_TWIST_COMPENSATION diff --git a/Marlin/src/feature/bedlevel/abl/x_twist.h b/Marlin/src/feature/x_twist.h similarity index 82% rename from Marlin/src/feature/bedlevel/abl/x_twist.h rename to Marlin/src/feature/x_twist.h index bbad9e73efac6..6a2ff279013a6 100644 --- a/Marlin/src/feature/bedlevel/abl/x_twist.h +++ b/Marlin/src/feature/x_twist.h @@ -21,15 +21,18 @@ */ #pragma once -#include "../../../inc/MarlinConfigPre.h" +#include "../inc/MarlinConfigPre.h" -typedef float xatc_points_t[XATC_MAX_POINTS]; +typedef float xatc_array_t[XATC_MAX_POINTS]; class XATC { + static bool enabled; public: static float spacing, start; - static xatc_points_t z_values; + static xatc_array_t z_offset; + static void reset(); + static void set_enabled(const bool ena) { enabled = ena; } static float compensation(const xy_pos_t &raw); static void print_points(); }; diff --git a/Marlin/src/feature/z_stepper_align.cpp b/Marlin/src/feature/z_stepper_align.cpp index 1b4eb44749036..fdbd464ea1b42 100644 --- a/Marlin/src/feature/z_stepper_align.cpp +++ b/Marlin/src/feature/z_stepper_align.cpp @@ -35,7 +35,7 @@ ZStepperAlign z_stepper_align; xy_pos_t ZStepperAlign::xy[NUM_Z_STEPPER_DRIVERS]; -#if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) +#if HAS_Z_STEPPER_ALIGN_STEPPER_XY xy_pos_t ZStepperAlign::stepper_xy[NUM_Z_STEPPER_DRIVERS]; #endif @@ -103,7 +103,7 @@ void ZStepperAlign::reset_to_default() { COPY(xy, xy_init); - #if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) + #if HAS_Z_STEPPER_ALIGN_STEPPER_XY constexpr xy_pos_t stepper_xy_init[] = Z_STEPPER_ALIGN_STEPPER_XY; static_assert( COUNT(stepper_xy_init) == NUM_Z_STEPPER_DRIVERS, diff --git a/Marlin/src/feature/z_stepper_align.h b/Marlin/src/feature/z_stepper_align.h index e1b235b52cb32..8a12cd18b0bd6 100644 --- a/Marlin/src/feature/z_stepper_align.h +++ b/Marlin/src/feature/z_stepper_align.h @@ -31,7 +31,7 @@ class ZStepperAlign { public: static xy_pos_t xy[NUM_Z_STEPPER_DRIVERS]; - #if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) + #if HAS_Z_STEPPER_ALIGN_STEPPER_XY static xy_pos_t stepper_xy[NUM_Z_STEPPER_DRIVERS]; #endif diff --git a/Marlin/src/gcode/bedlevel/G35.cpp b/Marlin/src/gcode/bedlevel/G35.cpp index 4dd1323a6c295..dd828bf0c8730 100644 --- a/Marlin/src/gcode/bedlevel/G35.cpp +++ b/Marlin/src/gcode/bedlevel/G35.cpp @@ -155,7 +155,7 @@ void GcodeSuite::G35() { // Restore the active tool after homing #if HAS_MULTI_HOTEND - tool_change(old_tool_index, DISABLED(PARKING_EXTRUDER)); // Fetch previous toolhead if not PARKING_EXTRUDER + if (old_tool_index != 0) tool_change(old_tool_index, DISABLED(PARKING_EXTRUDER)); // Fetch previous toolhead if not PARKING_EXTRUDER #endif #if BOTH(HAS_LEVELING, RESTORE_LEVELING_AFTER_G35) diff --git a/Marlin/src/gcode/bedlevel/abl/G29.cpp b/Marlin/src/gcode/bedlevel/abl/G29.cpp index fddca22c32114..1868c636ee361 100644 --- a/Marlin/src/gcode/bedlevel/abl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/abl/G29.cpp @@ -36,15 +36,6 @@ #include "../../../module/probe.h" #include "../../queue.h" -#if HAS_PTC - #include "../../../feature/probe_temp_comp.h" - #include "../../../module/temperature.h" -#endif - -#if HAS_STATUS_MESSAGE - #include "../../../lcd/marlinui.h" -#endif - #if ENABLED(AUTO_BED_LEVELING_LINEAR) #include "../../../libs/least_squares_fit.h" #endif @@ -53,14 +44,12 @@ #include "../../../libs/vector_3.h" #endif -#define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE) -#include "../../../core/debug_out.h" - +#include "../../../lcd/marlinui.h" #if ENABLED(EXTENSIBLE_UI) #include "../../../lcd/extui/ui_api.h" #elif ENABLED(DWIN_CREALITY_LCD) #include "../../../lcd/e3v2/creality/dwin.h" -#elif ENABLED(DWIN_CREALITY_LCD_ENHANCED) +#elif ENABLED(DWIN_LCD_PROUI) #include "../../../lcd/e3v2/proui/dwin.h" #endif @@ -68,6 +57,9 @@ #include "../../../module/tool_change.h" #endif +#define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE) +#include "../../../core/debug_out.h" + #if ABL_USES_GRID #if ENABLED(PROBE_Y_FIRST) #define PR_OUTER_VAR abl.meshCount.x @@ -82,7 +74,12 @@ #endif #endif -#define G29_RETURN(b) return TERN_(G29_RETRY_AND_RECOVER, b) +#define G29_RETURN(retry) do{ \ + if (TERN(G29_RETRY_AND_RECOVER, !retry, true)) { \ + TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_IDLE, false)); \ + } \ + return TERN_(G29_RETRY_AND_RECOVER, retry); \ +}while(0) // For manual probing values persist over multiple G29 class G29_State { @@ -93,6 +90,10 @@ class G29_State { bool dryrun, reenable; + #if HAS_MULTI_HOTEND + uint8_t tool_index; + #endif + #if EITHER(PROBE_MANUALLY, AUTO_BED_LEVELING_LINEAR) int abl_probe_index; #endif @@ -219,12 +220,13 @@ class G29_State { G29_TYPE GcodeSuite::G29() { DEBUG_SECTION(log_G29, "G29", DEBUGGING(LEVELING)); + // Leveling state is persistent when done manually with multiple G29 commands TERN_(PROBE_MANUALLY, static) G29_State abl; - TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_PROBE)); - + // Keep powered steppers from timing out reset_stepper_timeout(); + // Q = Query leveling and G29 state const bool seenQ = EITHER(DEBUG_LEVELING_FEATURE, PROBE_MANUALLY) && parser.seen_test('Q'); // G29 Q is also available if debugging @@ -233,11 +235,14 @@ G29_TYPE GcodeSuite::G29() { if (DISABLED(PROBE_MANUALLY) && seenQ) G29_RETURN(false); #endif + // A = Abort manual probing + // C = Generate fake probe points (DEBUG_LEVELING_FEATURE) const bool seenA = TERN0(PROBE_MANUALLY, parser.seen_test('A')), no_action = seenA || seenQ, faux = ENABLED(DEBUG_LEVELING_FEATURE) && DISABLED(PROBE_MANUALLY) ? parser.boolval('C') : no_action; - if (!no_action && planner.leveling_active && parser.boolval('O')) { // Auto-level only if needed + // O = Don't level if leveling is already active + if (!no_action && planner.leveling_active && parser.boolval('O')) { if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("> Auto-level not needed, skip"); G29_RETURN(false); } @@ -249,21 +254,29 @@ G29_TYPE GcodeSuite::G29() { // Don't allow auto-leveling without homing first if (homing_needed_error()) G29_RETURN(false); + // 3-point leveling gets points from the probe class #if ENABLED(AUTO_BED_LEVELING_3POINT) vector_3 points[3]; probe.get_three_points(points); #endif + // Storage for ABL Linear results #if ENABLED(AUTO_BED_LEVELING_LINEAR) struct linear_fit_data lsf_results; #endif + // Set and report "probing" state to host + TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_PROBE, false)); + /** * On the initial G29 fetch command parameters. */ if (!g29_in_progress) { - TERN_(HAS_MULTI_HOTEND, if (active_extruder) tool_change(0)); + #if HAS_MULTI_HOTEND + abl.tool_index = active_extruder; + if (active_extruder != 0) tool_change(0, true); + #endif #if EITHER(PROBE_MANUALLY, AUTO_BED_LEVELING_LINEAR) abl.abl_probe_index = -1; @@ -406,12 +419,13 @@ G29_TYPE GcodeSuite::G29() { planner.synchronize(); + TERN_(EXTENSIBLE_UI, ExtUI::onLevelingStart()); + #if ENABLED(AUTO_BED_LEVELING_3POINT) if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("> 3-point Leveling"); points[0].z = points[1].z = points[2].z = 0; // Probe at 3 arbitrary points #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) - TERN_(EXTENSIBLE_UI, ExtUI::onMeshLevelingStart()); - TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_MeshLevelingStart()); + TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_LevelingStart()); #endif if (!faux) { @@ -427,10 +441,10 @@ G29_TYPE GcodeSuite::G29() { if (!no_action) set_bed_leveling_enabled(false); // Deploy certain probes before starting probing - #if HAS_BED_PROBE - if (ENABLED(BLTOUCH)) - do_z_clearance(Z_CLEARANCE_DEPLOY_PROBE); - else if (probe.deploy()) { + #if ENABLED(BLTOUCH) + do_z_clearance(Z_CLEARANCE_DEPLOY_PROBE); + #elif HAS_BED_PROBE + if (probe.deploy()) { // (returns true on deploy failure) set_bed_leveling_enabled(abl.reenable); G29_RETURN(false); } @@ -481,6 +495,7 @@ G29_TYPE GcodeSuite::G29() { SERIAL_ECHOLNPGM("idle"); } + // For 'A' or 'Q' exit with success state if (no_action) G29_RETURN(false); if (abl.abl_probe_index == 0) { @@ -563,6 +578,7 @@ G29_TYPE GcodeSuite::G29() { SERIAL_ECHOLNPGM("Grid probing done."); // Re-enable software endstops, if needed SET_SOFT_ENDSTOP_LOOSE(false); + TERN_(EXTENSIBLE_UI, ExtUI::onLevelingDone()); } #elif ENABLED(AUTO_BED_LEVELING_3POINT) @@ -592,6 +608,8 @@ G29_TYPE GcodeSuite::G29() { abl.reenable = false; } + TERN_(EXTENSIBLE_UI, ExtUI::onLevelingDone()); + } #endif // AUTO_BED_LEVELING_3POINT @@ -651,10 +669,6 @@ G29_TYPE GcodeSuite::G29() { break; // Breaks out of both loops } - TERN_(PTC_BED, ptc.compensate_measurement(TSI_BED, thermalManager.degBed(), abl.measured_z)); - TERN_(PTC_PROBE, ptc.compensate_measurement(TSI_PROBE, thermalManager.degProbe(), abl.measured_z)); - TERN_(PTC_HOTEND, ptc.compensate_measurement(TSI_EXT, thermalManager.degHotend(0), abl.measured_z)); - #if ENABLED(AUTO_BED_LEVELING_LINEAR) abl.mean += abl.measured_z; @@ -668,7 +682,7 @@ G29_TYPE GcodeSuite::G29() { #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) const float z = abl.measured_z + abl.Z_offset; - z_values[abl.meshCount.x][abl.meshCount.y] = z PLUS_TERN0(X_AXIS_TWIST_COMPENSATION, xatc.compensation(abl.probePos)); + z_values[abl.meshCount.x][abl.meshCount.y] = z; TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(abl.meshCount, z)); #endif @@ -889,11 +903,11 @@ G29_TYPE GcodeSuite::G29() { process_subcommands_now(F(Z_PROBE_END_SCRIPT)); #endif - TERN_(HAS_DWIN_E3V2_BASIC, DWIN_CompletedLeveling()); + TERN_(HAS_DWIN_E3V2_BASIC, DWIN_LevelingDone()); - report_current_position(); + TERN_(HAS_MULTI_HOTEND, if (abl.tool_index != 0) tool_change(abl.tool_index)); - TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_IDLE)); + report_current_position(); G29_RETURN(isnan(abl.measured_z)); diff --git a/Marlin/src/gcode/bedlevel/mbl/G29.cpp b/Marlin/src/gcode/bedlevel/mbl/G29.cpp index 090c15b0578c2..74843235f4372 100644 --- a/Marlin/src/gcode/bedlevel/mbl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/mbl/G29.cpp @@ -40,7 +40,7 @@ #if ENABLED(EXTENSIBLE_UI) #include "../../../lcd/extui/ui_api.h" -#elif ENABLED(DWIN_CREALITY_LCD_ENHANCED) +#elif ENABLED(DWIN_LCD_PROUI) #include "../../../lcd/e3v2/proui/dwin.h" #endif @@ -75,8 +75,6 @@ void GcodeSuite::G29() { } #endif - TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_PROBE)); - static int mbl_probe_index = -1; MeshLevelingState state = (MeshLevelingState)parser.byteval('S', (int8_t)MeshReport); @@ -85,6 +83,8 @@ void GcodeSuite::G29() { return; } + TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_PROBE)); + int8_t ix, iy; ix = iy = 0; @@ -104,7 +104,8 @@ void GcodeSuite::G29() { mbl_probe_index = 0; if (!ui.wait_for_move) { queue.inject(parser.seen_test('N') ? F("G28" TERN(CAN_SET_LEVELING_AFTER_G28, "L0", "") "\nG29S2") : F("G29S2")); - TERN_(EXTENSIBLE_UI, ExtUI::onMeshLevelingStart()); + TERN_(EXTENSIBLE_UI, ExtUI::onLevelingStart()); + TERN_(DWIN_LCD_PROUI, DWIN_LevelingStart()); return; } state = MeshNext; @@ -117,9 +118,11 @@ void GcodeSuite::G29() { // For each G29 S2... if (mbl_probe_index == 0) { // Move close to the bed before the first point - do_blocking_move_to_z(0.4f + do_blocking_move_to_z( #ifdef MANUAL_PROBE_START_Z - + (MANUAL_PROBE_START_Z) - 0.4f + MANUAL_PROBE_START_Z + #else + 0.4f #endif ); } @@ -127,6 +130,7 @@ void GcodeSuite::G29() { // Save Z for the previous mesh position mbl.set_zigzag_z(mbl_probe_index - 1, current_position.z); TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(ix, iy, current_position.z)); + TERN_(DWIN_LCD_PROUI, DWIN_MeshUpdate(_MIN(mbl_probe_index, GRID_MAX_POINTS), int(GRID_MAX_POINTS), current_position.z)); SET_SOFT_ENDSTOP_LOOSE(false); } // If there's another point to sample, move there with optional lift. @@ -153,8 +157,7 @@ void GcodeSuite::G29() { mbl_probe_index = -1; SERIAL_ECHOLNPGM("Mesh probing done."); TERN_(HAS_STATUS_MESSAGE, LCD_MESSAGE(MSG_MESH_DONE)); - BUZZ(100, 659); - BUZZ(100, 698); + OKAY_BUZZ(); home_all_axes(); set_bed_leveling_enabled(true); @@ -166,6 +169,7 @@ void GcodeSuite::G29() { #endif TERN_(LCD_BED_LEVELING, ui.wait_for_move = false); + TERN_(EXTENSIBLE_UI, ExtUI::onLevelingDone()); } break; @@ -193,7 +197,7 @@ void GcodeSuite::G29() { if (parser.seenval('Z')) { mbl.z_values[ix][iy] = parser.value_linear_units(); TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(ix, iy, mbl.z_values[ix][iy])); - TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_MeshUpdate(ix, iy, mbl.z_values[ix][iy])); + TERN_(DWIN_LCD_PROUI, DWIN_MeshUpdate(ix, iy, mbl.z_values[ix][iy])); } else return echo_not_entered('Z'); diff --git a/Marlin/src/gcode/bedlevel/ubl/M421.cpp b/Marlin/src/gcode/bedlevel/ubl/M421.cpp index ac6f97b00acb5..c11a20ebf33cd 100644 --- a/Marlin/src/gcode/bedlevel/ubl/M421.cpp +++ b/Marlin/src/gcode/bedlevel/ubl/M421.cpp @@ -33,7 +33,7 @@ #if ENABLED(EXTENSIBLE_UI) #include "../../../lcd/extui/ui_api.h" -#elif ENABLED(DWIN_CREALITY_LCD_ENHANCED) +#elif ENABLED(DWIN_LCD_PROUI) #include "../../../lcd/e3v2/proui/dwin.h" #endif @@ -69,7 +69,7 @@ void GcodeSuite::M421() { float &zval = ubl.z_values[ij.x][ij.y]; // Altering this Mesh Point zval = hasN ? NAN : parser.value_linear_units() + (hasQ ? zval : 0); // N=NAN, Z=NEWVAL, or Q=ADDVAL TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(ij.x, ij.y, zval)); // Ping ExtUI in case it's showing the mesh - TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_MeshUpdate(ij.x, ij.y, zval)); + TERN_(DWIN_LCD_PROUI, DWIN_MeshUpdate(ij.x, ij.y, zval)); } } diff --git a/Marlin/src/gcode/calibrate/G28.cpp b/Marlin/src/gcode/calibrate/G28.cpp index 48f02d2a33100..9361790d74cf4 100644 --- a/Marlin/src/gcode/calibrate/G28.cpp +++ b/Marlin/src/gcode/calibrate/G28.cpp @@ -51,7 +51,7 @@ #include "../../lcd/extui/ui_api.h" #elif ENABLED(DWIN_CREALITY_LCD) #include "../../lcd/e3v2/creality/dwin.h" -#elif ENABLED(DWIN_CREALITY_LCD_ENHANCED) +#elif ENABLED(DWIN_LCD_PROUI) #include "../../lcd/e3v2/proui/dwin.h" #endif @@ -76,10 +76,9 @@ const int x_axis_home_dir = TOOL_X_HOME_DIR(active_extruder); - const float mlx = max_length(X_AXIS), - mly = max_length(Y_AXIS), - mlratio = mlx > mly ? mly / mlx : mlx / mly, - fr_mm_s = _MIN(homing_feedrate(X_AXIS), homing_feedrate(Y_AXIS)) * SQRT(sq(mlratio) + 1.0); + // Use a higher diagonal feedrate so axes move at homing speed + const float minfr = _MIN(homing_feedrate(X_AXIS), homing_feedrate(Y_AXIS)), + fr_mm_s = HYPOT(minfr, minfr); #if ENABLED(SENSORLESS_HOMING) sensorless_t stealth_states { @@ -95,7 +94,7 @@ }; #endif - do_blocking_move_to_xy(1.5 * mlx * x_axis_home_dir, 1.5 * mly * Y_HOME_DIR, fr_mm_s); + do_blocking_move_to_xy(1.5 * max_length(X_AXIS) * x_axis_home_dir, 1.5 * max_length(Y_AXIS) * Y_HOME_DIR, fr_mm_s); endstops.validate_homing_move(); @@ -214,8 +213,6 @@ void GcodeSuite::G28() { TERN_(LASER_MOVE_G28_OFF, cutter.set_inline_enabled(false)); // turn off laser - TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_HOMING)); - #if ENABLED(DUAL_X_CARRIAGE) bool IDEX_saved_duplication_state = extruder_duplication_enabled; DualXMode IDEX_saved_mode = dual_x_carriage_mode; @@ -237,7 +234,12 @@ void GcodeSuite::G28() { return; } - TERN_(HAS_DWIN_E3V2_BASIC, DWIN_StartHoming()); + #if ENABLED(FULL_REPORT_TO_HOST_FEATURE) + const M_StateEnum old_grblstate = M_State_grbl; + set_and_report_grblstate(M_HOMING); + #endif + + TERN_(HAS_DWIN_E3V2_BASIC, DWIN_HomingStart()); TERN_(EXTENSIBLE_UI, ExtUI::onHomingStart()); planner.synchronize(); // Wait for planner moves to finish! @@ -395,9 +397,10 @@ void GcodeSuite::G28() { TERN_(HOME_Z_FIRST, if (doZ) homeaxis(Z_AXIS)); - const float z_homing_height = parser.seenval('R') ? parser.value_linear_units() : Z_HOMING_HEIGHT; + const bool seenR = parser.seenval('R'); + const float z_homing_height = seenR ? parser.value_linear_units() : Z_HOMING_HEIGHT; - if (z_homing_height && (LINEAR_AXIS_GANG(doX, || doY, || TERN0(Z_SAFE_HOMING, doZ), || doI, || doJ, || doK))) { + if (z_homing_height && (seenR || LINEAR_AXIS_GANG(doX, || doY, || TERN0(Z_SAFE_HOMING, doZ), || doI, || doJ, || doK))) { // Raise Z before homing any other axes and z is not already high enough (never lower z) if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Raise Z (before homing) by ", z_homing_height); do_z_clearance(z_homing_height); @@ -451,7 +454,11 @@ void GcodeSuite::G28() { stepper.set_separate_multi_axis(false); #endif - TERN(Z_SAFE_HOMING, home_z_safely(), homeaxis(Z_AXIS)); + #if ENABLED(Z_SAFE_HOMING) + if (TERN1(POWER_LOSS_RECOVERY, !parser.seen_test('H'))) home_z_safely(); else homeaxis(Z_AXIS); + #else + homeaxis(Z_AXIS); + #endif probe.move_z_after_homing(); } #endif @@ -545,15 +552,15 @@ void GcodeSuite::G28() { ui.refresh(); - TERN_(HAS_DWIN_E3V2_BASIC, DWIN_CompletedHoming()); - TERN_(EXTENSIBLE_UI, ExtUI::onHomingComplete()); + TERN_(HAS_DWIN_E3V2_BASIC, DWIN_HomingDone()); + TERN_(EXTENSIBLE_UI, ExtUI::onHomingDone()); report_current_position(); if (ENABLED(NANODLP_Z_SYNC) && (doZ || ENABLED(NANODLP_ALL_AXIS))) SERIAL_ECHOLNPGM(STR_Z_MOVE_COMP); - TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_IDLE)); + TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(old_grblstate)); #if HAS_L64XX // Set L6470 absolute position registers to counts diff --git a/Marlin/src/gcode/calibrate/G33.cpp b/Marlin/src/gcode/calibrate/G33.cpp index a4b9aec01b675..506f367947df2 100644 --- a/Marlin/src/gcode/calibrate/G33.cpp +++ b/Marlin/src/gcode/calibrate/G33.cpp @@ -98,8 +98,7 @@ void ac_cleanup(TERN_(HAS_MULTI_HOTEND, const uint8_t old_tool_index)) { void print_signed_float(FSTR_P const prefix, const_float_t f) { SERIAL_ECHOPGM(" "); SERIAL_ECHOF(prefix, AS_CHAR(':')); - if (f >= 0) SERIAL_CHAR('+'); - SERIAL_ECHO_F(f, 2); + serial_offset(f); } /** diff --git a/Marlin/src/gcode/calibrate/G34_M422.cpp b/Marlin/src/gcode/calibrate/G34_M422.cpp index 328a40dbb46a1..d1f82e7e98749 100644 --- a/Marlin/src/gcode/calibrate/G34_M422.cpp +++ b/Marlin/src/gcode/calibrate/G34_M422.cpp @@ -41,7 +41,7 @@ #include "../../module/tool_change.h" #endif -#if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) +#if HAS_Z_STEPPER_ALIGN_STEPPER_XY #include "../../libs/least_squares_fit.h" #endif @@ -122,7 +122,7 @@ void GcodeSuite::G34() { break; } - const float z_auto_align_amplification = TERN(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS, Z_STEPPER_ALIGN_AMP, parser.floatval('A', Z_STEPPER_ALIGN_AMP)); + const float z_auto_align_amplification = TERN(HAS_Z_STEPPER_ALIGN_STEPPER_XY, Z_STEPPER_ALIGN_AMP, parser.floatval('A', Z_STEPPER_ALIGN_AMP)); if (!WITHIN(ABS(z_auto_align_amplification), 0.5f, 2.0f)) { SERIAL_ECHOLNPGM("?(A)mplification out of bounds (0.5-2.0)."); break; @@ -179,7 +179,7 @@ void GcodeSuite::G34() { // Now, the Z origin lies below the build plate. That allows to probe deeper, before run_z_probe throws an error. // This hack is un-done at the end of G34 - either by re-homing, or by using the probed heights of the last iteration. - #if DISABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) + #if !HAS_Z_STEPPER_ALIGN_STEPPER_XY float last_z_align_move[NUM_Z_STEPPER_DRIVERS] = ARRAY_N_1(NUM_Z_STEPPER_DRIVERS, 10000.0f); #else float last_z_align_level_indicator = 10000.0f; @@ -188,7 +188,7 @@ void GcodeSuite::G34() { z_maxdiff = 0.0f, amplification = z_auto_align_amplification; - #if DISABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) + #if !HAS_Z_STEPPER_ALIGN_STEPPER_XY bool adjustment_reverse = false; #endif @@ -256,7 +256,7 @@ void GcodeSuite::G34() { z_maxdiff = z_measured_max - z_measured_min; z_probe = Z_BASIC_CLEARANCE + z_measured_max + z_maxdiff; - #if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) + #if HAS_Z_STEPPER_ALIGN_STEPPER_XY // Replace the initial values in z_measured with calculated heights at // each stepper position. This allows the adjustment algorithm to be // shared between both possible probing mechanisms. @@ -338,7 +338,7 @@ void GcodeSuite::G34() { return false; }; - #if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) + #if HAS_Z_STEPPER_ALIGN_STEPPER_XY // Check if the applied corrections go in the correct direction. // Calculate the sum of the absolute deviations from the mean of the probe measurements. // Compare to the last iteration to ensure it's getting better. @@ -370,7 +370,7 @@ void GcodeSuite::G34() { float z_align_move = z_measured[zstepper] - z_measured_min; const float z_align_abs = ABS(z_align_move); - #if DISABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) + #if !HAS_Z_STEPPER_ALIGN_STEPPER_XY // Optimize one iteration's correction based on the first measurements if (z_align_abs) amplification = (iteration == 1) ? _MIN(last_z_align_move[zstepper] / z_align_abs, 2.0f) : z_auto_align_amplification; @@ -394,7 +394,7 @@ void GcodeSuite::G34() { // Lock all steppers except one stepper.set_all_z_lock(true, zstepper); - #if DISABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) + #if !HAS_Z_STEPPER_ALIGN_STEPPER_XY // Decreasing accuracy was detected so move was inverted. // Will match reversed Z steppers on dual steppers. Triple will need more work to map. if (adjustment_reverse) { @@ -467,7 +467,7 @@ void GcodeSuite::G34() { * * S : Index of the probe point to set * - * With Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS: + * With Z_STEPPER_ALIGN_STEPPER_XY: * W : Index of the Z stepper position to set * The W and S parameters may not be combined. * @@ -486,42 +486,43 @@ void GcodeSuite::M422() { return; } - const bool is_probe_point = parser.seen('S'); + const bool is_probe_point = parser.seen_test('S'); - if (TERN0(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS, is_probe_point && parser.seen('W'))) { + if (TERN0(HAS_Z_STEPPER_ALIGN_STEPPER_XY, is_probe_point && parser.seen_test('W'))) { SERIAL_ECHOLNPGM("?(S) and (W) may not be combined."); return; } - xy_pos_t *pos_dest = ( - TERN_(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS, !is_probe_point ? z_stepper_align.stepper_xy :) + xy_pos_t * const pos_dest = ( + TERN_(HAS_Z_STEPPER_ALIGN_STEPPER_XY, !is_probe_point ? z_stepper_align.stepper_xy :) z_stepper_align.xy ); - if (!is_probe_point && TERN1(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS, !parser.seen('W'))) { - SERIAL_ECHOLNPGM("?(S)" TERN_(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS, " or (W)") " is required."); + if (!is_probe_point && TERN1(HAS_Z_STEPPER_ALIGN_STEPPER_XY, !parser.seen_test('W'))) { + SERIAL_ECHOLNPGM("?(S)" TERN_(HAS_Z_STEPPER_ALIGN_STEPPER_XY, " or (W)") " is required."); return; } // Get the Probe Position Index or Z Stepper Index - int8_t position_index; - if (is_probe_point) { - position_index = parser.intval('S') - 1; - if (!WITHIN(position_index, 0, int8_t(NUM_Z_STEPPER_DRIVERS) - 1)) { - SERIAL_ECHOLNPGM("?(S) Probe-position index invalid."); - return; - } - } + int8_t position_index = 1; + FSTR_P err_string = F("?(S) Probe-position"); + if (is_probe_point) + position_index = parser.intval('S'); else { - #if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) - position_index = parser.intval('W') - 1; - if (!WITHIN(position_index, 0, NUM_Z_STEPPER_DRIVERS - 1)) { - SERIAL_ECHOLNPGM("?(W) Z-stepper index invalid."); - return; - } + #if HAS_Z_STEPPER_ALIGN_STEPPER_XY + err_string = F("?(W) Z-stepper"); + position_index = parser.intval('W'); #endif } + if (!WITHIN(position_index, 1, NUM_Z_STEPPER_DRIVERS)) { + SERIAL_ECHOF(err_string); + SERIAL_ECHOLNPGM(" index invalid (1.." STRINGIFY(NUM_Z_STEPPER_DRIVERS) ")."); + return; + } + + --position_index; + const xy_pos_t pos = { parser.floatval('X', pos_dest[position_index].x), parser.floatval('Y', pos_dest[position_index].y) @@ -551,7 +552,7 @@ void GcodeSuite::M422_report(const bool forReplay/*=true*/) { SP_Y_STR, z_stepper_align.xy[i].y ); } - #if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) + #if HAS_Z_STEPPER_ALIGN_STEPPER_XY LOOP_L_N(i, NUM_Z_STEPPER_DRIVERS) { report_echo_start(forReplay); SERIAL_ECHOLNPGM_P( diff --git a/Marlin/src/gcode/calibrate/G425.cpp b/Marlin/src/gcode/calibrate/G425.cpp index 906f8cc4194a2..a2dec64bc3a8e 100644 --- a/Marlin/src/gcode/calibrate/G425.cpp +++ b/Marlin/src/gcode/calibrate/G425.cpp @@ -105,13 +105,27 @@ struct measurements_t { }; #if ENABLED(BACKLASH_GCODE) - #define TEMPORARY_BACKLASH_CORRECTION(value) REMEMBER(tbst, backlash.correction, value) + class restorer_correction { + const uint8_t val_; + public: + restorer_correction(const uint8_t temp_val) : val_(backlash.get_correction_uint8()) { backlash.set_correction_uint8(temp_val); } + ~restorer_correction() { backlash.set_correction_uint8(val_); } + }; + + #define TEMPORARY_BACKLASH_CORRECTION(value) restorer_correction restorer_tbst(value) #else #define TEMPORARY_BACKLASH_CORRECTION(value) #endif #if ENABLED(BACKLASH_GCODE) && defined(BACKLASH_SMOOTHING_MM) - #define TEMPORARY_BACKLASH_SMOOTHING(value) REMEMBER(tbsm, backlash.smoothing_mm, value) + class restorer_smoothing { + const float val_; + public: + restorer_smoothing(const float temp_val) : val_(backlash.get_smoothing_mm()) { backlash.set_smoothing_mm(temp_val); } + ~restorer_smoothing() { backlash.set_smoothing_mm(val_); } + }; + + #define TEMPORARY_BACKLASH_SMOOTHING(value) restorer_smoothing restorer_tbsm(value) #else #define TEMPORARY_BACKLASH_SMOOTHING(value) #endif @@ -524,7 +538,7 @@ inline void calibrate_backlash(measurements_t &m, const float uncertainty) { { // New scope for TEMPORARY_BACKLASH_CORRECTION - TEMPORARY_BACKLASH_CORRECTION(all_off); + TEMPORARY_BACKLASH_CORRECTION(backlash.all_off); TEMPORARY_BACKLASH_SMOOTHING(0.0f); probe_sides(m, uncertainty); @@ -532,45 +546,45 @@ inline void calibrate_backlash(measurements_t &m, const float uncertainty) { #if ENABLED(BACKLASH_GCODE) #if HAS_X_CENTER - backlash.distance_mm.x = (m.backlash[LEFT] + m.backlash[RIGHT]) / 2; + backlash.set_distance_mm(X_AXIS, (m.backlash[LEFT] + m.backlash[RIGHT]) / 2); #elif ENABLED(CALIBRATION_MEASURE_LEFT) - backlash.distance_mm.x = m.backlash[LEFT]; + backlash.set_distance_mm(X_AXIS, m.backlash[LEFT]); #elif ENABLED(CALIBRATION_MEASURE_RIGHT) - backlash.distance_mm.x = m.backlash[RIGHT]; + backlash.set_distance_mm(X_AXIS, m.backlash[RIGHT]); #endif #if HAS_Y_CENTER - backlash.distance_mm.y = (m.backlash[FRONT] + m.backlash[BACK]) / 2; + backlash.set_distance_mm(Y_AXIS, (m.backlash[FRONT] + m.backlash[BACK]) / 2); #elif ENABLED(CALIBRATION_MEASURE_FRONT) - backlash.distance_mm.y = m.backlash[FRONT]; + backlash.set_distance_mm(Y_AXIS, m.backlash[FRONT]); #elif ENABLED(CALIBRATION_MEASURE_BACK) - backlash.distance_mm.y = m.backlash[BACK]; + backlash.set_distance_mm(Y_AXIS, m.backlash[BACK]); #endif - TERN_(HAS_Z_AXIS, if (AXIS_CAN_CALIBRATE(Z)) backlash.distance_mm.z = m.backlash[TOP]); + TERN_(HAS_Z_AXIS, if (AXIS_CAN_CALIBRATE(Z)) backlash.set_distance_mm(Z_AXIS, m.backlash[TOP])); #if HAS_I_CENTER - backlash.distance_mm.i = (m.backlash[IMINIMUM] + m.backlash[IMAXIMUM]) / 2; + backlash.set_distance_mm(I_AXIS, (m.backlash[IMINIMUM] + m.backlash[IMAXIMUM]) / 2); #elif ENABLED(CALIBRATION_MEASURE_IMIN) - backlash.distance_mm.i = m.backlash[IMINIMUM]; + backlash.set_distance_mm(I_AXIS, m.backlash[IMINIMUM]); #elif ENABLED(CALIBRATION_MEASURE_IMAX) - backlash.distance_mm.i = m.backlash[IMAXIMUM]; + backlash.set_distance_mm(I_AXIS, m.backlash[IMAXIMUM]); #endif #if HAS_J_CENTER - backlash.distance_mm.j = (m.backlash[JMINIMUM] + m.backlash[JMAXIMUM]) / 2; + backlash.set_distance_mm(J_AXIS, (m.backlash[JMINIMUM] + m.backlash[JMAXIMUM]) / 2); #elif ENABLED(CALIBRATION_MEASURE_JMIN) - backlash.distance_mm.j = m.backlash[JMINIMUM]; + backlash.set_distance_mm(J_AXIS, m.backlash[JMINIMUM]); #elif ENABLED(CALIBRATION_MEASURE_JMAX) - backlash.distance_mm.j = m.backlash[JMAXIMUM]; + backlash.set_distance_mm(J_AXIS, m.backlash[JMAXIMUM]); #endif #if HAS_K_CENTER - backlash.distance_mm.k = (m.backlash[KMINIMUM] + m.backlash[KMAXIMUM]) / 2; + backlash.set_distance_mm(K_AXIS, (m.backlash[KMINIMUM] + m.backlash[KMAXIMUM]) / 2); #elif ENABLED(CALIBRATION_MEASURE_KMIN) - backlash.distance_mm.k = m.backlash[KMINIMUM]; + backlash.set_distance_mm(K_AXIS, m.backlash[KMINIMUM]); #elif ENABLED(CALIBRATION_MEASURE_KMAX) - backlash.distance_mm.k = m.backlash[KMAXIMUM]; + backlash.set_distance_mm(K_AXIS, m.backlash[KMAXIMUM]); #endif #endif // BACKLASH_GCODE @@ -581,7 +595,7 @@ inline void calibrate_backlash(measurements_t &m, const float uncertainty) { // allowed directions to take up any backlash { // New scope for TEMPORARY_BACKLASH_CORRECTION - TEMPORARY_BACKLASH_CORRECTION(all_on); + TEMPORARY_BACKLASH_CORRECTION(backlash.all_on); TEMPORARY_BACKLASH_SMOOTHING(0.0f); const xyz_float_t move = LINEAR_AXIS_ARRAY( AXIS_CAN_CALIBRATE(X) * 3, AXIS_CAN_CALIBRATE(Y) * 3, AXIS_CAN_CALIBRATE(Z) * 3, @@ -611,7 +625,7 @@ inline void update_measurements(measurements_t &m, const AxisEnum axis) { * - Call calibrate_backlash() beforehand for best accuracy */ inline void calibrate_toolhead(measurements_t &m, const float uncertainty, const uint8_t extruder) { - TEMPORARY_BACKLASH_CORRECTION(all_on); + TEMPORARY_BACKLASH_CORRECTION(backlash.all_on); TEMPORARY_BACKLASH_SMOOTHING(0.0f); TERN(HAS_MULTI_HOTEND, set_nozzle(m, extruder), UNUSED(extruder)); @@ -648,7 +662,7 @@ inline void calibrate_toolhead(measurements_t &m, const float uncertainty, const * uncertainty in - How far away from the object to begin probing */ inline void calibrate_all_toolheads(measurements_t &m, const float uncertainty) { - TEMPORARY_BACKLASH_CORRECTION(all_on); + TEMPORARY_BACKLASH_CORRECTION(backlash.all_on); TEMPORARY_BACKLASH_SMOOTHING(0.0f); HOTEND_LOOP() calibrate_toolhead(m, uncertainty, e); @@ -674,7 +688,7 @@ inline void calibrate_all() { TERN_(HAS_HOTEND_OFFSET, reset_hotend_offsets()); - TEMPORARY_BACKLASH_CORRECTION(all_on); + TEMPORARY_BACKLASH_CORRECTION(backlash.all_on); TEMPORARY_BACKLASH_SMOOTHING(0.0f); // Do a fast and rough calibration of the toolheads diff --git a/Marlin/src/gcode/calibrate/G76_M871.cpp b/Marlin/src/gcode/calibrate/G76_M871.cpp index 21bb2c7590066..ad13b20306ae0 100644 --- a/Marlin/src/gcode/calibrate/G76_M871.cpp +++ b/Marlin/src/gcode/calibrate/G76_M871.cpp @@ -109,7 +109,9 @@ static void say_failed_to_calibrate() { SERIAL_ECHOPGM("!Failed to calibra auto g76_probe = [](const TempSensorID sid, celsius_t &targ, const xy_pos_t &nozpos) { do_z_clearance(5.0); // Raise nozzle before probing + ptc.set_enabled(false); const float measured_z = probe.probe_at_point(nozpos, PROBE_PT_STOW, 0, false); // verbose=0, probe_relative=false + ptc.set_enabled(true); if (isnan(measured_z)) SERIAL_ECHOLNPGM("!Received NAN. Aborting."); else { diff --git a/Marlin/src/gcode/calibrate/M425.cpp b/Marlin/src/gcode/calibrate/M425.cpp index 2d36e0d410d56..6b1f56fcf6588 100644 --- a/Marlin/src/gcode/calibrate/M425.cpp +++ b/Marlin/src/gcode/calibrate/M425.cpp @@ -63,7 +63,7 @@ void GcodeSuite::M425() { LOOP_LINEAR_AXES(a) { if (axis_can_calibrate(a) && parser.seen(AXIS_CHAR(a))) { planner.synchronize(); - backlash.distance_mm[a] = parser.has_value() ? parser.value_linear_units() : backlash.get_measurement(AxisEnum(a)); + backlash.set_distance_mm(AxisEnum(a), parser.has_value() ? parser.value_linear_units() : backlash.get_measurement(AxisEnum(a))); noArgs = false; } } @@ -77,25 +77,25 @@ void GcodeSuite::M425() { #ifdef BACKLASH_SMOOTHING_MM if (parser.seen('S')) { planner.synchronize(); - backlash.smoothing_mm = parser.value_linear_units(); + backlash.set_smoothing_mm(parser.value_linear_units()); noArgs = false; } #endif if (noArgs) { SERIAL_ECHOPGM("Backlash Correction "); - if (!backlash.correction) SERIAL_ECHOPGM("in"); + if (!backlash.get_correction_uint8()) SERIAL_ECHOPGM("in"); SERIAL_ECHOLNPGM("active:"); SERIAL_ECHOLNPGM(" Correction Amount/Fade-out: F", backlash.get_correction(), " (F1.0 = full, F0.0 = none)"); SERIAL_ECHOPGM(" Backlash Distance (mm): "); LOOP_LINEAR_AXES(a) if (axis_can_calibrate(a)) { SERIAL_CHAR(' ', AXIS_CHAR(a)); - SERIAL_ECHO(backlash.distance_mm[a]); + SERIAL_ECHO(backlash.get_distance_mm(AxisEnum(a))); SERIAL_EOL(); } #ifdef BACKLASH_SMOOTHING_MM - SERIAL_ECHOLNPGM(" Smoothing (mm): S", backlash.smoothing_mm); + SERIAL_ECHOLNPGM(" Smoothing (mm): S", backlash.get_smoothing_mm()); #endif #if ENABLED(MEASURE_BACKLASH_WHEN_PROBING) @@ -118,15 +118,15 @@ void GcodeSuite::M425_report(const bool forReplay/*=true*/) { SERIAL_ECHOLNPGM_P( PSTR(" M425 F"), backlash.get_correction() #ifdef BACKLASH_SMOOTHING_MM - , PSTR(" S"), LINEAR_UNIT(backlash.smoothing_mm) + , PSTR(" S"), LINEAR_UNIT(backlash.get_smoothing_mm()) #endif , LIST_N(DOUBLE(LINEAR_AXES), - SP_X_STR, LINEAR_UNIT(backlash.distance_mm.x), - SP_Y_STR, LINEAR_UNIT(backlash.distance_mm.y), - SP_Z_STR, LINEAR_UNIT(backlash.distance_mm.z), - SP_I_STR, LINEAR_UNIT(backlash.distance_mm.i), - SP_J_STR, LINEAR_UNIT(backlash.distance_mm.j), - SP_K_STR, LINEAR_UNIT(backlash.distance_mm.k) + SP_X_STR, LINEAR_UNIT(backlash.get_distance_mm(X_AXIS)), + SP_Y_STR, LINEAR_UNIT(backlash.get_distance_mm(Y_AXIS)), + SP_Z_STR, LINEAR_UNIT(backlash.get_distance_mm(Z_AXIS)), + SP_I_STR, LINEAR_UNIT(backlash.get_distance_mm(I_AXIS)), + SP_J_STR, LINEAR_UNIT(backlash.get_distance_mm(J_AXIS)), + SP_K_STR, LINEAR_UNIT(backlash.get_distance_mm(K_AXIS)) ) ); } diff --git a/Marlin/src/gcode/calibrate/M48.cpp b/Marlin/src/gcode/calibrate/M48.cpp index 913ffe30d478c..8b6ea0bf1fae4 100644 --- a/Marlin/src/gcode/calibrate/M48.cpp +++ b/Marlin/src/gcode/calibrate/M48.cpp @@ -35,11 +35,15 @@ #include "../../module/planner.h" #endif +#if HAS_PTC + #include "../../feature/probe_temp_comp.h" +#endif + /** * M48: Z probe repeatability measurement function. * * Usage: - * M48 + * M48 * P = Number of sampled points (4-50, default 10) * X = Sample X position * Y = Sample Y position @@ -47,6 +51,7 @@ * E = Engage Z probe for each reading * L = Number of legs of movement before probe * S = Schizoid (Or Star if you prefer) + * C = Enable probe temperature compensation (0 or 1, default 1) * * This function requires the machine to be homed before invocation. */ @@ -107,6 +112,8 @@ void GcodeSuite::M48() { set_bed_leveling_enabled(false); #endif + TERN_(HAS_PTC, ptc.set_enabled(!parser.seen('C') || parser.value_bool())); + // Work with reasonable feedrates remember_feedrate_scaling_off(); @@ -269,6 +276,9 @@ void GcodeSuite::M48() { // Re-enable bed level correction if it had been on TERN_(HAS_LEVELING, set_bed_leveling_enabled(was_enabled)); + // Re-enable probe temperature correction + TERN_(HAS_PTC, ptc.set_enabled(true)); + report_current_position(); } diff --git a/Marlin/src/gcode/config/M302.cpp b/Marlin/src/gcode/config/M302.cpp index e271dcd469eee..9f4d569d7b2e5 100644 --- a/Marlin/src/gcode/config/M302.cpp +++ b/Marlin/src/gcode/config/M302.cpp @@ -27,6 +27,10 @@ #include "../gcode.h" #include "../../module/temperature.h" +#if ENABLED(DWIN_LCD_PROUI) + #include "../../lcd/e3v2/proui/dwin_defines.h" +#endif + /** * M302: Allow cold extrudes, or set the minimum extrude temperature * @@ -47,6 +51,7 @@ void GcodeSuite::M302() { if (seen_S) { thermalManager.extrude_min_temp = parser.value_celsius(); thermalManager.allow_cold_extrude = (thermalManager.extrude_min_temp == 0); + TERN_(DWIN_LCD_PROUI, HMI_data.ExtMinT = thermalManager.extrude_min_temp); } if (parser.seen('P')) diff --git a/Marlin/src/gcode/control/M111.cpp b/Marlin/src/gcode/control/M111.cpp index 846bf70556764..d6aeb774108b1 100644 --- a/Marlin/src/gcode/control/M111.cpp +++ b/Marlin/src/gcode/control/M111.cpp @@ -22,20 +22,12 @@ #include "../gcode.h" -#if ENABLED(HOST_ACTION_COMMANDS) - #include "../../feature/host_actions.h" -#endif - /** * M111: Set the debug level */ void GcodeSuite::M111() { if (parser.seenval('S')) marlin_debug_flags = parser.value_byte(); - #if EITHER(HOST_ACTION_COMMANDS, HOST_PROMPT_SUPPORT) - if (parser.seenval('H')) hostui.flag.bits = parser.value_byte(); - #endif - static PGMSTR(str_debug_1, STR_DEBUG_ECHO); static PGMSTR(str_debug_2, STR_DEBUG_INFO); static PGMSTR(str_debug_4, STR_DEBUG_ERRORS); diff --git a/Marlin/src/gcode/control/M42.cpp b/Marlin/src/gcode/control/M42.cpp index 77c0ccc49b0f8..1b3a29d10056a 100644 --- a/Marlin/src/gcode/control/M42.cpp +++ b/Marlin/src/gcode/control/M42.cpp @@ -52,7 +52,7 @@ void protected_pin_err() { * S Pin status from 0 - 255 * I Flag to ignore Marlin's pin protection * - * M Pin mode: 0=INPUT 1=OUTPUT 2=INPUT_PULLUP 3=INPUT_PULLDOWN + * T Pin mode: 0=INPUT 1=OUTPUT 2=INPUT_PULLUP 3=INPUT_PULLDOWN */ void GcodeSuite::M42() { const int pin_index = PARSED_PIN_INDEX('P', GET_PIN_MAP_INDEX(LED_PIN)); @@ -63,7 +63,7 @@ void GcodeSuite::M42() { if (!parser.boolval('I') && pin_is_protected(pin)) return protected_pin_err(); bool avoidWrite = false; - if (parser.seenval('M')) { + if (parser.seenval('T')) { switch (parser.value_byte()) { case 0: pinMode(pin, INPUT); avoidWrite = true; break; case 1: pinMode(pin, OUTPUT); break; @@ -126,10 +126,10 @@ void GcodeSuite::M42() { extDigitalWrite(pin, pin_status); #ifdef ARDUINO_ARCH_STM32 - // A simple I/O will be set to 0 by set_pwm_duty() + // A simple I/O will be set to 0 by hal.set_pwm_duty() if (pin_status <= 1 && !PWM_PIN(pin)) return; #endif - set_pwm_duty(pin, pin_status); + hal.set_pwm_duty(pin, pin_status); } #endif // DIRECT_PIN_CONTROL diff --git a/Marlin/src/gcode/control/M997.cpp b/Marlin/src/gcode/control/M997.cpp index 359172faad7ce..74ed8b0d073e8 100644 --- a/Marlin/src/gcode/control/M997.cpp +++ b/Marlin/src/gcode/control/M997.cpp @@ -24,7 +24,7 @@ #if ENABLED(PLATFORM_M997_SUPPORT) -#if ENABLED(DWIN_CREALITY_LCD_ENHANCED) +#if ENABLED(DWIN_LCD_PROUI) #include "../../lcd/e3v2/proui/dwin.h" #endif @@ -33,7 +33,7 @@ */ void GcodeSuite::M997() { - TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_RebootScreen()); + TERN_(DWIN_LCD_PROUI, DWIN_RebootScreen()); flashFirmware(parser.intval('S')); diff --git a/Marlin/src/gcode/feature/powerloss/M1000.cpp b/Marlin/src/gcode/feature/powerloss/M1000.cpp index 6fb99226ce200..1629a154bce3e 100644 --- a/Marlin/src/gcode/feature/powerloss/M1000.cpp +++ b/Marlin/src/gcode/feature/powerloss/M1000.cpp @@ -33,7 +33,7 @@ #include "../../../lcd/extui/ui_api.h" #elif ENABLED(DWIN_CREALITY_LCD) #include "../../../lcd/e3v2/creality/dwin.h" -#elif ENABLED(DWIN_CREALITY_LCD_ENHANCED) +#elif ENABLED(DWIN_LCD_PROUI) #include "../../../lcd/e3v2/proui/dwin.h" #elif ENABLED(DWIN_CREALITY_LCD_JYERSUI) #include "../../../lcd/e3v2/jyersui/dwin.h" // Temporary fix until it can be better implemented diff --git a/Marlin/src/gcode/feature/powerloss/M413.cpp b/Marlin/src/gcode/feature/powerloss/M413.cpp index 0ccbfe6341ad7..4807d3e8f95b9 100644 --- a/Marlin/src/gcode/feature/powerloss/M413.cpp +++ b/Marlin/src/gcode/feature/powerloss/M413.cpp @@ -48,9 +48,8 @@ void GcodeSuite::M413() { if (parser.seen_test('W')) recovery.save(true); if (parser.seen_test('P')) recovery.purge(); if (parser.seen_test('D')) recovery.debug(F("M413")); - #if PIN_EXISTS(POWER_LOSS) - if (parser.seen_test('O')) recovery._outage(); - #endif + if (parser.seen_test('O')) recovery._outage(true); + if (parser.seen_test('C')) recovery.check(); if (parser.seen_test('E')) SERIAL_ECHOF(recovery.exists() ? F("PLR Exists\n") : F("No PLR\n")); if (parser.seen_test('V')) SERIAL_ECHOF(recovery.valid() ? F("Valid\n") : F("Invalid\n")); #endif diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index 78dd0bc680078..6e331c1273837 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -91,7 +91,7 @@ * *** Print from Media (SDSUPPORT) *** * M20 - List SD card. (Requires SDSUPPORT) - * M21 - Init SD card. (Requires SDSUPPORT) + * M21 - Init SD card. (Requires SDSUPPORT) With MULTI_VOLUME select a drive with `M21 Pn` / 'M21 S' / 'M21 U'. * M22 - Release SD card. (Requires SDSUPPORT) * M23 - Select SD file: "M23 /path/file.gco". (Requires SDSUPPORT) * M24 - Start/resume SD print. (Requires SDSUPPORT) @@ -1195,6 +1195,11 @@ class GcodeSuite { static void M1000(); #endif + #if ENABLED(X_AXIS_TWIST_COMPENSATION) + static void M423(); + static void M423_report(const bool forReplay=true); + #endif + #if ENABLED(SDSUPPORT) static void M1001(); #endif diff --git a/Marlin/src/gcode/gcode_d.cpp b/Marlin/src/gcode/gcode_d.cpp index 204455e65ec60..2dd1de00013b4 100644 --- a/Marlin/src/gcode/gcode_d.cpp +++ b/Marlin/src/gcode/gcode_d.cpp @@ -38,7 +38,7 @@ #include "../sd/cardreader.h" #include "../MarlinCore.h" // for kill -extern void dump_delay_accuracy_check(); +void dump_delay_accuracy_check(); /** * Dn: G-code for development and testing @@ -54,7 +54,7 @@ void GcodeSuite::D(const int16_t dcode) { for (;;) { /* loop forever (watchdog reset) */ } case 0: - HAL_reboot(); + hal.reboot(); break; case 10: @@ -74,7 +74,7 @@ void GcodeSuite::D(const int16_t dcode) { settings.reset(); settings.save(); #endif - HAL_reboot(); + hal.reboot(); } break; case 2: { // D2 Read / Write SRAM @@ -189,12 +189,12 @@ void GcodeSuite::D(const int16_t dcode) { SERIAL_ECHOLNPGM("(USE_WATCHDOG " TERN(USE_WATCHDOG, "ENABLED", "DISABLED") ")"); thermalManager.disable_all_heaters(); delay(1000); // Allow time to print - DISABLE_ISRS(); + hal.isr_off(); // Use a low-level delay that does not rely on interrupts to function // Do not spin forever, to avoid thermal risks if heaters are enabled and // watchdog does not work. for (int i = 10000; i--;) DELAY_US(1000UL); - ENABLE_ISRS(); + hal.isr_on(); SERIAL_ECHOLNPGM("FAILURE: Watchdog did not trigger board reset."); } break; diff --git a/Marlin/src/gcode/geometry/M206_M428.cpp b/Marlin/src/gcode/geometry/M206_M428.cpp index 131dbecf3343a..b32d729969405 100644 --- a/Marlin/src/gcode/geometry/M206_M428.cpp +++ b/Marlin/src/gcode/geometry/M206_M428.cpp @@ -92,7 +92,7 @@ void GcodeSuite::M428() { if (!WITHIN(diff[i], -20, 20)) { SERIAL_ERROR_MSG(STR_ERR_M428_TOO_FAR); LCD_ALERTMESSAGE_F("Err: Too far!"); - BUZZ(200, 40); + ERR_BUZZ(); return; } } @@ -100,8 +100,7 @@ void GcodeSuite::M428() { LOOP_LINEAR_AXES(i) set_home_offset((AxisEnum)i, diff[i]); report_current_position(); LCD_MESSAGE(MSG_HOME_OFFSETS_APPLIED); - BUZZ(100, 659); - BUZZ(100, 698); + OKAY_BUZZ(); } #endif // HAS_M206_COMMAND diff --git a/Marlin/src/gcode/host/M115.cpp b/Marlin/src/gcode/host/M115.cpp index 45e0061a5b842..36731c23da16f 100644 --- a/Marlin/src/gcode/host/M115.cpp +++ b/Marlin/src/gcode/host/M115.cpp @@ -142,6 +142,11 @@ void GcodeSuite::M115() { // SDCARD (M20, M23, M24, etc.) cap_line(F("SDCARD"), ENABLED(SDSUPPORT)); + // MULTI_VOLUME (M21 S/M21 U) + #if ENABLED(SDSUPPORT) + cap_line(F("MULTI_VOLUME"), ENABLED(MULTI_VOLUME)); + #endif + // REPEAT (M808) cap_line(F("REPEAT"), ENABLED(GCODE_REPEAT_MARKERS)); diff --git a/Marlin/src/gcode/lcd/M0_M1.cpp b/Marlin/src/gcode/lcd/M0_M1.cpp index a9223dda47f2e..af03fcb0b1a1c 100644 --- a/Marlin/src/gcode/lcd/M0_M1.cpp +++ b/Marlin/src/gcode/lcd/M0_M1.cpp @@ -35,7 +35,7 @@ #include "../../lcd/marlinui.h" #elif ENABLED(EXTENSIBLE_UI) #include "../../lcd/extui/ui_api.h" -#elif ENABLED(DWIN_CREALITY_LCD_ENHANCED) +#elif ENABLED(DWIN_LCD_PROUI) #include "../../lcd/e3v2/proui/dwin_popup.h" #include "../../lcd/e3v2/proui/dwin.h" #endif @@ -71,7 +71,7 @@ void GcodeSuite::M0_M1() { ExtUI::onUserConfirmRequired(parser.string_arg); // String in an SRAM buffer else ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_USERWAIT)); - #elif ENABLED(DWIN_CREALITY_LCD_ENHANCED) + #elif ENABLED(DWIN_LCD_PROUI) if (parser.string_arg) DWIN_Popup_Confirm(ICON_BLTouch, parser.string_arg, GET_TEXT_F(MSG_USERWAIT)); else diff --git a/Marlin/src/gcode/lcd/M73.cpp b/Marlin/src/gcode/lcd/M73.cpp index c2c5485072e5f..355445c573b99 100644 --- a/Marlin/src/gcode/lcd/M73.cpp +++ b/Marlin/src/gcode/lcd/M73.cpp @@ -28,7 +28,7 @@ #include "../../lcd/marlinui.h" #include "../../sd/cardreader.h" -#if ENABLED(DWIN_CREALITY_LCD_ENHANCED) +#if ENABLED(DWIN_LCD_PROUI) #include "../../lcd/e3v2/proui/dwin.h" #endif @@ -40,7 +40,7 @@ */ void GcodeSuite::M73() { - #if ENABLED(DWIN_CREALITY_LCD_ENHANCED) + #if ENABLED(DWIN_LCD_PROUI) DWIN_Progress_Update(); diff --git a/Marlin/src/gcode/probe/G30.cpp b/Marlin/src/gcode/probe/G30.cpp index f4152c76e9e5f..474f1f252a048 100644 --- a/Marlin/src/gcode/probe/G30.cpp +++ b/Marlin/src/gcode/probe/G30.cpp @@ -29,6 +29,10 @@ #include "../../module/probe.h" #include "../../feature/bedlevel/bedlevel.h" +#if HAS_PTC + #include "../../feature/probe_temp_comp.h" +#endif + /** * G30: Do a single Z probe at the current XY * @@ -37,6 +41,7 @@ * X Probe X position (default current X) * Y Probe Y position (default current Y) * E Engage the probe for each probe (default 1) + * C Enable probe temperature compensation (0 or 1, default 1) */ void GcodeSuite::G30() { @@ -51,7 +56,10 @@ void GcodeSuite::G30() { remember_feedrate_scaling_off(); const ProbePtRaise raise_after = parser.boolval('E', true) ? PROBE_PT_STOW : PROBE_PT_NONE; + + TERN_(HAS_PTC, ptc.set_enabled(!parser.seen('C') || parser.value_bool())); const float measured_z = probe.probe_at_point(pos, raise_after, 1); + TERN_(HAS_PTC, ptc.set_enabled(true)); if (!isnan(measured_z)) SERIAL_ECHOLNPGM("Bed X: ", pos.x, " Y: ", pos.y, " Z: ", measured_z); diff --git a/Marlin/src/gcode/probe/M401_M402.cpp b/Marlin/src/gcode/probe/M401_M402.cpp index 7cbae76f4b88e..33895749193fc 100644 --- a/Marlin/src/gcode/probe/M401_M402.cpp +++ b/Marlin/src/gcode/probe/M401_M402.cpp @@ -36,12 +36,18 @@ * M401: Deploy and activate the Z probe * * With BLTOUCH_HS_MODE: + * H Report the current BLTouch HS mode state and exit * S Set High Speed (HS) Mode and exit without deploy */ void GcodeSuite::M401() { - if (parser.seen('S')) { + const bool seenH = parser.seen_test('H'), + seenS = parser.seen('S'); + if (seenH || seenS) { #ifdef BLTOUCH_HS_MODE - bltouch.high_speed_mode = parser.value_bool(); + if (seenS) bltouch.high_speed_mode = parser.value_bool(); + SERIAL_ECHO_START(); + SERIAL_ECHOPGM("BLTouch HS mode "); + serialprintln_onoff(bltouch.high_speed_mode); #endif } else { diff --git a/Marlin/src/gcode/probe/M423.cpp b/Marlin/src/gcode/probe/M423.cpp new file mode 100644 index 0000000000000..fde5aaaf87c90 --- /dev/null +++ b/Marlin/src/gcode/probe/M423.cpp @@ -0,0 +1,99 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2022 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 . + * + */ + +/** + * M423.cpp - X-Axis Twist Compensation + */ + +#include "../../inc/MarlinConfig.h" + +#if ENABLED(X_AXIS_TWIST_COMPENSATION) + +#include "../gcode.h" +#include "../../feature/x_twist.h" +#include "../../module/probe.h" + +/** + * M423: Set a Z offset for X-Twist (added to the mesh on future G29). + * M423 [R] [A] [I] [X Z] + * + * R - Reset the twist compensation data + * A - Set the X twist starting X position + * E - Set the X twist ending X position + * I - Set the X twist X-spacing directly + * X - Index of a Z value in the list + * Z - A Z value to set + */ +void GcodeSuite::M423() { + + bool do_report = true; + float new_spacing = 0; + + if (parser.seen_test('R')) { + do_report = false; + xatc.reset(); + } + if (parser.seenval('A')) { + do_report = false; + xatc.start = parser.value_float(); + new_spacing = (probe.max_x() - xatc.start) / (XATC_MAX_POINTS - 1); + } + if (parser.seenval('E')) { + do_report = false; + new_spacing = (parser.value_float() - xatc.start) / (XATC_MAX_POINTS - 1); + } + else if (parser.seenval('I')) { + do_report = false; + new_spacing = parser.value_float(); + } + + if (new_spacing) xatc.spacing = new_spacing; + + if (parser.seenval('X')) { + do_report = false; + const int8_t x = parser.value_int(); + if (!WITHIN(x, 0, XATC_MAX_POINTS - 1)) + SERIAL_ECHOLNPGM("?(X) out of range (0..", XATC_MAX_POINTS - 1, ")."); + else { + if (parser.seenval('Z')) + xatc.z_offset[x] = parser.value_linear_units(); + else + SERIAL_ECHOLNPGM("?(Z) required."); + } + } + + if (do_report) M423_report(); + +} + +void GcodeSuite::M423_report(const bool forReplay/*=true*/) { + report_heading(forReplay, F("X-Twist Correction")); + SERIAL_ECHOLNPGM(" M423 A", xatc.start, " I", xatc.spacing); + LOOP_L_N(x, XATC_MAX_POINTS) { + const float z = xatc.z_offset[x]; + SERIAL_ECHOPGM(" M423 X", x, " Z"); + serial_offset(isnan(z) ? 0 : z); + SERIAL_EOL(); + } +} + +#endif // X_AXIS_TWIST_COMPENSATION diff --git a/Marlin/src/gcode/sd/M1001.cpp b/Marlin/src/gcode/sd/M1001.cpp index 1579efd555579..197177882c317 100644 --- a/Marlin/src/gcode/sd/M1001.cpp +++ b/Marlin/src/gcode/sd/M1001.cpp @@ -49,7 +49,7 @@ #if ENABLED(EXTENSIBLE_UI) #include "../../lcd/extui/ui_api.h" -#elif ENABLED(DWIN_CREALITY_LCD_ENHANCED) +#elif ENABLED(DWIN_LCD_PROUI) #include "../../lcd/e3v2/proui/dwin.h" #endif @@ -108,8 +108,8 @@ void GcodeSuite::M1001() { process_subcommands_now(F(SD_FINISHED_RELEASECOMMAND)); #endif - TERN_(EXTENSIBLE_UI, ExtUI::onPrintFinished()); - TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_Print_Finished()); + TERN_(EXTENSIBLE_UI, ExtUI::onPrintDone()); + TERN_(DWIN_LCD_PROUI, DWIN_Print_Finished()); // Re-select the last printed file in the UI TERN_(SD_REPRINT_LAST_SELECTED_FILE, ui.reselect_last_file()); diff --git a/Marlin/src/gcode/sd/M21_M22.cpp b/Marlin/src/gcode/sd/M21_M22.cpp index c7f41f9c817e0..aec0de27ca5c5 100644 --- a/Marlin/src/gcode/sd/M21_M22.cpp +++ b/Marlin/src/gcode/sd/M21_M22.cpp @@ -29,8 +29,21 @@ /** * M21: Init SD Card + * + * With MULTI_VOLUME: + * P0 or S - Change to the SD Card and mount it + * P1 or U - Change to the USB Drive and mount it */ -void GcodeSuite::M21() { card.mount(); } +void GcodeSuite::M21() { + #if ENABLED(MULTI_VOLUME) + const int8_t vol = parser.intval('P', -1); + if (vol == 0 || parser.seen_test('S')) // "S" for SD Card + card.changeMedia(&card.media_driver_sdcard); + else if (vol == 1 || parser.seen_test('U')) // "U" for USB + card.changeMedia(&card.media_driver_usbFlash); + #endif + card.mount(); +} /** * M22: Release SD Card diff --git a/Marlin/src/gcode/sd/M524.cpp b/Marlin/src/gcode/sd/M524.cpp index e7159155655c7..001a1e184263a 100644 --- a/Marlin/src/gcode/sd/M524.cpp +++ b/Marlin/src/gcode/sd/M524.cpp @@ -27,15 +27,27 @@ #include "../gcode.h" #include "../../sd/cardreader.h" +#if ENABLED(DWIN_LCD_PROUI) + #include "../../lcd/e3v2/proui/dwin.h" +#endif + /** * M524: Abort the current SD print job (started with M24) */ void GcodeSuite::M524() { - if (IS_SD_PRINTING()) - card.abortFilePrintSoon(); - else if (card.isMounted()) - card.closefile(); + #if ENABLED(DWIN_LCD_PROUI) + + HMI_flag.abort_flag = true; // The LCD will handle it + + #else + + if (IS_SD_PRINTING()) + card.abortFilePrintSoon(); + else if (card.isMounted()) + card.closefile(); + + #endif } diff --git a/Marlin/src/gcode/stats/M75-M78.cpp b/Marlin/src/gcode/stats/M75-M78.cpp index 368edb65d912e..0ed1e66930136 100644 --- a/Marlin/src/gcode/stats/M75-M78.cpp +++ b/Marlin/src/gcode/stats/M75-M78.cpp @@ -29,7 +29,7 @@ #include "../../MarlinCore.h" // for startOrResumeJob -#if ENABLED(DWIN_CREALITY_LCD_ENHANCED) +#if ENABLED(DWIN_LCD_PROUI) #include "../../lcd/e3v2/proui/dwin.h" #endif @@ -38,9 +38,9 @@ */ void GcodeSuite::M75() { startOrResumeJob(); - #if ENABLED(DWIN_CREALITY_LCD_ENHANCED) - DWIN_Print_Header(parser.string_arg && parser.string_arg[0] ? parser.string_arg : GET_TEXT(MSG_HOST_START_PRINT)); + #if ENABLED(DWIN_LCD_PROUI) DWIN_Print_Started(false); + if (!IS_SD_PRINTING()) DWIN_Print_Header(parser.string_arg && parser.string_arg[0] ? parser.string_arg : GET_TEXT(MSG_HOST_START_PRINT)); #endif } @@ -50,6 +50,7 @@ void GcodeSuite::M75() { void GcodeSuite::M76() { print_job_timer.pause(); TERN_(HOST_PAUSE_M76, hostui.pause()); + TERN_(DWIN_LCD_PROUI, DWIN_Print_Pause()); } /** @@ -57,7 +58,7 @@ void GcodeSuite::M76() { */ void GcodeSuite::M77() { print_job_timer.stop(); - TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_Print_Finished()); + TERN_(DWIN_LCD_PROUI, DWIN_Print_Finished()); } #if ENABLED(PRINTCOUNTER) diff --git a/Marlin/src/gcode/temp/M303.cpp b/Marlin/src/gcode/temp/M303.cpp index 7b56eb2d6ba95..c1e400511c915 100644 --- a/Marlin/src/gcode/temp/M303.cpp +++ b/Marlin/src/gcode/temp/M303.cpp @@ -30,7 +30,7 @@ #if ENABLED(EXTENSIBLE_UI) #include "../../lcd/extui/ui_api.h" -#elif ENABLED(DWIN_CREALITY_LCD_ENHANCED) +#elif ENABLED(DWIN_LCD_PROUI) #include "../../lcd/e3v2/proui/dwin.h" #endif @@ -73,7 +73,7 @@ void GcodeSuite::M303() { default: SERIAL_ECHOLNPGM(STR_PID_BAD_HEATER_ID); TERN_(EXTENSIBLE_UI, ExtUI::onPidTuning(ExtUI::result_t::PID_BAD_EXTRUDER_NUM)); - TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_PidTuning(PID_BAD_EXTRUDER_NUM)); + TERN_(DWIN_LCD_PROUI, DWIN_PidTuning(PID_BAD_EXTRUDER_NUM)); return; } @@ -83,7 +83,7 @@ void GcodeSuite::M303() { const celsius_t temp = seenS ? parser.value_celsius() : default_temp; const bool u = parser.boolval('U'); - #if ENABLED(DWIN_CREALITY_LCD_ENHANCED) + #if ENABLED(DWIN_LCD_PROUI) if (seenC) HMI_data.PidCycles = c; if (seenS) { if (hid == H_BED) HMI_data.BedPidT = temp; else HMI_data.HotendPidT = temp; } #endif diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index f4b517dd2356a..33d9e462209d6 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -473,12 +473,15 @@ #endif // Aliases for LCD features -#if EITHER(DWIN_CREALITY_LCD, DWIN_CREALITY_LCD_ENHANCED) +#if EITHER(DWIN_CREALITY_LCD, DWIN_LCD_PROUI) #define HAS_DWIN_E3V2_BASIC 1 #endif #if EITHER(HAS_DWIN_E3V2_BASIC, DWIN_CREALITY_LCD_JYERSUI) #define HAS_DWIN_E3V2 1 #endif +#if ENABLED(DWIN_LCD_PROUI) + #define DO_LIST_BIN_FILES 1 +#endif // E3V2 extras #if HAS_DWIN_E3V2 || IS_DWIN_MARLINUI @@ -494,7 +497,7 @@ #endif #define HAS_LCD_BRIGHTNESS 1 #define LCD_BRIGHTNESS_MAX 250 - #if ENABLED(DWIN_CREALITY_LCD_ENHANCED) + #if ENABLED(DWIN_LCD_PROUI) #define LCD_BRIGHTNESS_DEFAULT 127 #endif #endif @@ -513,10 +516,14 @@ #endif #endif -#if ANY(HAS_WIRED_LCD, EXTENSIBLE_UI, DWIN_CREALITY_LCD_JYERSUI) +#if ANY(HAS_WIRED_LCD, EXTENSIBLE_UI, DWIN_LCD_PROUI, DWIN_CREALITY_LCD_JYERSUI) #define HAS_DISPLAY 1 #endif +#if HAS_WIRED_LCD && !HAS_GRAPHICAL_TFT && !IS_DWIN_MARLINUI + #define HAS_LCDPRINT 1 +#endif + #if ANY(HAS_DISPLAY, HAS_DWIN_E3V2, GLOBAL_STATUS_MESSAGE) #define HAS_STATUS_MESSAGE 1 #endif diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h index 7b628d448ed65..d63395a7199fb 100644 --- a/Marlin/src/inc/Conditionals_adv.h +++ b/Marlin/src/inc/Conditionals_adv.h @@ -23,7 +23,7 @@ /** * Conditionals_adv.h - * Defines that depend on advanced configuration. + * Conditionals set before pins.h and which depend on Configuration_adv.h. */ #ifndef AXIS_RELATIVE_MODES @@ -630,7 +630,8 @@ #endif #if ENABLED(Z_STEPPER_AUTO_ALIGN) - #if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) + #ifdef Z_STEPPER_ALIGN_STEPPER_XY + #define HAS_Z_STEPPER_ALIGN_STEPPER_XY 1 #undef Z_STEPPER_ALIGN_AMP #endif #ifndef Z_STEPPER_ALIGN_AMP @@ -986,7 +987,7 @@ #endif // Flag whether least_squares_fit.cpp is used -#if ANY(AUTO_BED_LEVELING_UBL, AUTO_BED_LEVELING_LINEAR, Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) +#if ANY(AUTO_BED_LEVELING_UBL, AUTO_BED_LEVELING_LINEAR, HAS_Z_STEPPER_ALIGN_STEPPER_XY) #define NEED_LSF 1 #endif diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 37f0a5cbe5d6e..547ca36e92d3a 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -23,7 +23,7 @@ /** * Conditionals_post.h - * Defines that depend on configuration but are not editable. + * Internal defines that depend on Configurations and Pins but are not user-editable. */ #ifdef GITHUB_ACTIONS @@ -459,8 +459,8 @@ #endif -#if ANY(HAS_GRAPHICAL_TFT, LCD_USE_DMA_FSMC, HAS_FSMC_GRAPHICAL_TFT, HAS_SPI_GRAPHICAL_TFT, IS_DWIN_MARLINUI) || !PIN_EXISTS(SD_DETECT) - #define NO_LCD_REINIT 1 // Suppress LCD re-initialization +#if PIN_EXISTS(SD_DETECT) && NONE(HAS_GRAPHICAL_TFT, LCD_USE_DMA_FSMC, HAS_FSMC_GRAPHICAL_TFT, HAS_SPI_GRAPHICAL_TFT, IS_DWIN_MARLINUI, EXTENSIBLE_UI) + #define REINIT_NOISY_LCD 1 // Have the LCD re-init on SD insertion #endif /** @@ -3177,7 +3177,7 @@ * Advanced Pause - Filament Change */ #if ENABLED(ADVANCED_PAUSE_FEATURE) - #if ANY(HAS_MARLINUI_MENU, EXTENSIBLE_UI, DWIN_CREALITY_LCD_ENHANCED, DWIN_CREALITY_LCD_JYERSUI) || BOTH(EMERGENCY_PARSER, HOST_PROMPT_SUPPORT) + #if ANY(HAS_MARLINUI_MENU, EXTENSIBLE_UI, DWIN_LCD_PROUI, DWIN_CREALITY_LCD_JYERSUI) || BOTH(EMERGENCY_PARSER, HOST_PROMPT_SUPPORT) #define M600_PURGE_MORE_RESUMABLE 1 #endif #ifndef FILAMENT_CHANGE_SLOW_LOAD_LENGTH diff --git a/Marlin/src/inc/MarlinConfig.h b/Marlin/src/inc/MarlinConfig.h index 8fdb4b9baeaee..505a0682ebaaa 100644 --- a/Marlin/src/inc/MarlinConfig.h +++ b/Marlin/src/inc/MarlinConfig.h @@ -29,6 +29,7 @@ #ifndef __MARLIN_DEPS__ #include "../HAL/HAL.h" + extern MarlinHAL hal; #endif #include "../pins/pins.h" diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index f154592f4e489..a94846275e449 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -609,6 +609,14 @@ #error "LCD_SCREEN_ROT_270 is now LCD_SCREEN_ROTATE with a value of 270." #elif defined(DEFAULT_LCD_BRIGHTNESS) #error "DEFAULT_LCD_BRIGHTNESS is now LCD_BRIGHTNESS_DEFAULT." +#elif defined(NOZZLE_PARK_X_ONLY) + #error "NOZZLE_PARK_X_ONLY is now NOZZLE_PARK_MOVE 1." +#elif defined(NOZZLE_PARK_Y_ONLY) + #error "NOZZLE_PARK_X_ONLY is now NOZZLE_PARK_MOVE 2." +#elif defined(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) + #error "Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS is now just Z_STEPPER_ALIGN_STEPPER_XY." +#elif defined(DWIN_CREALITY_LCD_ENHANCED) + #error "DWIN_CREALITY_LCD_ENHANCED is now DWIN_LCD_PROUI." #endif constexpr float arm[] = AXIS_RELATIVE_MODES; @@ -840,7 +848,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "PROGRESS_MSG_EXPIRE must be greater than or equal to 0." #endif #elif ENABLED(LCD_SET_PROGRESS_MANUALLY) && NONE(HAS_MARLINUI_U8GLIB, HAS_GRAPHICAL_TFT, HAS_MARLINUI_HD44780, EXTENSIBLE_UI, HAS_DWIN_E3V2, IS_DWIN_MARLINUI) - #error "LCD_SET_PROGRESS_MANUALLY requires LCD_PROGRESS_BAR, Character LCD, Graphical LCD, TFT, DWIN_CREALITY_LCD, DWIN_CREALITY_LCD_ENHANCED, DWIN_CREALITY_LCD_JYERSUI, DWIN_MARLINUI_*, OR EXTENSIBLE_UI." + #error "LCD_SET_PROGRESS_MANUALLY requires LCD_PROGRESS_BAR, Character LCD, Graphical LCD, TFT, DWIN_CREALITY_LCD, DWIN_LCD_PROUI, DWIN_CREALITY_LCD_JYERSUI, DWIN_MARLINUI_*, OR EXTENSIBLE_UI." #endif #if ENABLED(USE_M73_REMAINING_TIME) && DISABLED(LCD_SET_PROGRESS_MANUALLY) @@ -856,6 +864,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS */ #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(SHOW_CUSTOM_BOOTSCREEN) && DISABLED(SHOW_BOOTSCREEN) + #error "SHOW_CUSTOM_BOOTSCREEN requires SHOW_BOOTSCREEN." #elif ENABLED(CUSTOM_STATUS_SCREEN_IMAGE) && !HAS_MARLINUI_U8GLIB #error "CUSTOM_STATUS_SCREEN_IMAGE requires a 128x64 DOGM B/W Graphical LCD." #endif @@ -1568,10 +1578,14 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #else #define _IS_5V_TOLERANT(P) 1 // Assume 5V tolerance #endif - #if USES_Z_MIN_PROBE_PIN && !_IS_5V_TOLERANT(Z_MIN_PROBE_PIN) - #error "BLTOUCH_SET_5V_MODE is not compatible with the Z_MIN_PROBE_PIN." + #if USES_Z_MIN_PROBE_PIN + #if !_IS_5V_TOLERANT(Z_MIN_PROBE_PIN) + #error "BLTOUCH_SET_5V_MODE is not compatible with the Z_MIN_PROBE_PIN." + #endif #elif !_IS_5V_TOLERANT(Z_MIN_PIN) - #error "BLTOUCH_SET_5V_MODE is not compatible with the Z_MIN_PIN." + #if !MB(CHITU3D_V6) + #error "BLTOUCH_SET_5V_MODE is not compatible with the Z_MIN_PIN." + #endif #endif #undef _IS_5V_TOLERANT #undef _5V @@ -1818,7 +1832,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS * LCD_BED_LEVELING requirements */ #if ENABLED(LCD_BED_LEVELING) - #if NONE(HAS_MARLINUI_MENU, DWIN_CREALITY_LCD, DWIN_CREALITY_LCD_ENHANCED) + #if NONE(HAS_MARLINUI_MENU, DWIN_CREALITY_LCD, DWIN_LCD_PROUI) #error "LCD_BED_LEVELING is not supported by the selected LCD controller." #elif !(ENABLED(MESH_BED_LEVELING) || HAS_ABL_NOT_UBL) #error "LCD_BED_LEVELING requires MESH_BED_LEVELING or AUTO_BED_LEVELING." @@ -2169,9 +2183,9 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS * Test Sensor & Heater pin combos. * Pins and Sensor IDs must be set for each heater */ -#if !ANY_PIN(TEMP_0, TEMP_0_CS) +#if HAS_EXTRUDERS && !ANY_PIN(TEMP_0, TEMP_0_CS) #error "TEMP_0_PIN or TEMP_0_CS_PIN not defined for this board." -#elif !HAS_HEATER_0 && EXTRUDERS +#elif HAS_EXTRUDERS && !HAS_HEATER_0 #error "HEATER_0_PIN not defined for this board." #elif TEMP_SENSOR_0_IS_MAX_TC && !PIN_EXISTS(TEMP_0_CS) #error "TEMP_SENSOR_0 MAX thermocouple requires TEMP_0_CS_PIN." @@ -2707,7 +2721,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS + COUNT_ENABLED(ANYCUBIC_LCD_I3MEGA, ANYCUBIC_LCD_CHIRON, ANYCUBIC_TFT35) \ + COUNT_ENABLED(DGUS_LCD_UI_ORIGIN, DGUS_LCD_UI_FYSETC, DGUS_LCD_UI_HIPRECY, DGUS_LCD_UI_MKS, DGUS_LCD_UI_RELOADED) \ + COUNT_ENABLED(ENDER2_STOCKDISPLAY, CR10_STOCKDISPLAY) \ - + COUNT_ENABLED(DWIN_CREALITY_LCD, DWIN_CREALITY_LCD_ENHANCED, DWIN_CREALITY_LCD_JYERSUI, DWIN_MARLINUI_PORTRAIT, DWIN_MARLINUI_LANDSCAPE) \ + + COUNT_ENABLED(DWIN_CREALITY_LCD, DWIN_LCD_PROUI, DWIN_CREALITY_LCD_JYERSUI, DWIN_MARLINUI_PORTRAIT, DWIN_MARLINUI_LANDSCAPE) \ + COUNT_ENABLED(FYSETC_MINI_12864_X_X, FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0, FYSETC_GENERIC_12864_1_1) \ + COUNT_ENABLED(LCD_SAINSMART_I2C_1602, LCD_SAINSMART_I2C_2004) \ + COUNT_ENABLED(MKS_12864OLED, MKS_12864OLED_SSD1306) \ @@ -2837,17 +2851,25 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #elif BOTH(LCD_BED_LEVELING, PROBE_MANUALLY) #error "DWIN_CREALITY_LCD does not support LCD_BED_LEVELING with PROBE_MANUALLY." #endif -#elif ENABLED(DWIN_CREALITY_LCD_ENHANCED) +#elif ENABLED(DWIN_LCD_PROUI) #if DISABLED(SDSUPPORT) - #error "DWIN_CREALITY_LCD_ENHANCED requires SDSUPPORT to be enabled." + #error "DWIN_LCD_PROUI requires SDSUPPORT to be enabled." #elif ENABLED(PID_EDIT_MENU) - #error "DWIN_CREALITY_LCD_ENHANCED does not support PID_EDIT_MENU." + #error "DWIN_LCD_PROUI does not support PID_EDIT_MENU." #elif ENABLED(PID_AUTOTUNE_MENU) - #error "DWIN_CREALITY_LCD_ENHANCED does not support PID_AUTOTUNE_MENU." + #error "DWIN_LCD_PROUI does not support PID_AUTOTUNE_MENU." #elif ENABLED(LEVEL_BED_CORNERS) - #error "DWIN_CREALITY_LCD_ENHANCED does not support LEVEL_BED_CORNERS." + #error "DWIN_LCD_PROUI does not support LEVEL_BED_CORNERS." #elif BOTH(LCD_BED_LEVELING, PROBE_MANUALLY) - #error "DWIN_CREALITY_LCD_ENHANCED does not support LCD_BED_LEVELING with PROBE_MANUALLY." + #error "DWIN_LCD_PROUI does not support LCD_BED_LEVELING with PROBE_MANUALLY." + #endif +#endif + +#if LCD_BACKLIGHT_TIMEOUT + #if !HAS_ENCODER_ACTION + #error "LCD_BACKLIGHT_TIMEOUT requires an LCD with encoder or keypad." + #elif !PIN_EXISTS(LCD_BACKLIGHT) + #error "LCD_BACKLIGHT_TIMEOUT requires LCD_BACKLIGHT_PIN." #endif #endif @@ -3418,7 +3440,7 @@ static_assert(_PLUS_TEST(4), "HOMING_FEEDRATE_MM_M values must be positive."); #error "A very large BLOCK_BUFFER_SIZE is not needed and takes longer to drain the buffer on pause / cancel." #endif -#if ENABLED(LED_CONTROL_MENU) && NONE(HAS_MARLINUI_MENU, DWIN_CREALITY_LCD_ENHANCED) +#if ENABLED(LED_CONTROL_MENU) && NONE(HAS_MARLINUI_MENU, DWIN_LCD_PROUI) #error "LED_CONTROL_MENU requires an LCD controller that implements the menu." #endif @@ -3447,8 +3469,6 @@ static_assert(_PLUS_TEST(4), "HOMING_FEEDRATE_MM_M values must be positive."); #if ENABLED(POWER_LOSS_RECOVERY) #if ENABLED(BACKUP_POWER_SUPPLY) && !PIN_EXISTS(POWER_LOSS) #error "BACKUP_POWER_SUPPLY requires a POWER_LOSS_PIN." - #elif BOTH(POWER_LOSS_RECOVER_ZHOME, Z_SAFE_HOMING) - #error "POWER_LOSS_RECOVER_ZHOME cannot be used with Z_SAFE_HOMING." #elif BOTH(POWER_LOSS_PULLUP, POWER_LOSS_PULLDOWN) #error "You can't enable POWER_LOSS_PULLUP and POWER_LOSS_PULLDOWN at the same time." #elif ENABLED(POWER_LOSS_RECOVER_ZHOME) && Z_HOME_TO_MAX @@ -3463,10 +3483,10 @@ static_assert(_PLUS_TEST(4), "HOMING_FEEDRATE_MM_M values must be positive."); #error "Z_STEPPER_AUTO_ALIGN requires NUM_Z_STEPPER_DRIVERS greater than 1." #elif !HAS_BED_PROBE #error "Z_STEPPER_AUTO_ALIGN requires a Z-bed probe." - #elif ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) + #elif HAS_Z_STEPPER_ALIGN_STEPPER_XY static_assert(WITHIN(Z_STEPPER_ALIGN_AMP, 0.5, 2.0), "Z_STEPPER_ALIGN_AMP must be between 0.5 and 2.0."); #if NUM_Z_STEPPER_DRIVERS < 3 - #error "Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS requires NUM_Z_STEPPER_DRIVERS to be 3 or 4." + #error "Z_STEPPER_ALIGN_STEPPER_XY requires NUM_Z_STEPPER_DRIVERS to be 3 or 4." #endif #endif #endif @@ -3889,3 +3909,10 @@ static_assert(_PLUS_TEST(4), "HOMING_FEEDRATE_MM_M values must be positive."); #undef _TEST_PWM #undef _LINEAR_AXES_STR #undef _LOGICAL_AXES_STR + +// JTAG support in the HAL +#if ENABLED(DISABLE_DEBUG) && !defined(JTAGSWD_DISABLE) + #error "DISABLE_DEBUG is not supported for the selected MCU/Board." +#elif ENABLED(DISABLE_JTAG) && !defined(JTAG_DISABLE) + #error "DISABLE_JTAG is not supported for the selected MCU/Board." +#endif diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index d850015710e13..76889cb40aadb 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2022-02-08" + #define STRING_DISTRIBUTION_DATE "2022-03-12" #endif /** diff --git a/Marlin/src/inc/Warnings.cpp b/Marlin/src/inc/Warnings.cpp index 95246343c7b38..9d7b14d763ac0 100644 --- a/Marlin/src/inc/Warnings.cpp +++ b/Marlin/src/inc/Warnings.cpp @@ -59,9 +59,9 @@ #warning "Your Configuration provides no method to acquire user feedback!" #endif -#if MB(DUE3DOM_MINI) && PIN_EXISTS(TEMP_2) && DISABLED(TEMP_SENSOR_BOARD) +#if MB(DUE3DOM_MINI) && PIN_EXISTS(TEMP_2) && !TEMP_SENSOR_BOARD #warning "Onboard temperature sensor for BOARD_DUE3DOM_MINI has moved from TEMP_SENSOR_2 (TEMP_2_PIN) to TEMP_SENSOR_BOARD (TEMP_BOARD_PIN)." -#elif MB(BTT_SKR_E3_TURBO) && PIN_EXISTS(TEMP_2) && DISABLED(TEMP_SENSOR_BOARD) +#elif MB(BTT_SKR_E3_TURBO) && PIN_EXISTS(TEMP_2) && !TEMP_SENSOR_BOARD #warning "Onboard temperature sensor for BOARD_BTT_SKR_E3_TURBO has moved from TEMP_SENSOR_2 (TEMP_2_PIN) to TEMP_SENSOR_BOARD (TEMP_BOARD_PIN)." #endif @@ -597,3 +597,10 @@ #ifdef __STM32F1__ #warning "Maple build environments are deprecated. Please use a non-Maple build environment. Report issues to the Marlin Firmware project." #endif + +/** + * Průša MK3/S/+ fan pin reassignment + */ +#if MB(BTT_BTT002_V1_0, EINSY_RAMBO) && DISABLED(NO_MK3_FAN_PINS_WARNING) + #warning "Define MK3_FAN_PINS to swap hotend and part cooling fan pins. (Define NO_MK3_FAN_PINS_WARNING to suppress this warning.)" +#endif diff --git a/Marlin/src/lcd/dogm/marlinui_DOGM.cpp b/Marlin/src/lcd/dogm/marlinui_DOGM.cpp index aafc4d880318b..fc862e54398b2 100644 --- a/Marlin/src/lcd/dogm/marlinui_DOGM.cpp +++ b/Marlin/src/lcd/dogm/marlinui_DOGM.cpp @@ -282,9 +282,9 @@ void MarlinUI::init_lcd() { #if PIN_EXISTS(LCD_RESET) // Perform a clean hardware reset with needed delays OUT_WRITE(LCD_RESET_PIN, LOW); - _delay_ms(5); + hal.delay_ms(5); WRITE(LCD_RESET_PIN, HIGH); - _delay_ms(5); + hal.delay_ms(5); u8g.begin(); #endif diff --git a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp index cac8ffd6ac9ac..c9a44e0c64d00 100644 --- a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp +++ b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp @@ -674,7 +674,7 @@ void MarlinUI::draw_status_screen() { #if CUTTER_UNIT_IS(PERCENT) lcd_put_u8str(STATUS_CUTTER_TEXT_X, STATUS_CUTTER_TEXT_Y, cutter_power2str(cutter.unitPower)); #elif CUTTER_UNIT_IS(RPM) - lcd_put_u8str(STATUS_CUTTER_TEXT_X - 2, STATUS_CUTTER_TEXT_Y, ftostr51rj(float(cutter.unitPower) / 1000)); + lcd_put_u8str(STATUS_CUTTER_TEXT_X - 2, STATUS_CUTTER_TEXT_Y, ftostr61rj(float(cutter.unitPower) / 1000)); lcd_put_wchar('K'); #else lcd_put_u8str(STATUS_CUTTER_TEXT_X, STATUS_CUTTER_TEXT_Y, cutter_power2str(cutter.unitPower)); diff --git a/Marlin/src/lcd/e3v2/common/encoder.h b/Marlin/src/lcd/e3v2/common/encoder.h index e5d9645ed43b8..3ab8c3bf422b5 100644 --- a/Marlin/src/lcd/e3v2/common/encoder.h +++ b/Marlin/src/lcd/e3v2/common/encoder.h @@ -45,12 +45,32 @@ typedef enum { ENCODER_DIFF_ENTER = 3 // click } EncoderState; +#define ENCODER_WAIT_MS 20 + // Encoder initialization void Encoder_Configuration(); // Analyze encoder value and return state EncoderState Encoder_ReceiveAnalyze(); +inline EncoderState get_encoder_state() { + static millis_t Encoder_ms = 0; + const millis_t ms = millis(); + if (PENDING(ms, Encoder_ms)) return ENCODER_DIFF_NO; + const EncoderState state = Encoder_ReceiveAnalyze(); + if (state != ENCODER_DIFF_NO) Encoder_ms = ms + ENCODER_WAIT_MS; + return state; +} + +template +inline bool Apply_Encoder(const EncoderState &encoder_diffState, T &valref) { + if (encoder_diffState == ENCODER_DIFF_CW) + valref += EncoderRate.encoderMoveValue; + else if (encoder_diffState == ENCODER_DIFF_CCW) + valref -= EncoderRate.encoderMoveValue; + return encoder_diffState == ENCODER_DIFF_ENTER; +} + /*********************** Encoder LED ***********************/ #if PIN_EXISTS(LCD_LED) diff --git a/Marlin/src/lcd/e3v2/creality/dwin.cpp b/Marlin/src/lcd/e3v2/creality/dwin.cpp index f20260e43d513..05ac38d226ce1 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin.cpp +++ b/Marlin/src/lcd/e3v2/creality/dwin.cpp @@ -471,15 +471,6 @@ void Draw_Back_First(const bool is_sel=true) { if (is_sel) Draw_Menu_Cursor(0); } -template -inline bool Apply_Encoder(const EncoderState &encoder_diffState, T &valref) { - if (encoder_diffState == ENCODER_DIFF_CW) - valref += EncoderRate.encoderMoveValue; - else if (encoder_diffState == ENCODER_DIFF_CCW) - valref -= EncoderRate.encoderMoveValue; - return encoder_diffState == ENCODER_DIFF_ENTER; -} - // // Draw Menus // @@ -1296,15 +1287,6 @@ void Goto_MainMenu() { TERN(HAS_ONESTEP_LEVELING, ICON_Leveling, ICON_StartInfo)(); } -inline EncoderState get_encoder_state() { - static millis_t Encoder_ms = 0; - const millis_t ms = millis(); - if (PENDING(ms, Encoder_ms)) return ENCODER_DIFF_NO; - const EncoderState state = Encoder_ReceiveAnalyze(); - if (state != ENCODER_DIFF_NO) Encoder_ms = ms + ENCODER_WAIT_MS; - return state; -} - void HMI_Plan_Move(const feedRate_t fr_mm_s) { if (!planner.is_full()) { planner.synchronize(); @@ -4086,6 +4068,13 @@ void HMI_Init() { HMI_SetLanguage(); } +void DWIN_InitScreen() { + Encoder_Configuration(); + HMI_Init(); + HMI_SetLanguageCache(); + HMI_StartFrame(true); +} + void DWIN_Update() { EachMomentUpdate(); // Status update HMI_SDCardUpdate(); // SD card update @@ -4292,7 +4281,7 @@ void DWIN_HandleScreen() { } } -void DWIN_CompletedHoming() { +void DWIN_HomingDone() { HMI_flag.home_flag = false; dwin_zoffset = TERN0(HAS_BED_PROBE, probe.offset.z); if (checkkey == Last_Prepare) { @@ -4308,7 +4297,7 @@ void DWIN_CompletedHoming() { } } -void DWIN_CompletedLeveling() { +void DWIN_LevelingDone() { if (checkkey == Leveling) Goto_MainMenu(); } diff --git a/Marlin/src/lcd/e3v2/creality/dwin.h b/Marlin/src/lcd/e3v2/creality/dwin.h index 3122a6fcbae1c..487f309ed996b 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin.h +++ b/Marlin/src/lcd/e3v2/creality/dwin.h @@ -236,13 +236,14 @@ void HMI_MaxJerk(); // Maximum jerk speed submenu void HMI_Step(); // Transmission ratio void HMI_Init(); +void DWIN_InitScreen(); void DWIN_Update(); void EachMomentUpdate(); void DWIN_HandleScreen(); void DWIN_StatusChanged(const char * const cstr=nullptr); void DWIN_StatusChanged(FSTR_P const fstr); -inline void DWIN_StartHoming() { HMI_flag.home_flag = true; } +inline void DWIN_HomingStart() { HMI_flag.home_flag = true; } -void DWIN_CompletedHoming(); -void DWIN_CompletedLeveling(); +void DWIN_HomingDone(); +void DWIN_LevelingDone(); diff --git a/Marlin/src/lcd/e3v2/creality/dwin_lcd.cpp b/Marlin/src/lcd/e3v2/creality/dwin_lcd.cpp index fee22932d2e50..3d60e32a79086 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin_lcd.cpp +++ b/Marlin/src/lcd/e3v2/creality/dwin_lcd.cpp @@ -49,6 +49,7 @@ void DWIN_Startup() { #if DISABLED(SHOW_BOOTSCREEN) DWIN_Frame_Clear(Color_Bg_Black); // MarlinUI handles the bootscreen so just clear here #endif + DWIN_JPG_ShowAndCache(3); DWIN_UpdateLCD(); } diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp index 0eedddb500999..3e777d4aaaede 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp @@ -958,8 +958,8 @@ void CrealityDWINClass::Update_Status_Bar(bool refresh/*=false*/) { static bool new_msg; static uint8_t msgscrl = 0; static char lastmsg[64]; - if (strcmp_P(lastmsg, statusmsg) != 0 || refresh) { - strcpy_P(lastmsg, statusmsg); + if (strcmp(lastmsg, statusmsg) != 0 || refresh) { + strcpy(lastmsg, statusmsg); msgscrl = 0; new_msg = true; } @@ -4695,10 +4695,7 @@ void CrealityDWINClass::Modify_Option(uint8_t value, const char * const * option /* Main Functions */ void CrealityDWINClass::Update_Status(const char * const text) { - char header[4]; - LOOP_L_N(i, 3) header[i] = text[i]; - header[3] = '\0'; - if (strcmp_P(header, PSTR("")) == 0) { + if (strncmp_P(text, PSTR(""), 3) == 0) { LOOP_L_N(i, _MIN((size_t)LONG_FILENAME_LENGTH, strlen(text))) filename[i] = text[i + 3]; filename[_MIN((size_t)LONG_FILENAME_LENGTH - 1, strlen(text))] = '\0'; Draw_Print_Filename(true); @@ -4722,10 +4719,10 @@ void CrealityDWINClass::Start_Print(bool sd) { card.selectFileByName(fname); } #endif - strcpy_P(filename, card.longest_filename()); + strcpy(filename, card.longest_filename()); } else - strcpy_P(filename, "Host Print"); + strcpy_P(filename, PSTR("Host Print")); TERN_(LCD_SET_PROGRESS_MANUALLY, ui.set_progress(0)); TERN_(USE_M73_REMAINING_TIME, ui.set_remaining_time(0)); Draw_Print_Screen(); @@ -4920,18 +4917,10 @@ void CrealityDWINClass::Screen_Update() { } void CrealityDWINClass::AudioFeedback(const bool success/*=true*/) { - if (success) { - if (ui.buzzer_enabled) { - BUZZ(100, 659); - BUZZ( 10, 0); - BUZZ(100, 698); - } - else Update_Status("Success"); - } - else if (ui.buzzer_enabled) - BUZZ(40, 440); + if (ui.buzzer_enabled) + DONE_BUZZ(success); else - Update_Status("Failed"); + Update_Status(success ? "Success" : "Failed"); } void CrealityDWINClass::Save_Settings(char *buff) { @@ -4989,6 +4978,8 @@ void MarlinUI::init_lcd() { DWIN_UpdateLCD(); delay(20); } + + DWIN_JPG_ShowAndCache(3); DWIN_JPG_CacheTo1(Language_English); CrealityDWIN.Redraw_Screen(); } diff --git a/Marlin/src/lcd/e3v2/marlinui/dwin_lcd.cpp b/Marlin/src/lcd/e3v2/marlinui/dwin_lcd.cpp index ef390ac9dc047..a4cefe4ab99a6 100644 --- a/Marlin/src/lcd/e3v2/marlinui/dwin_lcd.cpp +++ b/Marlin/src/lcd/e3v2/marlinui/dwin_lcd.cpp @@ -45,6 +45,7 @@ void DWIN_Startup() { const bool success = DWIN_Handshake(); if (success) DEBUG_ECHOLNPGM("ok."); else DEBUG_ECHOLNPGM("error."); DWIN_Frame_SetDir(TERN(DWIN_MARLINUI_LANDSCAPE, 0, 1)); + DWIN_JPG_ShowAndCache(3); DWIN_Frame_Clear(Color_Bg_Black); // MarlinUI handles the bootscreen so just clear here DWIN_UpdateLCD(); } diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index 4d7f38171d0ad..66e90740fdfb0 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -21,19 +21,18 @@ */ /** - * Enhanced DWIN implementation + * DWIN Enhanced implementation for PRO UI * Author: Miguel A. Risco-Castillo (MRISCOC) - * Version: 3.11.2 - * date: 2022/01/19 - * - * Based on the original code provided by Creality under GPL + * Version: 3.15.2 + * Date: 2022/03/01 */ -#include "../../../inc/MarlinConfigPre.h" +#include "../../../inc/MarlinConfig.h" -#if ENABLED(DWIN_CREALITY_LCD_ENHANCED) +#if ENABLED(DWIN_LCD_PROUI) #include "dwin.h" +#include "menus.h" #include "dwin_popup.h" #include "../../fontutils.h" @@ -65,6 +64,10 @@ #include "../../../feature/host_actions.h" #endif +#if ANY(AUTO_BED_LEVELING_BILINEAR, AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_3POINT) && DISABLED(PROBE_MANUALLY) + #define HAS_ONESTEP_LEVELING 1 +#endif + #if HAS_MESH || HAS_ONESTEP_LEVELING #include "../../../feature/bedlevel/bedlevel.h" #endif @@ -77,8 +80,14 @@ #include "../../../feature/bltouch.h" #endif -#if EITHER(BABYSTEP_ZPROBE_OFFSET, JUST_BABYSTEP) - #include "../../../feature/babystep.h" +#if ANY(BABYSTEPPING, HAS_BED_PROBE, HAS_WORKSPACE_OFFSET) + #define HAS_ZOFFSET_ITEM 1 + #if !HAS_BED_PROBE && ENABLED(BABYSTEPPING) + #define JUST_BABYSTEP 1 + #endif + #if EITHER(BABYSTEP_ZPROBE_OFFSET, JUST_BABYSTEP) + #include "../../../feature/babystep.h" + #endif #endif #if ENABLED(POWER_LOSS_RECOVERY) @@ -171,7 +180,7 @@ enum SelectItem : uint8_t { PAGE_PRINT = 0, PAGE_PREPARE, PAGE_CONTROL, - PAGE_INFO_LEV_ADV, + PAGE_ADVANCE, PAGE_COUNT, PRINT_SETUP = 0, @@ -192,14 +201,13 @@ typedef struct { select_t select_page{0}, select_file{0}, select_print{0}; uint8_t index_file = MROWS; -bool dwin_abort_flag = false; // Flag to reset feedrate, return to Home bool hash_changed = true; // Flag to know if message status was changed -constexpr float default_max_feedrate[] = DEFAULT_MAX_FEEDRATE; -constexpr float default_max_acceleration[] = DEFAULT_MAX_ACCELERATION; +constexpr float max_feedrate_edit_values[] = DEFAULT_MAX_FEEDRATE; +constexpr float max_acceleration_edit_values[] = DEFAULT_MAX_ACCELERATION; #if HAS_CLASSIC_JERK - constexpr float default_max_jerk[] = { DEFAULT_XJERK, DEFAULT_YJERK, DEFAULT_ZJERK, DEFAULT_EJERK }; + constexpr float max_jerk_edit_values[] = { DEFAULT_XJERK, DEFAULT_YJERK, DEFAULT_ZJERK, DEFAULT_EJERK }; #endif static uint8_t _percent_done = 0; @@ -208,18 +216,6 @@ static uint32_t _remain_time = 0; // Additional Aux Host Support static bool sdprint = false; -#if ENABLED(PAUSE_HEAT) - #if HAS_HOTEND - celsius_t resume_hotend_temp = 0; - #endif - #if HAS_HEATED_BED - celsius_t resume_bed_temp = 0; - #endif - #if HAS_FAN - uint16_t resume_fan = 0; - #endif -#endif - #if HAS_ZOFFSET_ITEM float dwin_zoffset = 0, last_zoffset = 0; #endif @@ -348,31 +344,13 @@ void ICON_Control() { ICON_Button(select_page.now == PAGE_CONTROL, ICON_Control_0, ico, txt, GET_TEXT_F(MSG_CONTROL)); } -// -// Main Menu: "Info" -// -void ICON_StartInfo() { - constexpr frame_rect_t ico = { 145, 226, 110, 100 }; - constexpr text_info_t txt = { 91, { 405, TERN(USE_STOCK_DWIN_SET, 446, 447) }, 27, 15 }; - ICON_Button(select_page.now == PAGE_INFO_LEV_ADV, ICON_Info_0, ico, txt, GET_TEXT_F(MSG_BUTTON_INFO)); -} - -// -// Main Menu: "Level" -// -void ICON_Leveling() { - constexpr frame_rect_t ico = { 145, 226, 110, 100 }; - constexpr text_info_t txt = { 211, { 405, TERN(USE_STOCK_DWIN_SET, 446, 447) }, 27, 15 }; - ICON_Button(select_page.now == PAGE_INFO_LEV_ADV, ICON_Leveling_0, ico, txt, GET_TEXT_F(MSG_BUTTON_LEVEL)); -} - // // Main Menu: "Advanced Settings" // void ICON_AdvSettings() { constexpr frame_rect_t ico = { 145, 226, 110, 100 }; constexpr text_info_t txt = { 91, { 405, TERN(USE_STOCK_DWIN_SET, 446, 447) }, 27, 15 }; - ICON_Button(select_page.now == PAGE_INFO_LEV_ADV, ICON_Info_0, ico, txt, GET_TEXT_F(MSG_BUTTON_ADVANCED)); + ICON_Button(select_page.now == PAGE_ADVANCE, ICON_Info_0, ico, txt, GET_TEXT_F(MSG_BUTTON_ADVANCED)); } // @@ -415,14 +393,6 @@ void ICON_Stop() { // Drawing routines //----------------------------------------------------------------------------- -void Draw_Menu_Cursor(const int8_t line) { - DWIN_Draw_Rectangle(1, HMI_data.Cursor_color, 0, MBASE(line) - 18, 14, MBASE(line + 1) - 20); -} - -void Erase_Menu_Cursor(const int8_t line) { - DWIN_Draw_Rectangle(1, HMI_data.Background_Color, 0, MBASE(line) - 18, 14, MBASE(line + 1) - 20); -} - void Move_Highlight(const int8_t from, const int8_t newline) { Erase_Menu_Cursor(newline - from); Draw_Menu_Cursor(newline); @@ -430,7 +400,7 @@ void Move_Highlight(const int8_t from, const int8_t newline) { void Add_Menu_Line() { Move_Highlight(1, MROWS); - DWIN_Draw_Line(HMI_data.SplitLine_Color, 16, MBASE(MROWS + 1) - 20, 256, MBASE(MROWS + 1) - 19); + DWIN_Draw_HLine(HMI_data.SplitLine_Color, 16, MYPOS(MROWS + 1), 240); } void Scroll_Menu(const uint8_t dir) { @@ -449,21 +419,6 @@ void Erase_Menu_Text(const uint8_t line) { DWIN_Draw_Rectangle(1, HMI_data.Background_Color, LBLX, MBASE(line) - 14, 271, MBASE(line) + 28); } -void Draw_Menu_Line(const uint8_t line, const uint8_t icon=0, const char * const label=nullptr, bool more=false) { - if (icon) DWINUI::Draw_Icon(icon, ICOX, MBASE(line) - 3); - if (label) DWINUI::Draw_String(LBLX, MBASE(line) - 1, (char*)label); - if (more) DWINUI::Draw_Icon(ICON_More, VALX + 16, MBASE(line) - 3); - DWIN_Draw_HLine(HMI_data.SplitLine_Color, 16, MYPOS(line + 1), 240); -} - -void Draw_Chkb_Line(const uint8_t line, const bool checked) { - DWINUI::Draw_Checkbox(HMI_data.Text_Color, HMI_data.Background_Color, VALX + 16, MBASE(line) - 1, checked); -} - -void Draw_Menu_IntValue(uint16_t bcolor, const uint8_t line, uint8_t iNum, const uint16_t value=0) { - DWINUI::Draw_Int(HMI_data.Text_Color, bcolor, iNum , VALX, MBASE(line) - 1, value); -} - // Draw "Back" line at the top void Draw_Back_First(const bool is_sel=true) { Draw_Menu_Line(0, ICON_Back); @@ -474,24 +429,6 @@ void Draw_Back_First(const bool is_sel=true) { if (is_sel) Draw_Menu_Cursor(0); } -inline EncoderState get_encoder_state() { - static millis_t Encoder_ms = 0; - const millis_t ms = millis(); - if (PENDING(ms, Encoder_ms)) return ENCODER_DIFF_NO; - const EncoderState state = Encoder_ReceiveAnalyze(); - if (state != ENCODER_DIFF_NO) Encoder_ms = ms + ENCODER_WAIT_MS; - return state; -} - -template -inline bool Apply_Encoder(const EncoderState &encoder_diffState, T &valref) { - if (encoder_diffState == ENCODER_DIFF_CW) - valref += EncoderRate.encoderMoveValue; - else if (encoder_diffState == ENCODER_DIFF_CCW) - valref -= EncoderRate.encoderMoveValue; - return encoder_diffState == ENCODER_DIFF_ENTER; -} - //PopUps void Popup_window_PauseOrStop() { if (HMI_IsChinese()) { @@ -530,9 +467,10 @@ void Popup_window_PauseOrStop() { #if HAS_HOTEND || HAS_HEATED_BED void DWIN_Popup_Temperature(const bool toohigh) { - DWINUI::ClearMenuArea(); - Draw_Popup_Bkgd(); + HMI_SaveProcessID(WaitResponse); if (HMI_IsChinese()) { + DWINUI::ClearMenuArea(); + Draw_Popup_Bkgd(); if (toohigh) { DWINUI::Draw_Icon(ICON_TempTooHigh, 102, 165); DWIN_Frame_AreaCopy(1, 103, 371, 237, 386, 52, 285); @@ -545,23 +483,14 @@ void Popup_window_PauseOrStop() { DWIN_Frame_AreaCopy(1, 189, 389, 271, 402, 95, 310); } } - else { - DWIN_Draw_Popup(toohigh ? ICON_TempTooHigh : ICON_TempTooLow, F("Nozzle or Bed temperature"), toohigh ? F("is too high") : F("is too low")); - } + else DWIN_Show_Popup(toohigh ? ICON_TempTooHigh : ICON_TempTooLow, F("Nozzle or Bed temperature"), toohigh ? F("is too high") : F("is too low"), BTN_Continue); } #endif // Draw status line -void DWIN_DrawStatusLine(const uint16_t color, const uint16_t bgcolor, const char *text, const bool center = true) { - DWIN_Draw_Rectangle(1, bgcolor, 0, STATUS_Y, DWIN_WIDTH, STATUS_Y + 20); - if (text) { - if (center) DWINUI::Draw_CenteredString(color, STATUS_Y + 2, text); - else DWINUI::Draw_String(color, 0, STATUS_Y + 2, text); - } - DWIN_UpdateLCD(); -} -void DWIN_DrawStatusLine(const char *text, const bool center = true) { - DWIN_DrawStatusLine(HMI_data.StatusTxt_Color, HMI_data.StatusBg_Color, text, center); +void DWIN_DrawStatusLine(const char *text) { + DWIN_Draw_Rectangle(1, HMI_data.StatusBg_Color, 0, STATUS_Y, DWIN_WIDTH, STATUS_Y + 20); + if (text) DWINUI::Draw_CenteredString(HMI_data.StatusTxt_Color, STATUS_Y + 2, text); } // Clear & reset status line @@ -582,17 +511,15 @@ void DWIN_CheckStatusMessage() { }; void DWIN_DrawStatusMessage() { - const uint8_t max_status_chars = DWIN_WIDTH / DWINUI::fontWidth(); - #if ENABLED(STATUS_MESSAGE_SCROLLING) // Get the UTF8 character count of the string uint8_t slen = utf8_strlen(ui.status_message); // If the string fits the status line do not scroll it - if (slen <= max_status_chars) { + if (slen <= LCD_WIDTH) { if (hash_changed) { - DWIN_DrawStatusLine(HMI_data.StatusTxt_Color, HMI_data.StatusBg_Color, ui.status_message); + DWIN_DrawStatusLine(ui.status_message); hash_changed = false; } } @@ -605,16 +532,16 @@ void DWIN_DrawStatusMessage() { const char *stat = MarlinUI::status_and_len(rlen); DWIN_Draw_Rectangle(1, HMI_data.StatusBg_Color, 0, STATUS_Y, DWIN_WIDTH, STATUS_Y + 20); DWINUI::MoveTo(0, STATUS_Y + 2); - DWINUI::Draw_String(stat, max_status_chars); + DWINUI::Draw_String(HMI_data.StatusTxt_Color, stat, LCD_WIDTH); // If the string doesn't completely fill the line... - if (rlen < max_status_chars) { - DWINUI::Draw_Char('.'); // Always at 1+ spaces left, draw a dot - uint8_t chars = max_status_chars - rlen; // Amount of space left in characters + if (rlen < LCD_WIDTH) { + DWINUI::Draw_Char(HMI_data.StatusTxt_Color, '.'); // 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 - DWINUI::Draw_Char('.'); + DWINUI::Draw_Char(HMI_data.StatusTxt_Color, '.'); if (--chars) - DWINUI::Draw_String(ui.status_message, chars); // Print a second copy of the message + DWINUI::Draw_String(HMI_data.StatusTxt_Color, ui.status_message, chars); // Print a second copy of the message } } MarlinUI::advance_status_scroll(); @@ -623,8 +550,8 @@ void DWIN_DrawStatusMessage() { #else if (hash_changed) { - ui.status_message[max_status_chars] = 0; - DWIN_DrawStatusLine(HMI_data.StatusTxt_Color, HMI_data.StatusBg_Color, ui.status_message); + ui.status_message[LCD_WIDTH] = 0; + DWIN_DrawStatusLine(ui.status_message); hash_changed = false; } @@ -643,7 +570,7 @@ void Draw_Print_Labels() { } void Draw_Print_ProgressBar() { - DWINUI::Draw_IconWB(ICON_Bar, 15, 93); + DWIN_ICON_Show(true, false, false, ICON, ICON_Bar, 15, 93); DWIN_Draw_Rectangle(1, HMI_data.Barfill_Color, 16 + _percent_done * 240 / 100, 93, 256, 113); DWINUI::Draw_Int(HMI_data.PercentTxt_Color, HMI_data.Background_Color, 3, 117, 133, _percent_done); DWINUI::Draw_String(HMI_data.PercentTxt_Color, 142, 133, F("%")); @@ -663,10 +590,21 @@ void Draw_Print_ProgressRemain() { } void ICON_ResumeOrPause() { - if (printingIsPaused() || HMI_flag.pause_flag || HMI_flag.pause_action) - ICON_Resume(); - else - ICON_Pause(); + if (checkkey == PrintProcess) printingIsPaused() ? ICON_Resume() : ICON_Pause(); +} + +// Update filename on print +void DWIN_Print_Header(const char *text = nullptr) { + static char headertxt[31] = ""; // Print header text + if (text) { + const int8_t size = _MIN(30U, strlen_P(text)); + LOOP_L_N(i, size) headertxt[i] = text[i]; + headertxt[size] = '\0'; + } + if (checkkey == PrintProcess || checkkey == PrintDone) { + DWIN_Draw_Rectangle(1, HMI_data.Background_Color, 0, 60, DWIN_WIDTH, 60+16); + DWINUI::Draw_CenteredString(60, headertxt); + } } void Draw_PrintProcess() { @@ -685,17 +623,16 @@ void Draw_PrintProcess() { ICON_Tune(); ICON_ResumeOrPause(); ICON_Stop(); - DWIN_UpdateLCD(); } void Goto_PrintProcess() { - if (checkkey == PrintProcess) { + if (checkkey == PrintProcess) ICON_ResumeOrPause(); - DWIN_UpdateLCD(); - return; + else { + checkkey = PrintProcess; + Draw_PrintProcess(); } - checkkey = PrintProcess; - Draw_PrintProcess(); + DWIN_UpdateLCD(); } void Draw_PrintDone() { @@ -713,8 +650,16 @@ void Draw_PrintDone() { Draw_Print_ProgressElapsed(); Draw_Print_ProgressRemain(); // show print done confirm - DWINUI::Draw_IconWB(HMI_IsChinese() ? ICON_Confirm_C : ICON_Confirm_E, 86, 273); - DWIN_UpdateLCD(); + DWINUI::Draw_Button(BTN_Confirm, 86, 273); +} + +void Goto_PrintDone() { + wait_for_user = true; + if (checkkey != PrintDone) { + checkkey = PrintDone; + Draw_PrintDone(); + DWIN_UpdateLCD(); + } } void Draw_Main_Menu() { @@ -724,18 +669,18 @@ void Draw_Main_Menu() { else Title.ShowCaption(MACHINE_NAME); DWINUI::Draw_Icon(ICON_LOGO, 71, 52); // CREALITY logo + DWIN_ResetStatusLine(); ICON_Print(); ICON_Prepare(); ICON_Control(); ICON_AdvSettings(); - DWIN_UpdateLCD(); } void Goto_Main_Menu() { if (checkkey == MainMenu) return; checkkey = MainMenu; - ui.reset_status(true); Draw_Main_Menu(); + DWIN_UpdateLCD(); } // Draw X, Y, Z and blink if in an un-homed or un-trusted state @@ -751,9 +696,9 @@ void _update_axis_value(const AxisEnum axis, const uint16_t x, const uint16_t y, if (force || changed || draw_qmark || draw_empty) { if (blink && draw_qmark) - DWINUI::Draw_String(HMI_data.Coordinate_Color, HMI_data.Background_Color, x, y, F(" - ? -")); + DWINUI::Draw_String(HMI_data.Coordinate_Color, HMI_data.Background_Color, x, y, F(" - ? -")); else if (blink && draw_empty) - DWINUI::Draw_String(HMI_data.Coordinate_Color, HMI_data.Background_Color, x, y, F(" ")); + DWINUI::Draw_String(HMI_data.Coordinate_Color, HMI_data.Background_Color, x, y, F(" ")); else DWINUI::Draw_Signed_Float(HMI_data.Coordinate_Color, HMI_data.Background_Color, 3, 2, x, y, p); } @@ -766,9 +711,9 @@ void _draw_xyz_position(const bool force) { if (force || blink != _blink) { _blink = blink; //SERIAL_ECHOPGM(" (blink)"); - _update_axis_value(X_AXIS, 35, 459, blink, true); - _update_axis_value(Y_AXIS, 120, 459, blink, true); - _update_axis_value(Z_AXIS, 205, 459, blink, true); + _update_axis_value(X_AXIS, 27, 459, blink, true); + _update_axis_value(Y_AXIS, 112, 459, blink, true); + _update_axis_value(Z_AXIS, 197, 459, blink, true); } //SERIAL_EOL(); } @@ -852,7 +797,7 @@ void update_variable() { static float _offset = 0; if (BABY_Z_VAR != _offset) { _offset = BABY_Z_VAR; - DWINUI::Draw_Signed_Float(DWIN_FONT_STAT, HMI_data.Indicator_Color, HMI_data.Background_Color, 2, 2, 210, 417, _offset); + DWINUI::Draw_Signed_Float(DWIN_FONT_STAT, HMI_data.Indicator_Color, HMI_data.Background_Color, 2, 2, 204, 417, _offset); } #if HAS_MESH @@ -908,15 +853,6 @@ void make_name_without_ext(char *dst, char *src, size_t maxlen=MENU_CHAR_LIMIT) void HMI_SDCardInit() { card.cdroot(); } -// Initialize or re-initialize the LCD -void MarlinUI::init_lcd() { DWIN_Startup(); } - -void MarlinUI::refresh() { /* Nothing to see here */ } - -#if HAS_LCD_BRIGHTNESS - void MarlinUI::_set_brightness() { DWIN_LCD_Brightness(backlight ? brightness : 0); } -#endif - #if ENABLED(SCROLL_LONG_FILENAMES) char shift_name[LONG_FILENAME_LENGTH + 1]; @@ -966,7 +902,8 @@ void Draw_SDItem(const uint16_t item, int16_t row=-1) { // 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); + const uint8_t icon = card.flag.filenameIsDir ? ICON_Folder : card.fileIsBinary() ? ICON_Binary : ICON_File; + Draw_Menu_Line(row, icon, str); } #if ENABLED(SCROLL_LONG_FILENAMES) @@ -1045,11 +982,8 @@ void HMI_SDCardUpdate() { Redraw_SD_List(); } else if (sdprint && card.isPrinting() && printingIsActive()) { - // TODO: Move card removed abort handling - // to CardReader::manage_media. - card.abortFilePrintSoon(); wait_for_heatup = wait_for_user = false; - dwin_abort_flag = true; // Reset feedrate, return to Home + HMI_flag.abort_flag = true; // Abort print } } DWIN_UpdateLCD(); @@ -1057,10 +991,10 @@ void HMI_SDCardUpdate() { } // -// The status area is always on-screen, except during -// full-screen modal dialogs. (TODO: Keep alive during dialogs) +// The Dashboard is always on-screen, except during +// full-screen modal dialogs. // -void Draw_Status_Area(const bool with_update) { +void DWIN_Draw_Dashboard() { DWIN_Draw_Rectangle(1, HMI_data.Background_Color, 0, STATUS_Y + 21, DWIN_WIDTH, DWIN_HEIGHT - 1); @@ -1095,7 +1029,7 @@ void Draw_Status_Area(const bool with_update) { DWINUI::Draw_Icon(planner.leveling_active ? ICON_SetZOffset : ICON_Zoffset, 187, 416); #endif - DWINUI::Draw_Signed_Float(DWIN_FONT_STAT, HMI_data.Indicator_Color, HMI_data.Background_Color, 2, 2, 210, 417, BABY_Z_VAR); + DWINUI::Draw_Signed_Float(DWIN_FONT_STAT, HMI_data.Indicator_Color, HMI_data.Background_Color, 2, 2, 204, 417, BABY_Z_VAR); DWIN_Draw_Rectangle(1, HMI_data.SplitLine_Color, 0, 449, DWIN_WIDTH, 451); @@ -1104,16 +1038,6 @@ void Draw_Status_Area(const bool with_update) { DWINUI::Draw_Icon(ICON_MaxSpeedZ, 180, 456); _draw_xyz_position(true); - if (with_update) { - DWIN_UpdateLCD(); - delay(5); - } -} - -void HMI_StartFrame(const bool with_update) { - Goto_Main_Menu(); - DWIN_DrawStatusLine(nullptr); - Draw_Status_Area(with_update); } void Draw_Info_Menu() { @@ -1143,8 +1067,6 @@ void Draw_Info_Menu() { DWINUI::Draw_Icon(ICON_PrintSize + i, ICOX, 99 + i * 73); DWIN_Draw_HLine(HMI_data.SplitLine_Color, 16, MBASE(2) + i * 73, 240); } - - DWIN_UpdateLCD(); } void Draw_Print_File_Menu() { @@ -1166,7 +1088,7 @@ void HMI_MainMenu() { case PAGE_PRINT: ICON_Print(); break; case PAGE_PREPARE: ICON_Print(); ICON_Prepare(); break; case PAGE_CONTROL: ICON_Prepare(); ICON_Control(); break; - case PAGE_INFO_LEV_ADV: ICON_Control(); ICON_AdvSettings(); break; + case PAGE_ADVANCE: ICON_Control(); ICON_AdvSettings(); break; } } } @@ -1176,7 +1098,7 @@ void HMI_MainMenu() { case PAGE_PRINT: ICON_Print(); ICON_Prepare(); break; case PAGE_PREPARE: ICON_Prepare(); ICON_Control(); break; case PAGE_CONTROL: ICON_Control(); ICON_AdvSettings(); break; - case PAGE_INFO_LEV_ADV: ICON_AdvSettings(); break; + case PAGE_ADVANCE: ICON_AdvSettings(); break; } } } @@ -1185,14 +1107,12 @@ void HMI_MainMenu() { case PAGE_PRINT: checkkey = SelectFile; card.mount(); + delay(300); Draw_Print_File_Menu(); break; - case PAGE_PREPARE: Draw_Prepare_Menu(); break; - case PAGE_CONTROL: Draw_Control_Menu(); break; - - case PAGE_INFO_LEV_ADV: Draw_AdvancedSettings_Menu(); break; + case PAGE_ADVANCE: Draw_AdvancedSettings_Menu(); break; } } DWIN_UpdateLCD(); @@ -1277,7 +1197,7 @@ void HMI_SelectFile() { else if (encoder_diffState == ENCODER_DIFF_ENTER) { if (select_file.now == 0) { // Back select_page.set(PAGE_PRINT); - Goto_Main_Menu(); + return Goto_Main_Menu(); } else if (hasUpDir && select_file.now == 1) { // CD-Up SDCard_Up(); @@ -1301,16 +1221,10 @@ void HMI_SelectFile() { HMI_flag.heat_flag = true; HMI_flag.print_finish = false; - card.openAndPrintFile(card.filename); - - #if HAS_FAN - // All fans on for Ender 3 v2 ? - // The slicer should manage this for us. - //for (uint8_t i = 0; i < FAN_COUNT; i++) - // thermalManager.fan_speed[i] = 255; - #endif - - DWIN_Print_Started(true); + if (card.fileIsBinary()) + return DWIN_Popup_Confirm(ICON_Error, F("Please check filenames"), F("Only G-code can be printed")); + else + return Goto_ConfirmToPrint(); } } @@ -1318,6 +1232,16 @@ void HMI_SelectFile() { DWIN_UpdateLCD(); } +// Pause or Stop popup +void onClick_PauseOrStop() { + switch (select_print.now) { + case PRINT_PAUSE_RESUME: if (HMI_flag.select_flag) HMI_flag.pause_flag = true; break; // confirm pause + case PRINT_STOP: if (HMI_flag.select_flag) HMI_flag.abort_flag = true; break; // stop confirmed then abort print + default: break; + } + return Goto_PrintProcess(); +} + // Printing void HMI_Printing() { EncoderState encoder_diffState = get_encoder_state(); @@ -1345,106 +1269,23 @@ void HMI_Printing() { switch (select_print.now) { case PRINT_SETUP: Draw_Tune_Menu(); break; case PRINT_PAUSE_RESUME: - if (HMI_flag.pause_flag) { - ICON_Pause(); - #if DISABLED(ADVANCED_PAUSE_FEATURE) - char cmd[40]; - cmd[0] = '\0'; - #if BOTH(HAS_HEATED_BED, PAUSE_HEAT) - if (resume_bed_temp) sprintf_P(cmd, PSTR("M190 S%i\n"), resume_bed_temp); - #endif - #if BOTH(HAS_HOTEND, PAUSE_HEAT) - if (resume_hotend_temp) sprintf_P(&cmd[strlen(cmd)], PSTR("M109 S%i\n"), resume_hotend_temp); - #endif - #if HAS_FAN - if (resume_fan) thermalManager.fan_speed[0] = resume_fan; - #endif - strcat_P(cmd, M24_STR); - queue.inject(cmd); - #endif - } - else { - HMI_flag.select_flag = true; - checkkey = PauseOrStop; - Popup_window_PauseOrStop(); + if (printingIsPaused()) { // if printer is already in pause + ui.resume_print(); + break; } - break; - + else + return Goto_Popup(Popup_window_PauseOrStop, onClick_PauseOrStop); case PRINT_STOP: - HMI_flag.select_flag = true; - checkkey = PauseOrStop; - Popup_window_PauseOrStop(); - break; - + return Goto_Popup(Popup_window_PauseOrStop, onClick_PauseOrStop); default: break; } } DWIN_UpdateLCD(); } -// Print done -void HMI_PrintDone() { - EncoderState encoder_diffState = get_encoder_state(); - if (encoder_diffState == ENCODER_DIFF_NO) return; - if (encoder_diffState == ENCODER_DIFF_ENTER) { - dwin_abort_flag = true; // Reset feedrate, return to Home - Goto_Main_Menu(); // Return to Main menu after print done - } -} - -// Pause or Stop popup -void HMI_PauseOrStop() { - EncoderState 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 == PRINT_PAUSE_RESUME) { - if (HMI_flag.select_flag) { - HMI_flag.pause_action = true; - ICON_Resume(); - queue.inject(F("M25")); - } - else { - // cancel pause - } - Goto_PrintProcess(); - } - else if (select_print.now == PRINT_STOP) { - if (HMI_flag.select_flag) { - checkkey = MainMenu; - if (HMI_flag.home_flag) planner.synchronize(); // Wait for planner moves to finish! - wait_for_heatup = wait_for_user = false; // Stop waiting for heating/user - card.abortFilePrintSoon(); // Let the main loop handle SD abort - dwin_abort_flag = true; // Reset feedrate, return to Home - #ifdef ACTION_ON_CANCEL - hostui.cancel(); - #endif - DWIN_Draw_Popup(ICON_BLTouch, GET_TEXT_F(MSG_STOPPING), GET_TEXT_F(MSG_PLEASE_WAIT)); - } - else - Goto_PrintProcess(); // cancel stop - } - } - DWIN_UpdateLCD(); -} - #include "../../../libs/buzzer.h" -void HMI_AudioFeedback(const bool success/*=true*/) { - #if HAS_BUZZER - if (success) { - BUZZ(100, 659); - BUZZ(10, 0); - BUZZ(100, 698); - } - else - BUZZ(40, 440); - #endif -} +void HMI_AudioFeedback(const bool success/*=true*/) { DONE_BUZZ(success); } void Draw_Main_Area() { switch (checkkey) { @@ -1452,24 +1293,11 @@ void Draw_Main_Area() { case SelectFile: Draw_Print_File_Menu(); break; case PrintProcess: Draw_PrintProcess(); break; case PrintDone: Draw_PrintDone(); break; - case Info: Draw_Info_Menu(); break; #if HAS_ESDIAG case ESDiagProcess: Draw_EndStopDiag(); break; #endif - #if ENABLED(PRINTCOUNTER) - case PrintStatsProcess: Draw_PrintStats(); break; - #endif - case PauseOrStop: Popup_window_PauseOrStop(); break; - #if ENABLED(POWER_LOSS_RECOVERY) - case PwrlossRec: Popup_PowerLossRecovery(); break; - #endif - #if ENABLED(ADVANCED_PAUSE_FEATURE) - case FilamentPurge: Draw_Popup_FilamentPurge(); break; - #endif + case Popup: popupDraw(); break; case Locked: lockScreen.draw(); break; - #if HAS_GCODE_PREVIEW - case ConfirmToPrint: Draw_PreviewFromSD(); break; - #endif case Menu: case SetInt: case SetPInt: @@ -1484,19 +1312,32 @@ void HMI_ReturnScreen() { checkkey = last_checkkey; wait_for_user = false; Draw_Main_Area(); - return; } -void HMI_Popup() { - EncoderState encoder_diffState = get_encoder_state(); - if (encoder_diffState == ENCODER_DIFF_NO) return; - if (encoder_diffState == ENCODER_DIFF_ENTER) { - HMI_ReturnScreen(); +void HMI_WaitForUser() { + get_encoder_state(); + if (!wait_for_user) { + switch (checkkey) { + case PrintDone: + select_page.reset(); + Goto_Main_Menu(); + break; + #if HAS_ONESTEP_LEVELING + case Leveling: + //TERN_(ProUI, ProEx.StopLeveling()); + HMI_ReturnScreen(); + break; + #endif + default: + HMI_ReturnScreen(); + break; + } } } void HMI_Init() { - HMI_SDCardInit(); + DWINUI::Draw_Box(1, Color_Black, {5, 220, DWIN_WIDTH-5, DWINUI::fontHeight()}); + DWINUI::Draw_CenteredString(Color_White, 220, F("Professional Firmware ")); for (uint16_t t = 0; t <= 100; t += 2) { DWINUI::Draw_Icon(ICON_Bar, 15, 260); DWIN_Draw_Rectangle(1, HMI_data.Background_Color, 15 + t * 242 / 100, 260, 257, 280); @@ -1506,12 +1347,6 @@ void HMI_Init() { HMI_SetLanguage(); } -void DWIN_Update() { - EachMomentUpdate(); // Status update - HMI_SDCardUpdate(); // SD card update - DWIN_HandleScreen(); // Rotary encoder update -} - void EachMomentUpdate() { static millis_t next_var_update_ms = 0, next_rts_update_ms = 0, next_status_update_ms = 0; @@ -1538,52 +1373,45 @@ void EachMomentUpdate() { if (PENDING(ms, next_rts_update_ms)) return; next_rts_update_ms = ms + DWIN_SCROLL_UPDATE_INTERVAL; - if (checkkey == PrintProcess) { + if (checkkey == PrintProcess) { // print process + + // Print pause + if (HMI_flag.pause_flag && !HMI_flag.home_flag) { + HMI_flag.pause_flag = false; + if (!HMI_flag.pause_action) { + HMI_flag.pause_action = true; + return ui.pause_print(); + } + } + // if print done - if (HMI_flag.print_finish) { + if (HMI_flag.print_finish && !HMI_flag.home_flag) { HMI_flag.print_finish = false; - TERN_(POWER_LOSS_RECOVERY, recovery.cancel()); - planner.finish_and_disable(); - checkkey = PrintDone; - Draw_PrintDone(); + return DWIN_Print_Finished(); } - else if (HMI_flag.pause_flag != printingIsPaused()) { - // print status update - HMI_flag.pause_flag = printingIsPaused(); - ICON_ResumeOrPause(); - } - } - // pause after homing - if (HMI_flag.pause_action && printingIsPaused() && !planner.has_blocks_queued()) { - HMI_flag.pause_action = false; - #if ENABLED(PAUSE_HEAT) - TERN_(HAS_HOTEND, resume_hotend_temp = sdprint ? thermalManager.degTargetHotend(0) : thermalManager.wholeDegHotend(0)); - TERN_(HAS_HEATED_BED, resume_bed_temp = sdprint ? thermalManager.degTargetBed() : thermalManager.wholeDegBed()); - TERN_(HAS_FAN, resume_fan = thermalManager.fan_speed[0]); - #endif - IF_DISABLED(ADVANCED_PAUSE_FEATURE, thermalManager.disable_all_heaters()); - IF_DISABLED(PARK_HEAD_ON_PAUSE, queue.inject(F("G1 F1200 X0 Y0"))); - } - - if (checkkey == PrintProcess) { // print process + // if print was aborted + if (HMI_flag.abort_flag && !HMI_flag.home_flag) { // Print Stop + HMI_flag.abort_flag = false; + if (!HMI_flag.abort_action) { + HMI_flag.abort_action = true; + ui.abort_print(); + return Goto_PrintDone(); + } + } duration_t elapsed = print_job_timer.duration(); // print timer if (sdprint && card.isPrinting()) { uint8_t percentDone = card.percentDone(); - static uint8_t last_percentValue = 101; - if (last_percentValue != percentDone) { // print percent - last_percentValue = percentDone; - if (percentDone) { + if (_percent_done != percentDone) { // print percent _percent_done = percentDone; Draw_Print_ProgressBar(); } - } // Estimate remaining time every 20 seconds static millis_t next_remain_time_update = 0; - if (_percent_done > 1 && ELAPSED(ms, next_remain_time_update) && !HMI_flag.heat_flag) { + if (_percent_done > 1 && ELAPSED(ms, next_remain_time_update) && !HMI_flag.heat_flag && !HMI_flag.remain_flag) { _remain_time = (elapsed.value - dwin_heat_time) / (_percent_done * 0.01f) - (elapsed.value - dwin_heat_time); next_remain_time_update += DWIN_REMAIN_TIME_UPDATE_INTERVAL; Draw_Print_ProgressRemain(); @@ -1599,12 +1427,6 @@ void EachMomentUpdate() { } } - else if (dwin_abort_flag && !HMI_flag.home_flag) { // Print Stop - dwin_abort_flag = false; - dwin_zoffset = BABY_Z_VAR; - select_page.set(PAGE_PRINT); - Goto_Main_Menu(); - } #if ENABLED(POWER_LOSS_RECOVERY) else if (DWIN_lcd_sd_status && recovery.dwin_flag) { // resume print before power off @@ -1629,8 +1451,8 @@ void EachMomentUpdate() { DWINUI::Draw_CenteredString(HMI_data.PopupTxt_Color, 70, GET_TEXT_F(MSG_OUTAGE_RECOVERY)); DWINUI::Draw_CenteredString(HMI_data.PopupTxt_Color, 147, F("It looks like the last")); DWINUI::Draw_CenteredString(HMI_data.PopupTxt_Color, 167, F("file was interrupted.")); - DWINUI::Draw_IconWB(ICON_Cancel_E, 26, 280); - DWINUI::Draw_IconWB(ICON_Continue_E, 146, 280); + DWINUI::Draw_Button(BTN_Cancel, 26, 280); + DWINUI::Draw_Button(BTN_Continue, 146, 280); } SdFile *dir = nullptr; const char * const filename = card.diveToFile(true, dir, recovery.info.sd_filename); @@ -1640,35 +1462,26 @@ void EachMomentUpdate() { DWIN_UpdateLCD(); } + void onClick_PowerLossRecovery() { + if (HMI_flag.select_flag) { + queue.inject(F("M1000C")); + select_page.reset(); + return Goto_Main_Menu(); + } + else { + select_print.set(PRINT_SETUP); + queue.inject(F("M1000")); + sdprint = true; + return Goto_PrintProcess(); + } + } + void Goto_PowerLossRecovery() { recovery.dwin_flag = false; LCD_MESSAGE_F(GET_TEXT_F(MSG_CONTINUE_PRINT_JOB)); - HMI_flag.select_flag = false; - Popup_PowerLossRecovery(); - last_checkkey = MainMenu; - checkkey = PwrlossRec; - } - - void HMI_PowerlossRecovery() { - EncoderState encoder_diffState = get_encoder_state(); - if (encoder_diffState == ENCODER_DIFF_NO) return; - if (encoder_diffState == ENCODER_DIFF_ENTER) { - if (HMI_flag.select_flag) { - queue.inject(F("M1000C")); - select_page.reset(); - Goto_Main_Menu(); - } - else { - select_print.set(PRINT_SETUP); - queue.inject(F("M1000")); - sdprint = true; - Goto_PrintProcess(); - } - } - else - Draw_Select_Highlight(encoder_diffState != ENCODER_DIFF_CW); - DWIN_UpdateLCD(); + Goto_Popup(Popup_PowerLossRecovery, onClick_PowerLossRecovery); } + #endif // POWER_LOSS_RECOVERY @@ -1682,87 +1495,75 @@ void DWIN_HandleScreen() { case SetFloat: HMI_SetFloat(); break; case SetPFloat: HMI_SetPFloat(); break; case SelectFile: HMI_SelectFile(); break; - case Homing: break; - case Leveling: break; case PrintProcess: HMI_Printing(); break; - case PrintDone: HMI_PrintDone(); break; - case PauseOrStop: HMI_PauseOrStop(); break; - case Info: HMI_Popup(); break; - case WaitResponse: HMI_Popup(); break; - #if ENABLED(ADVANCED_PAUSE_FEATURE) - case FilamentPurge: HMI_FilamentPurge(); break; - #endif - case NothingToDo: break; + case Popup: HMI_Popup(); break; + case Leveling: //TERN_(ProUI, HMI_WaitForUser()); + break; case Locked: HMI_LockScreen(); break; - #if ENABLED(POWER_LOSS_RECOVERY) - case PwrlossRec: HMI_PowerlossRecovery(); break; - #endif - #if HAS_GCODE_PREVIEW - case ConfirmToPrint: HMI_ConfirmToPrint(); break; - #endif - #if HAS_ESDIAG - case ESDiagProcess: HMI_Popup(); break; - #endif - #if ENABLED(PRINTCOUNTER) - case PrintStatsProcess: HMI_Popup(); break; - #endif + case PrintDone: + TERN_(HAS_ESDIAG, case ESDiagProcess:) + case WaitResponse: HMI_WaitForUser(); break; + case Homing: + case PidProcess: + case NothingToDo: break; default: break; } } bool IDisPopUp() { // If ID is popup... - return (checkkey == NothingToDo) || - (checkkey == WaitResponse) || - (checkkey == Info) || - (checkkey == Homing) || - (checkkey == Leveling) || - TERN_(HAS_ESDIAG, (checkkey == ESDiagProcess) ||) - TERN_(PRINTCOUNTER, (checkkey == PrintStatsProcess) ||) - (checkkey == PauseOrStop) || - (checkkey == FilamentPurge); + return (checkkey == NothingToDo) + || (checkkey == WaitResponse) + || (checkkey == Homing) + || (checkkey == Leveling) + || (checkkey == PidProcess) + || TERN0(HAS_ESDIAG, (checkkey == ESDiagProcess)) + || (checkkey == Popup); } void HMI_SaveProcessID(const uint8_t id) { if (checkkey != id) { if (!IDisPopUp()) last_checkkey = checkkey; // if previous is not a popup + if ((id == Popup) + || TERN0(HAS_ESDIAG, (id == ESDiagProcess)) + || (id == PrintDone) + || (id == Leveling) + || (id == WaitResponse)) wait_for_user = true; checkkey = id; } } -void DWIN_StartHoming() { +void DWIN_HomingStart() { HMI_flag.home_flag = true; HMI_SaveProcessID(Homing); - Title.ShowCaption(GET_TEXT_F(MSG_LEVEL_BED_HOMING)); - DWIN_Draw_Popup(ICON_BLTouch, GET_TEXT_F(MSG_LEVEL_BED_HOMING), GET_TEXT_F(MSG_PLEASE_WAIT)); + Title.ShowCaption(GET_TEXT_F(MSG_HOMING)); + DWIN_Show_Popup(ICON_BLTouch, GET_TEXT_F(MSG_HOMING), GET_TEXT_F(MSG_PLEASE_WAIT)); } -void DWIN_CompletedHoming() { +void DWIN_HomingDone() { HMI_flag.home_flag = false; dwin_zoffset = TERN0(HAS_BED_PROBE, probe.offset.z); - if (dwin_abort_flag) { - planner.finish_and_disable(); - } - HMI_ReturnScreen(); + if (HMI_flag.abort_action) DWIN_Print_Aborted(); else HMI_ReturnScreen(); } -void DWIN_MeshLevelingStart() { +void DWIN_LevelingStart() { #if HAS_ONESTEP_LEVELING HMI_SaveProcessID(Leveling); Title.ShowCaption(GET_TEXT_F(MSG_BED_LEVELING)); - DWIN_Show_Popup(ICON_AutoLeveling, GET_TEXT_F(MSG_BED_LEVELING), GET_TEXT_F(MSG_PLEASE_WAIT), ICON_Cancel_E); + DWIN_Show_Popup(ICON_AutoLeveling, GET_TEXT_F(MSG_BED_LEVELING), GET_TEXT_F(MSG_PLEASE_WAIT)); #elif ENABLED(MESH_BED_LEVELING) Draw_ManualMesh_Menu(); #endif } -void DWIN_CompletedLeveling() { TERN_(HAS_MESH, DWIN_MeshViewer()); } +void DWIN_LevelingDone() { + TERN_(HAS_ONESTEP_LEVELING, if (planner.leveling_active) Goto_MeshViewer()); +} #if HAS_MESH - void DWIN_MeshUpdate(const int8_t xpos, const int8_t ypos, const float zval) { + void DWIN_MeshUpdate(const int8_t xpos, const int8_t ypos, const_float_t zval) { char msg[33] = ""; char str_1[6] = ""; - sprintf_P(msg, PSTR(S_FMT " %i/%i Z=%s"), GET_TEXT(MSG_PROBING_POINT), xpos, ypos, - dtostrf(zval, 1, 2, str_1)); + sprintf_P(msg, PSTR(S_FMT " %i/%i Z=%s"), GET_TEXT(MSG_PROBING_POINT), xpos, ypos, dtostrf(zval, 1, 2, str_1)); ui.set_status(msg); } #endif @@ -1800,66 +1601,63 @@ void DWIN_PidTuning(pidresult_t result) { } } -// Update filename on print -void DWIN_Print_Header(const char *text = nullptr) { - static char headertxt[31] = ""; // Print header text - - if (text) { - const int8_t size = _MIN((unsigned) 30, strlen_P(text)); - LOOP_L_N(i, size) headertxt[i] = text[i]; - headertxt[size] = '\0'; - } - if (checkkey == PrintProcess || checkkey == PrintDone) { - DWIN_Draw_Rectangle(1, HMI_data.Background_Color, 0, 60, DWIN_WIDTH, 60+16); - DWINUI::Draw_CenteredString(60, headertxt); - } -} - -void Draw_Title(TitleClass* title) { - DWIN_Draw_Rectangle(1, HMI_data.TitleBg_color, 0, 0, DWIN_WIDTH - 1, TITLE_HEIGHT - 1); - if (title->frameid) - DWIN_Frame_AreaCopy(title->frameid, title->frame.left, title->frame.top, title->frame.right, title->frame.bottom, 14, (TITLE_HEIGHT - (title->frame.bottom - title->frame.top)) / 2 - 1); - else - DWIN_Draw_String(false, DWIN_FONT_HEAD, HMI_data.TitleTxt_color, HMI_data.TitleBg_color, 14, (TITLE_HEIGHT - DWINUI::fontHeight(DWIN_FONT_HEAD)) / 2 - 1, title->caption); -} - -void Draw_Menu(MenuClass* menu) { - DWINUI::SetColors(HMI_data.Text_Color, HMI_data.Background_Color); - DWIN_Draw_Rectangle(1, DWINUI::backcolor, 0, TITLE_HEIGHT, DWIN_WIDTH - 1, STATUS_Y - 1); - DWIN_ResetStatusLine(); -} - -// Startup routines -void DWIN_Startup() { - DWINUI::init(); - DWINUI::onCursorDraw = Draw_Menu_Cursor; - DWINUI::onCursorErase = Erase_Menu_Cursor; - DWINUI::onTitleDraw = Draw_Title; - DWINUI::onMenuDraw = Draw_Menu; - HMI_SetLanguage(); -} - // Started a Print Job void DWIN_Print_Started(const bool sd) { - sdprint = card.isPrinting() || sd; + sdprint = IS_SD_PRINTING() || sd; _percent_done = 0; _remain_time = 0; + HMI_flag.remain_flag = false; + HMI_flag.pause_flag = false; + HMI_flag.pause_action = false; + HMI_flag.abort_flag = false; + HMI_flag.abort_action = false; HMI_flag.print_finish = false; Goto_PrintProcess(); } +// Pause a print job +void DWIN_Print_Pause() { + ICON_ResumeOrPause(); +} + +// Resume print job +void DWIN_Print_Resume() { + HMI_flag.pause_action = false; + ICON_ResumeOrPause(); + if (printJobOngoing()) { + LCD_MESSAGE(MSG_RESUME_PRINT); + Goto_PrintProcess(); + } +} + // Ended print job void DWIN_Print_Finished() { - if (checkkey == PrintProcess || printingIsActive()) { + if (HMI_flag.abort_flag || checkkey == PrintDone) return; + TERN_(POWER_LOSS_RECOVERY, if (card.isPrinting()) recovery.cancel()); + HMI_flag.pause_flag = false; + wait_for_heatup = false; + planner.finish_and_disable(); thermalManager.cooldown(); - HMI_flag.print_finish = true; - } + Goto_PrintDone(); +} + +// Print was aborted +void DWIN_Print_Aborted() { + TERN_(DEBUG_DWIN, SERIAL_ECHOLNPGM("DWIN_Print_Aborted")); + HMI_flag.abort_action = false; + wait_for_heatup = false; + planner.finish_and_disable(); + thermalManager.cooldown(); + Goto_PrintDone(); } // Progress Bar update void DWIN_Progress_Update() { if (parser.seenval('P')) _percent_done = parser.byteval('P'); - if (parser.seenval('R')) _remain_time = parser.ulongval('R') * 60; + if (parser.seenval('R')) { + _remain_time = parser.ulongval('R') * 60; + HMI_flag.remain_flag = true; + } if (checkkey == PrintProcess) { Draw_Print_ProgressBar(); Draw_Print_ProgressRemain(); @@ -1895,11 +1693,18 @@ void DWIN_SetColorDefaults() { void DWIN_SetDataDefaults() { DWIN_SetColorDefaults(); - DWINUI::SetColors(HMI_data.Text_Color, HMI_data.Background_Color); - TERN_(HAS_HOTEND, HMI_data.HotendPidT = PREHEAT_1_TEMP_HOTEND); - TERN_(HAS_HEATED_BED, HMI_data.BedPidT = PREHEAT_1_TEMP_BED); - TERN_(HAS_HOTEND, HMI_data.PidCycles = 5); - TERN_(PREVENT_COLD_EXTRUSION, HMI_data.ExtMinT = EXTRUDE_MINTEMP); + DWINUI::SetColors(HMI_data.Text_Color, HMI_data.Background_Color, HMI_data.StatusBg_Color); + TERN_(HAS_HOTEND, HMI_data.HotendPidT = PREHEAT_1_TEMP_HOTEND); + TERN_(HAS_HEATED_BED, HMI_data.BedPidT = PREHEAT_1_TEMP_BED); + TERN_(HAS_HOTEND, HMI_data.PidCycles = 5); + #if ENABLED(PREVENT_COLD_EXTRUSION) + HMI_data.ExtMinT = EXTRUDE_MINTEMP; + ApplyExtMinT(); + #endif + #if BOTH(HAS_HEATED_BED, PREHEAT_BEFORE_LEVELING) + HMI_data.BedLevT = PREHEAT_1_TEMP_BED; + #endif + TERN_(BAUD_RATE_GCODE, SetBaud250K()); } void DWIN_StoreSettings(char *buff) { @@ -1911,9 +1716,10 @@ void DWIN_LoadSettings(const char *buff) { memcpy((void *)&HMI_data, buff, _MIN(sizeof(HMI_data), eeprom_data_size)); dwin_zoffset = TERN0(HAS_BED_PROBE, probe.offset.z); if (HMI_data.Text_Color == HMI_data.Background_Color) DWIN_SetColorDefaults(); - DWINUI::SetColors(HMI_data.Text_Color, HMI_data.Background_Color); + DWINUI::SetColors(HMI_data.Text_Color, HMI_data.Background_Color, HMI_data.StatusBg_Color); TERN_(PREVENT_COLD_EXTRUSION, ApplyExtMinT()); feedrate_percentage = 100; + TERN_(BAUD_RATE_GCODE, HMI_SetBaudRate()); #if BOTH(CASE_LIGHT_MENU, CASELIGHT_USES_BRIGHTNESS) // Apply Case light brightness caselight.brightness = HMI_data.CaseLight_Brightness; @@ -1925,6 +1731,37 @@ void DWIN_LoadSettings(const char *buff) { #endif } +// Initialize or re-initialize the LCD +void MarlinUI::init_lcd() { + TERN_(DEBUG_DWIN, SERIAL_ECHOLNPGM("DWIN_Startup")); + DWINUI::init(); + DWIN_JPG_CacheTo1(Language_English); + Encoder_Configuration(); +} + +void DWIN_InitScreen() { + HMI_Init(); // draws boot screen + DWINUI::onCursorDraw = Draw_Menu_Cursor; + DWINUI::onCursorErase = Erase_Menu_Cursor; + DWINUI::onTitleDraw = Draw_Title; + DWINUI::onMenuDraw = Draw_Menu; + DWIN_DrawStatusLine(nullptr); + DWIN_Draw_Dashboard(); + Goto_Main_Menu(); +} + +void MarlinUI::update() { + EachMomentUpdate(); // Status update + HMI_SDCardUpdate(); // SD card update + DWIN_HandleScreen(); // Rotary encoder update +} + +void MarlinUI::refresh() { /* Nothing to see here */ } + +#if HAS_LCD_BRIGHTNESS + void MarlinUI::_set_brightness() { DWIN_LCD_Brightness(backlight ? brightness : 0); } +#endif + void MarlinUI::kill_screen(FSTR_P const lcd_error, FSTR_P const lcd_component) { DWIN_Draw_Popup(ICON_BLTouch, F("Printer killed:"), lcd_error); DWINUI::Draw_CenteredString(HMI_data.PopupTxt_Color, 270, F("Turn off the printer")); @@ -1941,60 +1778,51 @@ void DWIN_RebootScreen() { void DWIN_Redraw_screen() { Draw_Main_Area(); - Draw_Status_Area(false); + hash_changed = true; + DWIN_DrawStatusMessage(); + DWIN_Draw_Dashboard(); } #if ENABLED(ADVANCED_PAUSE_FEATURE) - - void DWIN_Popup_Pause(FSTR_P const fmsg, uint8_t button = 0) { + void DWIN_Popup_Pause(FSTR_P const fmsg, uint8_t button /*= 0*/) { HMI_SaveProcessID(button ? WaitResponse : NothingToDo); - DWIN_Draw_Popup(ICON_BLTouch, GET_TEXT_F(MSG_ADVANCED_PAUSE), fmsg, button); - ui.reset_status(true); + DWIN_Show_Popup(ICON_BLTouch, GET_TEXT_F(MSG_ADVANCED_PAUSE), fmsg, button); } void MarlinUI::pause_show_message(const PauseMessage message, const PauseMode mode/*=PAUSE_MODE_SAME*/, const uint8_t extruder/*=active_extruder*/) { + //if (mode == PAUSE_MODE_SAME) return; + pause_mode = mode; switch (message) { - case PAUSE_MESSAGE_PARKING: DWIN_Popup_Pause(GET_TEXT_F(MSG_PAUSE_PRINT_PARKING)); break; - case PAUSE_MESSAGE_CHANGING: DWIN_Popup_Pause(GET_TEXT_F(MSG_FILAMENT_CHANGE_INIT)); break; - case PAUSE_MESSAGE_UNLOAD: DWIN_Popup_Pause(GET_TEXT_F(MSG_FILAMENT_CHANGE_UNLOAD)); break; - case PAUSE_MESSAGE_WAITING: DWIN_Popup_Pause(GET_TEXT_F(MSG_ADVANCED_PAUSE_WAITING), ICON_Continue_E); break; + case PAUSE_MESSAGE_PARKING: DWIN_Popup_Pause(GET_TEXT_F(MSG_PAUSE_PRINT_PARKING)); break; // M125 + case PAUSE_MESSAGE_CHANGING: DWIN_Popup_Pause(GET_TEXT_F(MSG_FILAMENT_CHANGE_INIT)); break; // pause_print (M125, M600) + case PAUSE_MESSAGE_WAITING: DWIN_Popup_Pause(GET_TEXT_F(MSG_ADVANCED_PAUSE_WAITING), BTN_Continue); break; case PAUSE_MESSAGE_INSERT: DWIN_Popup_Continue(ICON_BLTouch, GET_TEXT_F(MSG_ADVANCED_PAUSE), GET_TEXT_F(MSG_FILAMENT_CHANGE_INSERT)); break; case PAUSE_MESSAGE_LOAD: DWIN_Popup_Pause(GET_TEXT_F(MSG_FILAMENT_CHANGE_LOAD)); break; - case PAUSE_MESSAGE_PURGE: DWIN_Popup_Pause(GET_TEXT_F(MSG_FILAMENT_CHANGE_PURGE)); break; - case PAUSE_MESSAGE_OPTION: DWIN_Popup_FilamentPurge(); break; + case PAUSE_MESSAGE_UNLOAD: DWIN_Popup_Pause(GET_TEXT_F(MSG_FILAMENT_CHANGE_UNLOAD)); break; // Unload of pause and Unload of M702 + case PAUSE_MESSAGE_PURGE: + #if ENABLED(ADVANCED_PAUSE_CONTINUOUS_PURGE) + DWIN_Popup_Pause(GET_TEXT_F(MSG_FILAMENT_CHANGE_CONT_PURGE)); + #else + DWIN_Popup_Pause(GET_TEXT_F(MSG_FILAMENT_CHANGE_PURGE)); + #endif + break; + case PAUSE_MESSAGE_OPTION: Goto_FilamentPurge(); break; case PAUSE_MESSAGE_RESUME: DWIN_Popup_Pause(GET_TEXT_F(MSG_FILAMENT_CHANGE_RESUME)); break; - case PAUSE_MESSAGE_HEAT: DWIN_Popup_Pause(GET_TEXT_F(MSG_FILAMENT_CHANGE_HEAT), ICON_Continue_E); break; + case PAUSE_MESSAGE_HEAT: DWIN_Popup_Pause(GET_TEXT_F(MSG_FILAMENT_CHANGE_HEAT), BTN_Continue); break; case PAUSE_MESSAGE_HEATING: LCD_MESSAGE(MSG_FILAMENT_CHANGE_HEATING); break; - case PAUSE_MESSAGE_STATUS: HMI_ReturnScreen(); break; + case PAUSE_MESSAGE_STATUS: HMI_ReturnScreen(); break; // Exit from Pause, Load and Unload default: break; } } void Draw_Popup_FilamentPurge() { DWIN_Draw_Popup(ICON_BLTouch, GET_TEXT_F(MSG_ADVANCED_PAUSE), F("Purge or Continue?")); - DWINUI::Draw_IconWB(ICON_Confirm_E, 26, 280); - DWINUI::Draw_IconWB(ICON_Continue_E, 146, 280); + DWINUI::Draw_Button(BTN_Confirm, 26, 280); + DWINUI::Draw_Button(BTN_Continue, 146, 280); Draw_Select_Highlight(true); - DWIN_UpdateLCD(); } - // Handle responses such as: - // - Purge More, Continue - // - General "Continue" response - void DWIN_Popup_FilamentPurge() { - HMI_SaveProcessID(FilamentPurge); - pause_menu_response = PAUSE_RESPONSE_WAIT_FOR; - Draw_Popup_FilamentPurge(); - } - - void HMI_FilamentPurge() { - EncoderState 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) { + void onClick_FilamentPurge() { if (HMI_flag.select_flag) pause_menu_response = PAUSE_RESPONSE_EXTRUDE_MORE; // "Purge More" button else { @@ -2002,7 +1830,10 @@ void DWIN_Redraw_screen() { pause_menu_response = PAUSE_RESPONSE_RESUME_PRINT; // "Continue" button } } - DWIN_UpdateLCD(); + + void Goto_FilamentPurge() { + pause_menu_response = PAUSE_RESPONSE_WAIT_FOR; + Goto_Popup(Draw_Popup_FilamentPurge, onClick_FilamentPurge); } #endif // ADVANCED_PAUSE_FEATURE @@ -2040,39 +1871,10 @@ void HMI_LockScreen() { if (lockScreen.isUnlocked()) DWIN_UnLockScreen(); } -#if HAS_GCODE_PREVIEW - - void HMI_ConfirmToPrint() { - EncoderState encoder_diffState = get_encoder_state(); - if (encoder_diffState == ENCODER_DIFF_NO) return; - if (encoder_diffState == ENCODER_DIFF_CW) - Draw_Select_Highlight(false); - else if (encoder_diffState == ENCODER_DIFF_CCW) - Draw_Select_Highlight(true); - else if (encoder_diffState == ENCODER_DIFF_ENTER) { - if (HMI_flag.select_flag) { // Confirm - card.openAndPrintFile(card.filename); - DWIN_Print_Started(true); - } - else { // Cancel - DWIN_ResetStatusLine(); - checkkey = SelectFile; - Draw_Print_File_Menu(); - } - } - DWIN_UpdateLCD(); - } - -#endif void Goto_ConfirmToPrint() { - #if HAS_GCODE_PREVIEW - HMI_SaveProcessID(ConfirmToPrint); - Draw_PreviewFromSD(); - #else - card.openAndPrintFile(card.filename); - DWIN_Print_Started(true); - #endif + card.openAndPrintFile(card.filename); + DWIN_Print_Started(true); } #if HAS_ESDIAG @@ -2082,103 +1884,11 @@ void Goto_ConfirmToPrint() { } #endif -#if ENABLED(PRINTCOUNTER) - void Draw_PrintStats() { - HMI_SaveProcessID(PrintStatsProcess); - PrintStats.Draw(); - } -#endif - //============================================================================= // NEW MENU SUBSYSTEM //============================================================================= -// On click functions - -// Generic onclick event without draw anything -// process: process id HMI destiny -// lo: low limit -// hi: high limit -// dp: decimal places, 0 for integers -// val: value / scaled value -// LiveUpdate: live update function when the encoder changes -// Apply: update function when the encoder is pressed -void SetOnClick(uint8_t process, const int32_t lo, const int32_t hi, uint8_t dp, const int32_t val, void (*Apply)() = nullptr, void (*LiveUpdate)() = nullptr) { - checkkey = process; - HMI_value.MinValue = lo; - HMI_value.MaxValue = hi; - HMI_value.dp = dp; - HMI_value.Apply = Apply; - HMI_value.LiveUpdate = LiveUpdate; - HMI_value.Value = val; - EncoderRate.enabled = true; -} - -// Generic onclick event for integer values -// process: process id HMI destiny -// lo: scaled low limit -// hi: scaled high limit -// val: value -// LiveUpdate: live update function when the encoder changes -// Apply: update function when the encoder is pressed -void SetValueOnClick(uint8_t process, const int32_t lo, const int32_t hi, const int32_t val, void (*Apply)() = nullptr, void (*LiveUpdate)() = nullptr) { - SetOnClick(process, lo, hi, 0, val, Apply, LiveUpdate); - Draw_Menu_IntValue(HMI_data.Selected_Color, CurrentMenu->line(), 4, HMI_value.Value); -} - -// Generic onclick event for float values -// process: process id HMI destiny -// lo: scaled low limit -// hi: scaled high limit -// val: value -// LiveUpdate: live update function when the encoder changes -// Apply: update function when the encoder is pressed -void SetValueOnClick(uint8_t process, const float lo, const float hi, uint8_t dp, const float val, void (*Apply)() = nullptr, void (*LiveUpdate)() = nullptr) { - const int32_t value = round(val * POW(10, dp)); - SetOnClick(process, lo * POW(10, dp), hi * POW(10, dp), dp, value, Apply, LiveUpdate); - DWINUI::Draw_Signed_Float(HMI_data.Text_Color, HMI_data.Selected_Color, 3, dp, VALX - dp * DWINUI::fontWidth(DWIN_FONT_MENU), MBASE(CurrentMenu->line()), val); -} - -// Generic onclick event for integer values -// lo: scaled low limit -// hi: scaled high limit -// val: value -// LiveUpdate: live update function when the encoder changes -// Apply: update function when the encoder is pressed -inline void SetIntOnClick(const int32_t lo, const int32_t hi, const int32_t val, void (*Apply)() = nullptr, void (*LiveUpdate)() = nullptr) { - SetValueOnClick(SetInt, lo, hi, val, Apply, LiveUpdate); -} - -// Generic onclick event for set pointer to 16 bit uinteger values -// lo: low limit -// hi: high limit -// LiveUpdate: live update function when the encoder changes -// Apply: update function when the encoder is pressed -void SetPIntOnClick(const int32_t lo, const int32_t hi, void (*Apply)() = nullptr, void (*LiveUpdate)() = nullptr) { - HMI_value.P_Int = (int16_t*)static_cast(CurrentMenu->SelectedItem())->value; - const int32_t value = *HMI_value.P_Int; - SetValueOnClick(SetPInt, lo, hi, value, Apply, LiveUpdate); -} - -// Generic onclick event for float values -// process: process id HMI destiny -// lo: low limit -// hi: high limit -// dp: decimal places -// val: value -inline void SetFloatOnClick(const float lo, const float hi, uint8_t dp, const float val, void (*Apply)() = nullptr, void (*LiveUpdate)() = nullptr) { - SetValueOnClick(SetFloat, lo, hi, dp, val, Apply, LiveUpdate); -} - -// Generic onclick event for set pointer to float values -// lo: low limit -// hi: high limit -// LiveUpdate: live update function when the encoder changes -// Apply: update function when the encoder is pressed -void SetPFloatOnClick(const float lo, const float hi, uint8_t dp, void (*Apply)() = nullptr, void (*LiveUpdate)() = nullptr) { - HMI_value.P_Float = (float*)static_cast(CurrentMenu->SelectedItem())->value; - SetValueOnClick(SetPFloat, lo, hi, dp, *HMI_value.P_Float, Apply, LiveUpdate); -} +// Tool functions #if ENABLED(EEPROM_SETTINGS) void WriteEeprom() { @@ -2201,17 +1911,16 @@ void SetPFloatOnClick(const float lo, const float hi, uint8_t dp, void (*Apply)( // Reset Printer void RebootPrinter() { - dwin_abort_flag = true; wait_for_heatup = wait_for_user = false; // Stop waiting for heating/user thermalManager.disable_all_heaters(); planner.finish_and_disable(); DWIN_RebootScreen(); - HAL_reboot(); + hal.reboot(); } void Goto_Info_Menu(){ - HMI_SaveProcessID(Info); Draw_Info_Menu(); + HMI_SaveProcessID(WaitResponse); } void Goto_Move_Menu() { @@ -2224,14 +1933,11 @@ void Goto_Move_Menu() { void DisableMotors() { queue.inject(F("M84")); } -void AutoLev() { queue.inject(F("G28Z\nG29")); } // Force to get the current Z home position +void AutoLev() { queue.inject(F("G28XYO\nG28Z\nG29")); } // Force to get the current Z home position void AutoHome() { queue.inject_P(G28_STR); } - void HomeX() { queue.inject(F("G28X")); } - void HomeY() { queue.inject(F("G28Y")); } - void HomeZ() { queue.inject(F("G28Z")); } void SetHome() { @@ -2245,7 +1951,7 @@ void SetHome() { void ApplyZOffset() { TERN_(EEPROM_SETTINGS, settings.save()); } void LiveZOffset() { last_zoffset = dwin_zoffset; - dwin_zoffset = HMI_value.Value / 100.0f; + dwin_zoffset = MenuData.Value / 100.0f; #if EITHER(BABYSTEP_ZPROBE_OFFSET, JUST_BABYSTEP) if (BABYSTEP_ALLOWED()) babystep.add_mm(Z_AXIS, dwin_zoffset - last_zoffset); #endif @@ -2255,6 +1961,24 @@ void SetHome() { SetPFloatOnClick(Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX, 2, ApplyZOffset, LiveZOffset); } #endif + + void SetMoveZto0() { + char cmd[48] = ""; + char str_1[5] = "", str_2[5] = ""; + sprintf_P(cmd, PSTR("G28XYO\nG28Z\nG0X%sY%sF5000\nM420S0\nG0Z0F300"), + #if ENABLED(MESH_BED_LEVELING) + dtostrf(0, 1, 1, str_1), + dtostrf(0, 1, 1, str_2) + #else + dtostrf(X_CENTER, 1, 1, str_1), + dtostrf(Y_CENTER, 1, 1, str_2) + #endif + ); + gcode.process_subcommands_now(cmd); + planner.synchronize(); + LCD_MESSAGE_F("Now adjust Z Offset"); + HMI_AudioFeedback(true); + } #endif #if HAS_PREHEAT @@ -2272,14 +1996,14 @@ void SetLanguage() { } void LiveMove() { - *HMI_value.P_Float = HMI_value.Value / MINUNITMULT; + *MenuData.P_Float = MenuData.Value / MINUNITMULT; if (!planner.is_full()) { planner.synchronize(); planner.buffer_line(current_position, homing_feedrate(HMI_value.axis)); } } void ApplyMoveE() { - last_E = HMI_value.Value / MINUNITMULT; + last_E = MenuData.Value / MINUNITMULT; if (!planner.is_full()) { planner.synchronize(); planner.buffer_line(current_position, MMM_TO_MMS(FEEDRATE_E)); @@ -2292,33 +2016,13 @@ void SetMoveZ() { HMI_value.axis = Z_AXIS; SetPFloatOnClick(Z_MIN_POS, Z_MAX_POS #if HAS_HOTEND void SetMoveE() { #if ENABLED(PREVENT_COLD_EXTRUSION) - if (thermalManager.tooColdToExtrude(0)) { - Popup_Window_ETempTooLow(); - return; - } + if (thermalManager.tooColdToExtrude(0)) + return DWIN_Popup_Confirm(ICON_TempTooLow, GET_TEXT_F(MSG_HOTEND_TOO_COLD), GET_TEXT_F(MSG_PLEASE_PREHEAT)); #endif SetPFloatOnClick(last_E - (EXTRUDE_MAXLENGTH), last_E + (EXTRUDE_MAXLENGTH), UNITFDIGITS, ApplyMoveE); } #endif -void SetMoveZto0() { - char cmd[48] = ""; - char str_1[5] = "", str_2[5] = ""; - sprintf_P(cmd, PSTR("G28Z\nG0X%sY%sF5000\nM420S0\nG0Z0F300"), - #if ENABLED(MESH_BED_LEVELING) - dtostrf(0, 1, 1, str_1), - dtostrf(0, 1, 1, str_2) - #else - dtostrf(X_CENTER, 1, 1, str_1), - dtostrf(Y_CENTER, 1, 1, str_2) - #endif - ); - gcode.process_subcommands_now(cmd); - planner.synchronize(); - LCD_MESSAGE_F("Now adjust Z Offset"); - HMI_AudioFeedback(true); -} - void SetPID(celsius_t t, heater_id_t h) { char cmd[48] = ""; char str_1[5] = "", str_2[5] = ""; @@ -2345,10 +2049,24 @@ void SetPID(celsius_t t, heater_id_t h) { } #endif +#if ENABLED(BAUD_RATE_GCODE) + void HMI_SetBaudRate() { + if (HMI_data.Baud115K) SetBaud115K(); else SetBaud250K(); + } + void SetBaudRate() { + HMI_SetBaudRate(); + Draw_Chkb_Line(CurrentMenu->line(), HMI_data.Baud115K); + DWIN_UpdateLCD(); + } + void SetBaud115K() { queue.inject(F("M575 P0 B115200")); HMI_data.Baud115K = true; } + void SetBaud250K() { queue.inject(F("M575 P0 B250000")); HMI_data.Baud115K = false; } +#endif + #if HAS_LCD_BRIGHTNESS - void ApplyBrightness() { ui.set_brightness(HMI_value.Value); } - void LiveBrightness() { DWIN_LCD_Brightness(HMI_value.Value); } + void ApplyBrightness() { ui.set_brightness(MenuData.Value); } + void LiveBrightness() { DWIN_LCD_Brightness(MenuData.Value); } void SetBrightness() { SetIntOnClick(LCD_BRIGHTNESS_MIN, LCD_BRIGHTNESS_MAX, ui.brightness, ApplyBrightness, LiveBrightness); } + void TurnOffBacklight() { HMI_SaveProcessID(WaitResponse); ui.set_brightness(0); DWIN_Redraw_screen(); } #endif #if ENABLED(CASE_LIGHT_MENU) @@ -2359,7 +2077,7 @@ void SetPID(celsius_t t, heater_id_t h) { DWIN_UpdateLCD(); } #if ENABLED(CASELIGHT_USES_BRIGHTNESS) - void LiveCaseLightBrightness() { HMI_data.CaseLight_Brightness = caselight.brightness = HMI_value.Value; caselight.update_brightness(); } + void LiveCaseLightBrightness() { HMI_data.CaseLight_Brightness = caselight.brightness = MenuData.Value; caselight.update_brightness(); } void SetCaseLightBrightness() { SetIntOnClick(0, 255, caselight.brightness, nullptr, LiveCaseLightBrightness); } #endif #endif @@ -2373,14 +2091,14 @@ void SetPID(celsius_t t, heater_id_t h) { } #endif #if ENABLED(HAS_COLOR_LEDS) - void LiveLedColorR() { leds.color.r = HMI_value.Value; HMI_data.Led_Color = leds.color; leds.update(); } + void LiveLedColorR() { leds.color.r = MenuData.Value; HMI_data.Led_Color = leds.color; leds.update(); } void SetLedColorR() { SetIntOnClick(0, 255, leds.color.r, nullptr, LiveLedColorR); } - void LiveLedColorG() { leds.color.g = HMI_value.Value; HMI_data.Led_Color = leds.color; leds.update(); } + void LiveLedColorG() { leds.color.g = MenuData.Value; HMI_data.Led_Color = leds.color; leds.update(); } void SetLedColorG() { SetIntOnClick(0, 255, leds.color.g, nullptr, LiveLedColorG); } - void LiveLedColorB() { leds.color.b = HMI_value.Value; HMI_data.Led_Color = leds.color; leds.update(); } + void LiveLedColorB() { leds.color.b = MenuData.Value; HMI_data.Led_Color = leds.color; leds.update(); } void SetLedColorB() { SetIntOnClick(0, 255, leds.color.b, nullptr, LiveLedColorB); } #if HAS_WHITE_LED - void LiveLedColorW() { leds.color.w = HMI_value.Value; HMI_data.Led_Color = leds.color; leds.update(); } + void LiveLedColorW() { leds.color.w = MenuData.Value; HMI_data.Led_Color = leds.color; leds.update(); } void SetLedColorW() { SetIntOnClick(0, 255, leds.color.w, nullptr, LiveLedColorW); } #endif #endif @@ -2395,7 +2113,7 @@ void SetPID(celsius_t t, heater_id_t h) { #endif #if HAS_HOME_OFFSET - void ApplyHomeOffset() { set_home_offset(HMI_value.axis, HMI_value.Value / MINUNITMULT); } + void ApplyHomeOffset() { set_home_offset(HMI_value.axis, MenuData.Value / MINUNITMULT); } void SetHomeOffsetX() { HMI_value.axis = X_AXIS; SetPFloatOnClick(-50, 50, UNITFDIGITS, ApplyHomeOffset); } void SetHomeOffsetY() { HMI_value.axis = Y_AXIS; SetPFloatOnClick(-50, 50, UNITFDIGITS, ApplyHomeOffset); } void SetHomeOffsetZ() { HMI_value.axis = Z_AXIS; SetPFloatOnClick( -2, 2, UNITFDIGITS, ApplyHomeOffset); } @@ -2419,12 +2137,11 @@ void SetPID(celsius_t t, heater_id_t h) { DWIN_UpdateLCD(); } #endif -#endif -#if ENABLED(NOZZLE_PARK_FEATURE) - void SetParkPosX() { SetPIntOnClick(0, X_MAX_POS); } - void SetParkPosY() { SetPIntOnClick(0, Y_MAX_POS); } - void SetParkZRaise() { SetPIntOnClick(0, 50); } + #if BOTH(HAS_HEATED_BED, PREHEAT_BEFORE_LEVELING) + void SetBedLevT() { SetPIntOnClick(BED_MINTEMP, BED_MAX_TARGET); } + #endif + #endif #if HAS_FILAMENT_SENSOR @@ -2435,7 +2152,7 @@ void SetPID(celsius_t t, heater_id_t h) { DWIN_UpdateLCD(); } #if HAS_FILAMENT_RUNOUT_DISTANCE - void ApplyRunoutDistance() { runout.set_runout_distance(HMI_value.Value / MINUNITMULT); } + void ApplyRunoutDistance() { runout.set_runout_distance(MenuData.Value / MINUNITMULT); } void SetRunoutDistance() { SetFloatOnClick(0, 999, UNITFDIGITS, runout.runout_distance(), ApplyRunoutDistance); } #endif #endif @@ -2452,20 +2169,20 @@ void SetPID(celsius_t t, heater_id_t h) { void RestoreDefaultsColors() { DWIN_SetColorDefaults(); - DWINUI::SetColors(HMI_data.Text_Color, HMI_data.Background_Color); + DWINUI::SetColors(HMI_data.Text_Color, HMI_data.Background_Color, HMI_data.StatusBg_Color); DWIN_Redraw_screen(); } void SelColor() { - HMI_value.P_Int = (int16_t*)static_cast(CurrentMenu->SelectedItem())->value; - HMI_value.Color[0] = GetRColor(*HMI_value.P_Int); // Red - HMI_value.Color[1] = GetGColor(*HMI_value.P_Int); // Green - HMI_value.Color[2] = GetBColor(*HMI_value.P_Int); // Blue + MenuData.P_Int = (int16_t*)static_cast(CurrentMenu->SelectedItem())->value; + HMI_value.Color[0] = GetRColor(*MenuData.P_Int); // Red + HMI_value.Color[1] = GetGColor(*MenuData.P_Int); // Green + HMI_value.Color[2] = GetBColor(*MenuData.P_Int); // Blue Draw_GetColor_Menu(); } void LiveRGBColor() { - HMI_value.Color[CurrentMenu->line() - 2] = HMI_value.Value; + HMI_value.Color[CurrentMenu->line() - 2] = MenuData.Value; uint16_t color = RGB(HMI_value.Color[0], HMI_value.Color[1], HMI_value.Color[2]); DWIN_Draw_Rectangle(1, color, 20, 315, DWIN_WIDTH - 20, 335); } @@ -2475,27 +2192,28 @@ void SetRGBColor() { } void DWIN_ApplyColor() { - *HMI_value.P_Int = RGB(HMI_value.Color[0], HMI_value.Color[1], HMI_value.Color[2]); - DWINUI::SetColors(HMI_data.Text_Color, HMI_data.Background_Color); - Draw_Status_Area(false); + *MenuData.P_Int = RGB(HMI_value.Color[0], HMI_value.Color[1], HMI_value.Color[2]); + DWINUI::SetColors(HMI_data.Text_Color, HMI_data.Background_Color, HMI_data.StatusBg_Color); Draw_SelectColors_Menu(); + hash_changed = true; LCD_MESSAGE_F(GET_TEXT_F(MSG_COLORS_APPLIED)); + DWIN_Draw_Dashboard(); } void SetSpeed() { SetPIntOnClick(MIN_PRINT_SPEED, MAX_PRINT_SPEED); } #if HAS_HOTEND - void ApplyHotendTemp() { thermalManager.setTargetHotend(HMI_value.Value, 0); } + void ApplyHotendTemp() { thermalManager.setTargetHotend(MenuData.Value, 0); } void SetHotendTemp() { SetIntOnClick(MIN_ETEMP, MAX_ETEMP, thermalManager.degTargetHotend(0), ApplyHotendTemp); } #endif #if HAS_HEATED_BED - void ApplyBedTemp() { thermalManager.setTargetBed(HMI_value.Value); } + void ApplyBedTemp() { thermalManager.setTargetBed(MenuData.Value); } void SetBedTemp() { SetIntOnClick(BED_MINTEMP, BED_MAX_TARGET, thermalManager.degTargetBed(), ApplyBedTemp); } #endif #if HAS_FAN - void ApplyFanSpeed() { thermalManager.set_fan_speed(0, HMI_value.Value); } + void ApplyFanSpeed() { thermalManager.set_fan_speed(0, MenuData.Value); } void SetFanSpeed() { SetIntOnClick(0, 255, thermalManager.fan_speed[0], ApplyFanSpeed); } #endif @@ -2529,17 +2247,15 @@ void ApplyFlow() { planner.refresh_e_factor(0); } void SetFlow() { SetPIntOnClick(MIN_PRINT_FLOW, MAX_PRINT_FLOW, ApplyFlow); } // Bed Tramming -void Tram(uint8_t point) { +TERN(HAS_ONESTEP_LEVELING, float, void) Tram(uint8_t point) { char cmd[100] = ""; #if HAS_ONESTEP_LEVELING static bool inLev = false; - if (inLev) return; + float xpos = 0, ypos = 0, zval = 0, margin = 0; char str_1[6] = "", str_2[6] = "", str_3[6] = ""; - #define fmt "X:%s, Y:%s, Z:%s" - float xpos = 0, ypos = 0, zval = 0; - float margin = PROBING_MARGIN; + if (inLev) return NAN; + margin = HMI_data.FullManualTramming ? 30 : PROBING_MARGIN; #else - #define fmt "M420S0\nG28O\nG90\nG0Z5F300\nG0X%iY%iF5000\nG0Z0F300" int16_t xpos = 0, ypos = 0; int16_t margin = 30; #endif @@ -2567,24 +2283,45 @@ void Tram(uint8_t point) { break; } + planner.synchronize(); + #if HAS_ONESTEP_LEVELING - planner.synchronize(); - probe.stow(); - gcode.process_subcommands_now(F("M420S0\nG28O")); - planner.synchronize(); - inLev = true; - zval = probe.probe_at_point(xpos, ypos, PROBE_PT_STOW); - sprintf_P(cmd, PSTR(fmt), - dtostrf(xpos, 1, 1, str_1), - dtostrf(ypos, 1, 1, str_2), - dtostrf(zval, 1, 2, str_3) - ); - ui.set_status(cmd); - inLev = false; + + if (HMI_data.FullManualTramming) { + planner.synchronize(); + sprintf_P(cmd, PSTR("M420S0\nG28O\nG90\nG0Z5F300\nG0X%sY%sF5000\nG0Z0F300"), + dtostrf(xpos, 1, 1, str_1), + dtostrf(ypos, 1, 1, str_2) + ); + queue.inject(cmd); + } + else { + LIMIT(xpos, X_MIN_POS, (X_MAX_POS + probe.offset.x)); + LIMIT(ypos, Y_MIN_POS, (Y_MAX_POS + probe.offset.y)); + probe.stow(); + gcode.process_subcommands_now(F("M420S0\nG28O")); + planner.synchronize(); + inLev = true; + zval = probe.probe_at_point(xpos, ypos, PROBE_PT_STOW); + if (isnan(zval)) + ui.set_status(F("Position Not Reachable, check offsets")); + else { + sprintf_P(cmd, PSTR("X:%s, Y:%s, Z:%s"), + dtostrf(xpos, 1, 1, str_1), + dtostrf(ypos, 1, 1, str_2), + dtostrf(zval, 1, 2, str_3) + ); + ui.set_status(cmd); + } + inLev = false; + } + return zval; + #else - planner.synchronize(); - sprintf_P(cmd, PSTR(fmt), xpos, ypos); + + sprintf_P(cmd, PSTR("M420S0\nG28O\nG90\nG0Z5F300\nG0X%iY%iF5000\nG0Z0F300"), xpos, ypos); queue.inject(cmd); + #endif } @@ -2594,11 +2331,72 @@ void TramBR() { Tram(2); } void TramBL() { Tram(3); } void TramC () { Tram(4); } +#if HAS_ONESTEP_LEVELING + + void Trammingwizard() { + bed_mesh_t zval = {0}; + if (HMI_data.FullManualTramming) { + ui.set_status(F("Disable manual tramming")); + return; + } + zval[0][0] = Tram(0); + checkkey = NothingToDo; + MeshViewer.DrawMesh(zval, 2, 2); + zval[1][0] = Tram(1); + MeshViewer.DrawMesh(zval, 2, 2); + zval[1][1] = Tram(2); + MeshViewer.DrawMesh(zval, 2, 2); + zval[0][1] = Tram(3); + MeshViewer.DrawMesh(zval, 2, 2); + char str_1[6] = "", str_2[6] = ""; + ui.status_printf(0, F("Limits minZ: %s, maxZ: %s"), + dtostrf(MeshViewer.min, 1, 2, str_1), + dtostrf(MeshViewer.max, 1, 2, str_2) + ); + if (ABS(MeshViewer.max - MeshViewer.min) < 0.05) { + DWINUI::Draw_CenteredString(140,F("Corners leveled")); + DWINUI::Draw_CenteredString(160,F("Tolerance achieved!")); + } + else { + uint8_t p = 0; + float d, max = 0; + FSTR_P plabel; + LOOP_L_N(x,2) LOOP_L_N(y,2) { + d = ABS(zval[x][y] - MeshViewer.avg); + if (max < d) { + max = d; + p = x + 2 * y; + } + } + switch (p) { + case 0b00 : plabel = GET_TEXT_F(MSG_LEVBED_FL); break; + case 0b01 : plabel = GET_TEXT_F(MSG_LEVBED_FR); break; + case 0b10 : plabel = GET_TEXT_F(MSG_LEVBED_BL); break; + case 0b11 : plabel = GET_TEXT_F(MSG_LEVBED_BR); break; + default : plabel = F(""); break; + } + DWINUI::Draw_CenteredString(130, F("Corners not leveled")); + DWINUI::Draw_CenteredString(150, F("Knob adjustment required")); + DWINUI::Draw_CenteredString(Color_Green, 170, plabel); + } + DWINUI::Draw_Button(BTN_Continue, 86, 305); + checkkey = Menu; + HMI_SaveProcessID(WaitResponse); + } + + void SetManualTramming() { + HMI_data.FullManualTramming = !HMI_data.FullManualTramming; + Draw_Chkb_Line(CurrentMenu->line(), HMI_data.FullManualTramming); + DWIN_UpdateLCD(); + } + +#endif // HAS_ONESTEP_LEVELING + #if ENABLED(MESH_BED_LEVELING) void ManualMeshStart(){ LCD_MESSAGE(MSG_UBL_BUILD_MESH_MENU); - gcode.process_subcommands_now(F("G28Z\nM211S0\nG29S1")); + gcode.process_subcommands_now(F("G28XYO\nG28Z\nM211S0\nG29S1")); planner.synchronize(); #ifdef MANUAL_PROBE_START_Z const uint8_t line = CurrentMenu->line(MMeshMoveZItem->pos); @@ -2607,7 +2405,7 @@ void TramC () { Tram(4); } } void LiveMeshMoveZ() { - *HMI_value.P_Float = HMI_value.Value / POW(10, 2); + *MenuData.P_Float = MenuData.Value / POW(10, 2); if (!planner.is_full()) { planner.synchronize(); planner.buffer_line(current_position, homing_feedrate(Z_AXIS)); @@ -2640,29 +2438,29 @@ void TramC () { Tram(4); } #endif #endif -void ApplyMaxSpeed() { planner.set_max_feedrate(HMI_value.axis, HMI_value.Value / MINUNITMULT); } -void SetMaxSpeedX() { HMI_value.axis = X_AXIS, SetFloatOnClick(MIN_MAXFEEDSPEED, default_max_feedrate[X_AXIS] * 2, UNITFDIGITS, planner.settings.max_feedrate_mm_s[X_AXIS], ApplyMaxSpeed); } -void SetMaxSpeedY() { HMI_value.axis = Y_AXIS, SetFloatOnClick(MIN_MAXFEEDSPEED, default_max_feedrate[Y_AXIS] * 2, UNITFDIGITS, planner.settings.max_feedrate_mm_s[Y_AXIS], ApplyMaxSpeed); } -void SetMaxSpeedZ() { HMI_value.axis = Z_AXIS, SetFloatOnClick(MIN_MAXFEEDSPEED, default_max_feedrate[Z_AXIS] * 2, UNITFDIGITS, planner.settings.max_feedrate_mm_s[Z_AXIS], ApplyMaxSpeed); } +void ApplyMaxSpeed() { planner.set_max_feedrate(HMI_value.axis, MenuData.Value / MINUNITMULT); } +void SetMaxSpeedX() { HMI_value.axis = X_AXIS, SetFloatOnClick(MIN_MAXFEEDSPEED, max_feedrate_edit_values[X_AXIS], UNITFDIGITS, planner.settings.max_feedrate_mm_s[X_AXIS], ApplyMaxSpeed); } +void SetMaxSpeedY() { HMI_value.axis = Y_AXIS, SetFloatOnClick(MIN_MAXFEEDSPEED, max_feedrate_edit_values[Y_AXIS], UNITFDIGITS, planner.settings.max_feedrate_mm_s[Y_AXIS], ApplyMaxSpeed); } +void SetMaxSpeedZ() { HMI_value.axis = Z_AXIS, SetFloatOnClick(MIN_MAXFEEDSPEED, max_feedrate_edit_values[Z_AXIS], UNITFDIGITS, planner.settings.max_feedrate_mm_s[Z_AXIS], ApplyMaxSpeed); } #if HAS_HOTEND - void SetMaxSpeedE() { HMI_value.axis = E_AXIS; SetFloatOnClick(MIN_MAXFEEDSPEED, default_max_feedrate[E_AXIS] * 2, UNITFDIGITS, planner.settings.max_feedrate_mm_s[E_AXIS], ApplyMaxSpeed); } + void SetMaxSpeedE() { HMI_value.axis = E_AXIS; SetFloatOnClick(MIN_MAXFEEDSPEED, max_feedrate_edit_values[E_AXIS], UNITFDIGITS, planner.settings.max_feedrate_mm_s[E_AXIS], ApplyMaxSpeed); } #endif -void ApplyMaxAccel() { planner.set_max_acceleration(HMI_value.axis, HMI_value.Value); } -void SetMaxAccelX() { HMI_value.axis = X_AXIS, SetIntOnClick(MIN_MAXACCELERATION, default_max_acceleration[X_AXIS] * 2, planner.settings.max_acceleration_mm_per_s2[X_AXIS], ApplyMaxAccel); } -void SetMaxAccelY() { HMI_value.axis = Y_AXIS, SetIntOnClick(MIN_MAXACCELERATION, default_max_acceleration[Y_AXIS] * 2, planner.settings.max_acceleration_mm_per_s2[Y_AXIS], ApplyMaxAccel); } -void SetMaxAccelZ() { HMI_value.axis = Z_AXIS, SetIntOnClick(MIN_MAXACCELERATION, default_max_acceleration[Z_AXIS] * 2, planner.settings.max_acceleration_mm_per_s2[Z_AXIS], ApplyMaxAccel); } +void ApplyMaxAccel() { planner.set_max_acceleration(HMI_value.axis, MenuData.Value); } +void SetMaxAccelX() { HMI_value.axis = X_AXIS, SetIntOnClick(MIN_MAXACCELERATION, max_acceleration_edit_values[X_AXIS], planner.settings.max_acceleration_mm_per_s2[X_AXIS], ApplyMaxAccel); } +void SetMaxAccelY() { HMI_value.axis = Y_AXIS, SetIntOnClick(MIN_MAXACCELERATION, max_acceleration_edit_values[Y_AXIS], planner.settings.max_acceleration_mm_per_s2[Y_AXIS], ApplyMaxAccel); } +void SetMaxAccelZ() { HMI_value.axis = Z_AXIS, SetIntOnClick(MIN_MAXACCELERATION, max_acceleration_edit_values[Z_AXIS], planner.settings.max_acceleration_mm_per_s2[Z_AXIS], ApplyMaxAccel); } #if HAS_HOTEND - void SetMaxAccelE() { HMI_value.axis = E_AXIS; SetIntOnClick(MIN_MAXACCELERATION, default_max_acceleration[E_AXIS] * 2, planner.settings.max_acceleration_mm_per_s2[E_AXIS], ApplyMaxAccel); } + void SetMaxAccelE() { HMI_value.axis = E_AXIS; SetIntOnClick(MIN_MAXACCELERATION, max_acceleration_edit_values[E_AXIS], planner.settings.max_acceleration_mm_per_s2[E_AXIS], ApplyMaxAccel); } #endif #if HAS_CLASSIC_JERK - void ApplyMaxJerk() { planner.set_max_jerk(HMI_value.axis, HMI_value.Value / MINUNITMULT); } - void SetMaxJerkX() { HMI_value.axis = X_AXIS, SetFloatOnClick(MIN_MAXJERK, default_max_jerk[X_AXIS] * 2, UNITFDIGITS, planner.max_jerk[X_AXIS], ApplyMaxJerk); } - void SetMaxJerkY() { HMI_value.axis = Y_AXIS, SetFloatOnClick(MIN_MAXJERK, default_max_jerk[Y_AXIS] * 2, UNITFDIGITS, planner.max_jerk[Y_AXIS], ApplyMaxJerk); } - void SetMaxJerkZ() { HMI_value.axis = Z_AXIS, SetFloatOnClick(MIN_MAXJERK, default_max_jerk[Z_AXIS] * 2, UNITFDIGITS, planner.max_jerk[Z_AXIS], ApplyMaxJerk); } + void ApplyMaxJerk() { planner.set_max_jerk(HMI_value.axis, MenuData.Value / MINUNITMULT); } + void SetMaxJerkX() { HMI_value.axis = X_AXIS, SetFloatOnClick(MIN_MAXJERK, max_jerk_edit_values[X_AXIS], UNITFDIGITS, planner.max_jerk[X_AXIS], ApplyMaxJerk); } + void SetMaxJerkY() { HMI_value.axis = Y_AXIS, SetFloatOnClick(MIN_MAXJERK, max_jerk_edit_values[Y_AXIS], UNITFDIGITS, planner.max_jerk[Y_AXIS], ApplyMaxJerk); } + void SetMaxJerkZ() { HMI_value.axis = Z_AXIS, SetFloatOnClick(MIN_MAXJERK, max_jerk_edit_values[Z_AXIS], UNITFDIGITS, planner.max_jerk[Z_AXIS], ApplyMaxJerk); } #if HAS_HOTEND - void SetMaxJerkE() { HMI_value.axis = E_AXIS; SetFloatOnClick(MIN_MAXJERK, default_max_jerk[E_AXIS] * 2, UNITFDIGITS, planner.max_jerk[E_AXIS], ApplyMaxJerk); } + void SetMaxJerkE() { HMI_value.axis = E_AXIS; SetFloatOnClick(MIN_MAXJERK, max_jerk_edit_values[E_AXIS], UNITFDIGITS, planner.max_jerk[E_AXIS], ApplyMaxJerk); } #endif #endif @@ -2681,21 +2479,21 @@ void SetStepsZ() { HMI_value.axis = Z_AXIS, SetPFloatOnClick( MIN_STEP, MAX_STEP void SetPidCycles() { SetPIntOnClick(3, 50); } void SetKp() { SetPFloatOnClick(0, 1000, 2); } void ApplyPIDi() { - *HMI_value.P_Float = scalePID_i(HMI_value.Value / POW(10, 2)); + *MenuData.P_Float = scalePID_i(MenuData.Value / POW(10, 2)); thermalManager.updatePID(); } void ApplyPIDd() { - *HMI_value.P_Float = scalePID_d(HMI_value.Value / POW(10, 2)); + *MenuData.P_Float = scalePID_d(MenuData.Value / POW(10, 2)); thermalManager.updatePID(); } void SetKi() { - HMI_value.P_Float = (float*)static_cast(CurrentMenu->SelectedItem())->value; - const float value = unscalePID_i(*HMI_value.P_Float); + MenuData.P_Float = (float*)static_cast(CurrentMenu->SelectedItem())->value; + const float value = unscalePID_i(*MenuData.P_Float); SetFloatOnClick(0, 1000, 2, value, ApplyPIDi); } void SetKd() { - HMI_value.P_Float = (float*)static_cast(CurrentMenu->SelectedItem())->value; - const float value = unscalePID_d(*HMI_value.P_Float); + MenuData.P_Float = (float*)static_cast(CurrentMenu->SelectedItem())->value; + const float value = unscalePID_d(*MenuData.P_Float); SetFloatOnClick(0, 1000, 2, value, ApplyPIDd); } #endif @@ -2707,62 +2505,7 @@ void SetStepsZ() { HMI_value.axis = Z_AXIS, SetPFloatOnClick( MIN_STEP, MAX_STEP void SetRecoverSpeed() { SetPFloatOnClick( 1, 90, UNITFDIGITS); }; #endif -// Menuitem Drawing functions ================================================= - -void onDrawMenuItem(MenuItemClass* menuitem, int8_t line) { - if (menuitem->icon) DWINUI::Draw_Icon(menuitem->icon, ICOX, MBASE(line) - 3); - if (menuitem->frameid) - DWIN_Frame_AreaCopy(menuitem->frameid, menuitem->frame.left, menuitem->frame.top, menuitem->frame.right, menuitem->frame.bottom, LBLX, MBASE(line)); - else if (menuitem->caption) - DWINUI::Draw_String(LBLX, MBASE(line) - 1, menuitem->caption); - DWIN_Draw_HLine(HMI_data.SplitLine_Color, 16, MYPOS(line + 1), 240); -} - -void onDrawSubMenu(MenuItemClass* menuitem, int8_t line) { - onDrawMenuItem(menuitem, line); - DWINUI::Draw_Icon(ICON_More, VALX + 16, MBASE(line) - 3); -} - -void onDrawIntMenu(MenuItemClass* menuitem, int8_t line, uint16_t value) { - onDrawMenuItem(menuitem, line); - Draw_Menu_IntValue(HMI_data.Background_Color, line, 4, value); -} - -void onDrawPIntMenu(MenuItemClass* menuitem, int8_t line) { - const uint16_t value = *(uint16_t*)static_cast(menuitem)->value; - onDrawIntMenu(menuitem, line, value); -} - -void onDrawPInt8Menu(MenuItemClass* menuitem, int8_t line) { - const uint8_t value = *(uint8_t*)static_cast(menuitem)->value; - onDrawIntMenu(menuitem, line, value); -} - -void onDrawPInt32Menu(MenuItemClass* menuitem, int8_t line) { - const uint32_t value = *(uint32_t*)static_cast(menuitem)->value; - onDrawIntMenu(menuitem, line, value); -} - -void onDrawFloatMenu(MenuItemClass* menuitem, int8_t line, uint8_t dp, const float value) { - onDrawMenuItem(menuitem, line); - DWINUI::Draw_Signed_Float(HMI_data.Text_Color, HMI_data.Background_Color, 3, dp, VALX - dp * DWINUI::fontWidth(DWIN_FONT_MENU), MBASE(line), value); -} - -void onDrawPFloatMenu(MenuItemClass* menuitem, int8_t line) { - const float value = *(float*)static_cast(menuitem)->value; - const int8_t dp = UNITFDIGITS; - onDrawFloatMenu(menuitem, line, dp, value); -} - -void onDrawPFloat2Menu(MenuItemClass* menuitem, int8_t line) { - const float value = *(float*)static_cast(menuitem)->value; - onDrawFloatMenu(menuitem, line, 2, value); -} - -void onDrawChkbMenu(MenuItemClass* menuitem, int8_t line, bool checked) { - onDrawMenuItem(menuitem, line); - Draw_Chkb_Line(line, checked); -} +// Special Menuitem Drawing functions ================================================= void onDrawBack(MenuItemClass* menuitem, int8_t line) { if (HMI_IsChinese()) menuitem->SetFrame(1, 129, 72, 156, 84); @@ -2880,6 +2623,10 @@ void onDrawLanguage(MenuItemClass* menuitem, int8_t line) { void onDrawPwrLossR(MenuItemClass* menuitem, int8_t line) { onDrawChkbMenu(menuitem, line, recovery.enabled); } #endif +#if ENABLED(BAUD_RATE_GCODE) + void onDrawBaudrate(MenuItemClass* menuitem, int8_t line) { onDrawChkbMenu(menuitem, line, HMI_data.Baud115K); } +#endif + #if ENABLED(CASE_LIGHT_MENU) void onDrawCaseLight(MenuItemClass* menuitem, int8_t line) { onDrawChkbMenu(menuitem, line, caselight.on); } #endif @@ -3170,137 +2917,9 @@ void onDrawStepsZ(MenuItemClass* menuitem, int8_t line) { } #endif -// HMI Control functions ====================================================== - -// Generic menu control using the encoder -void HMI_Menu() { - EncoderState encoder_diffState = get_encoder_state(); - if (encoder_diffState == ENCODER_DIFF_NO) return; - if (CurrentMenu) { - if (encoder_diffState == ENCODER_DIFF_ENTER) - CurrentMenu->onClick(); - else - CurrentMenu->onScroll(encoder_diffState == ENCODER_DIFF_CW); - } -} - -// Get an integer value using the encoder without draw anything -// lo: low limit -// hi: high limit -// Return value: -// 0 : no change -// 1 : live change -// 2 : apply change -int8_t HMI_GetIntNoDraw(const int32_t lo, const int32_t hi) { - EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - if (Apply_Encoder(encoder_diffState, HMI_value.Value)) { - EncoderRate.enabled = false; - checkkey = Menu; - return 2; - } - LIMIT(HMI_value.Value, lo, hi); - return 1; - } - return 0; -} - -// Get an integer value using the encoder -// lo: low limit -// hi: high limit -// Return value: -// 0 : no change -// 1 : live change -// 2 : apply change -int8_t HMI_GetInt(const int32_t lo, const int32_t hi) { - EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - if (Apply_Encoder(encoder_diffState, HMI_value.Value)) { - EncoderRate.enabled = false; - DWINUI::Draw_Int(HMI_data.Text_Color, HMI_data.Background_Color, 4 , VALX, MBASE(CurrentMenu->line()) - 1, HMI_value.Value); - checkkey = Menu; - return 2; - } - LIMIT(HMI_value.Value, lo, hi); - DWINUI::Draw_Int(HMI_data.Text_Color, HMI_data.Selected_Color, 4 , VALX, MBASE(CurrentMenu->line()) - 1, HMI_value.Value); - return 1; - } - return 0; -} - -// Set an integer using the encoder -void HMI_SetInt() { - int8_t val = HMI_GetInt(HMI_value.MinValue, HMI_value.MaxValue); - switch (val) { - case 0: return; break; - case 1: if (HMI_value.LiveUpdate) HMI_value.LiveUpdate(); break; - case 2: if (HMI_value.Apply) HMI_value.Apply(); break; - } -} - -// Set an integer without drawing -void HMI_SetIntNoDraw() { - int8_t val = HMI_GetIntNoDraw(HMI_value.MinValue, HMI_value.MaxValue); - switch (val) { - case 0: return; break; - case 1: if (HMI_value.LiveUpdate) HMI_value.LiveUpdate(); break; - case 2: if (HMI_value.Apply) HMI_value.Apply(); break; - } -} - -// Set an integer pointer variable using the encoder -void HMI_SetPInt() { - int8_t val = HMI_GetInt(HMI_value.MinValue, HMI_value.MaxValue); - switch (val) { - case 0: return; - case 1: if (HMI_value.LiveUpdate) HMI_value.LiveUpdate(); break; - case 2: *HMI_value.P_Int = HMI_value.Value; if (HMI_value.Apply) HMI_value.Apply(); break; - } -} - -// Get a scaled float value using the encoder -// dp: decimal places -// lo: scaled low limit -// hi: scaled high limit -// Return value: -// 0 : no change -// 1 : live change -// 2 : apply change -int8_t HMI_GetFloat(uint8_t dp, int32_t lo, int32_t hi) { - EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); - if (encoder_diffState != ENCODER_DIFF_NO) { - if (Apply_Encoder(encoder_diffState, HMI_value.Value)) { - EncoderRate.enabled = false; - DWINUI::Draw_Signed_Float(HMI_data.Text_Color, HMI_data.Background_Color, 3, dp, VALX - dp * DWINUI::fontWidth(DWIN_FONT_MENU), MBASE(CurrentMenu->line()), HMI_value.Value / POW(10, dp)); - checkkey = Menu; - return 2; - } - LIMIT(HMI_value.Value, lo, hi); - DWINUI::Draw_Signed_Float(HMI_data.Text_Color, HMI_data.Selected_Color, 3, dp, VALX - dp * DWINUI::fontWidth(DWIN_FONT_MENU), MBASE(CurrentMenu->line()), HMI_value.Value / POW(10, dp)); - return 1; - } - return 0; -} - -// Set a scaled float using the encoder -void HMI_SetFloat() { - const int8_t val = HMI_GetFloat(HMI_value.dp, HMI_value.MinValue, HMI_value.MaxValue); - switch (val) { - case 0: return; - case 1: if (HMI_value.LiveUpdate) HMI_value.LiveUpdate(); break; - case 2: if (HMI_value.Apply) HMI_value.Apply(); break; - } -} - -// Set a scaled float pointer variable using the encoder -void HMI_SetPFloat() { - const int8_t val = HMI_GetFloat(HMI_value.dp, HMI_value.MinValue, HMI_value.MaxValue); - switch (val) { - case 0: return; - case 1: if (HMI_value.LiveUpdate) HMI_value.LiveUpdate(); break; - case 2: *HMI_value.P_Float = HMI_value.Value / POW(10, HMI_value.dp); if (HMI_value.Apply) HMI_value.Apply(); break; - } -} +#if HAS_ONESTEP_LEVELING + void onDrawManualTramming(MenuItemClass* menuitem, int8_t line) { onDrawChkbMenu(menuitem, line, HMI_data.FullManualTramming); } +#endif // Menu Creation and Drawing functions ====================================================== @@ -3357,6 +2976,7 @@ void Draw_Prepare_Menu() { MENU_ITEM(ICON_Cool, GET_TEXT_F(MSG_COOLDOWN), onDrawCooldown, DoCoolDown); MENU_ITEM(ICON_Language, PSTR(GET_TEXT_F(MSG_UI_LANGUAGE)), onDrawLanguage, SetLanguage); } + ui.reset_status(true); CurrentMenu->draw(); } @@ -3367,13 +2987,17 @@ void Draw_Tramming_Menu() { if (CurrentMenu != TrammingMenu) { CurrentMenu = TrammingMenu; SetMenuTitle({0}, GET_TEXT_F(MSG_BED_TRAMMING)); // TODO: Chinese, English "Bed Tramming" JPG - DWINUI::MenuItemsPrepare(6); + DWINUI::MenuItemsPrepare(8); MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_Prepare_Menu); MENU_ITEM(ICON_Axis, GET_TEXT_F(MSG_LEVBED_FL), onDrawMenuItem, TramFL); MENU_ITEM(ICON_Axis, GET_TEXT_F(MSG_LEVBED_FR), onDrawMenuItem, TramFR); MENU_ITEM(ICON_Axis, GET_TEXT_F(MSG_LEVBED_BR), onDrawMenuItem, TramBR); MENU_ITEM(ICON_Axis, GET_TEXT_F(MSG_LEVBED_BL), onDrawMenuItem, TramBL); MENU_ITEM(ICON_Axis, GET_TEXT_F(MSG_LEVBED_C ), onDrawMenuItem, TramC ); + #if HAS_ONESTEP_LEVELING + MENU_ITEM(ICON_ProbeSet, F("Bed tramming wizard"), onDrawMenuItem, Trammingwizard); + MENU_ITEM(ICON_ProbeSet, GET_TEXT_F(MSG_BED_TRAMMING_MANUAL), onDrawManualTramming, SetManualTramming); + #endif } CurrentMenu->draw(); } @@ -3384,7 +3008,7 @@ void Draw_Control_Menu() { if (CurrentMenu != ControlMenu) { CurrentMenu = ControlMenu; SetMenuTitle({103, 1, 28, 14}, GET_TEXT_F(MSG_CONTROL)); - DWINUI::MenuItemsPrepare(8); + DWINUI::MenuItemsPrepare(10); MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Goto_Main_Menu); #if ENABLED(CASE_LIGHT_MENU) #if ENABLED(CASELIGHT_USES_BRIGHTNESS) @@ -3406,6 +3030,7 @@ void Draw_Control_Menu() { MENU_ITEM(ICON_Reboot, GET_TEXT_F(MSG_RESET_PRINTER), onDrawMenuItem, RebootPrinter); MENU_ITEM(ICON_Info, GET_TEXT_F(MSG_INFO_SCREEN), onDrawInfoSubMenu, Goto_Info_Menu); } + ui.reset_status(true); CurrentMenu->draw(); } @@ -3415,8 +3040,11 @@ void Draw_AdvancedSettings_Menu() { if (CurrentMenu != AdvancedSettings) { CurrentMenu = AdvancedSettings; SetMenuTitle({0}, GET_TEXT_F(MSG_ADVANCED_SETTINGS)); // TODO: Chinese, English "Advanced Settings" JPG - DWINUI::MenuItemsPrepare(15); + DWINUI::MenuItemsPrepare(17); MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Goto_Main_Menu); + #if ENABLED(EEPROM_SETTINGS) + MENU_ITEM(ICON_WriteEEPROM, GET_TEXT_F(MSG_STORE_EEPROM), onDrawMenuItem, WriteEeprom); + #endif #if HAS_HOME_OFFSET MENU_ITEM(ICON_HomeOffset, GET_TEXT_F(MSG_SET_HOME_OFFSETS), onDrawSubMenu, Draw_HomeOffset_Menu); #endif @@ -3435,6 +3063,9 @@ void Draw_AdvancedSettings_Menu() { #if ENABLED(POWER_LOSS_RECOVERY) MENU_ITEM(ICON_Pwrlossr, GET_TEXT_F(MSG_OUTAGE_RECOVERY), onDrawPwrLossR, SetPwrLossr); #endif + #if ENABLED(BAUD_RATE_GCODE) + MENU_ITEM(ICON_SetBaudRate, F("115K baud"), onDrawBaudrate, SetBaudRate); + #endif #if HAS_LCD_BRIGHTNESS EDIT_ITEM(ICON_Brightness, GET_TEXT_F(MSG_BRIGHTNESS), onDrawPInt8Menu, SetBrightness, &ui.brightness); #endif @@ -3449,11 +3080,12 @@ void Draw_AdvancedSettings_Menu() { MENU_ITEM(ICON_ESDiag, F("End-stops diag."), onDrawSubMenu, Draw_EndStopDiag); #endif #if ENABLED(PRINTCOUNTER) - MENU_ITEM(ICON_PrintStats, GET_TEXT_F(MSG_INFO_STATS_MENU), onDrawSubMenu, Draw_PrintStats); + MENU_ITEM(ICON_PrintStats, GET_TEXT_F(MSG_INFO_STATS_MENU), onDrawSubMenu, Goto_PrintStats); MENU_ITEM(ICON_PrintStatsReset, GET_TEXT_F(MSG_INFO_PRINT_COUNT_RESET), onDrawSubMenu, PrintStats.Reset); #endif MENU_ITEM(ICON_Lock, GET_TEXT_F(MSG_LOCKSCREEN), onDrawMenuItem, DWIN_LockScreen); } + ui.reset_status(true); CurrentMenu->draw(); } @@ -3500,11 +3132,14 @@ void Draw_Move_Menu() { if (CurrentMenu != ProbeSetMenu) { CurrentMenu = ProbeSetMenu; SetMenuTitle({0}, GET_TEXT_F(MSG_ZPROBE_SETTINGS)); // TODO: Chinese, English "Probe Settings" JPG - DWINUI::MenuItemsPrepare(8); + DWINUI::MenuItemsPrepare(9); MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Draw_AdvancedSettings_Menu); EDIT_ITEM(ICON_ProbeOffsetX, GET_TEXT_F(MSG_ZPROBE_XOFFSET), onDrawPFloatMenu, SetProbeOffsetX, &probe.offset.x); EDIT_ITEM(ICON_ProbeOffsetY, GET_TEXT_F(MSG_ZPROBE_YOFFSET), onDrawPFloatMenu, SetProbeOffsetY, &probe.offset.y); EDIT_ITEM(ICON_ProbeOffsetZ, GET_TEXT_F(MSG_ZPROBE_ZOFFSET), onDrawPFloat2Menu, SetProbeOffsetZ, &probe.offset.z); + #if BOTH(HAS_HEATED_BED, PREHEAT_BEFORE_LEVELING) + EDIT_ITEM(ICON_Temperature, GET_TEXT_F(MSG_UBL_SET_TEMP_BED), onDrawPIntMenu, SetBedLevT, &HMI_data.BedLevT); + #endif #ifdef BLTOUCH_HS_MODE MENU_ITEM(ICON_HSMode, F("Enable HS mode"), onDrawHSMode, SetHSMode); #endif @@ -3594,7 +3229,7 @@ void Draw_GetColor_Menu() { MENU_ITEM(2, GET_TEXT_F(MSG_COLORS_BLUE), onDrawGetColorItem, SetRGBColor); } CurrentMenu->draw(); - DWIN_Draw_Rectangle(1, *HMI_value.P_Int, 20, 315, DWIN_WIDTH - 20, 335); + DWIN_Draw_Rectangle(1, *MenuData.P_Int, 20, 315, DWIN_WIDTH - 20, 335); } #if BOTH(CASE_LIGHT_MENU, CASELIGHT_USES_BRIGHTNESS) @@ -3644,7 +3279,7 @@ void Draw_Tune_Menu() { if (CurrentMenu != TuneMenu) { CurrentMenu = TuneMenu; SetMenuTitle({73, 2, 28, 12}, GET_TEXT_F(MSG_TUNE)); // TODO: Chinese, English "Tune" JPG - DWINUI::MenuItemsPrepare(14); + DWINUI::MenuItemsPrepare(16); MENU_ITEM(ICON_Back, GET_TEXT_F(MSG_BUTTON_BACK), onDrawBack, Goto_PrintProcess); #if ENABLED(CASE_LIGHT_MENU) MENU_ITEM(ICON_CaseLight, GET_TEXT_F(MSG_CASE_LIGHT), onDrawCaseLight, SetCaseLight); @@ -3677,6 +3312,7 @@ void Draw_Tune_Menu() { MENU_ITEM(ICON_Lock, GET_TEXT_F(MSG_LOCKSCREEN), onDrawMenuItem, DWIN_LockScreen); #if HAS_LCD_BRIGHTNESS EDIT_ITEM(ICON_Brightness, GET_TEXT_F(MSG_BRIGHTNESS), onDrawPInt8Menu, SetBrightness, &ui.brightness); + MENU_ITEM(ICON_Brightness, GET_TEXT_F(MSG_BRIGHTNESS_OFF), onDrawMenuItem, TurnOffBacklight); #endif } CurrentMenu->draw(); @@ -3972,4 +3608,4 @@ void Draw_Steps_Menu() { } #endif -#endif // DWIN_CREALITY_LCD_ENHANCED +#endif // DWIN_LCD_PROUI diff --git a/Marlin/src/lcd/e3v2/proui/dwin.h b/Marlin/src/lcd/e3v2/proui/dwin.h index 04ac1590ebf18..b61ed846dfcbf 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.h +++ b/Marlin/src/lcd/e3v2/proui/dwin.h @@ -22,32 +22,18 @@ #pragma once /** - * Enhanced DWIN implementation + * DWIN Enhanced implementation for PRO UI * Author: Miguel A. Risco-Castillo (MRISCOC) - * Version: 3.9.2 - * date: 2021/11/21 - * - * Based on the original code provided by Creality under GPL + * Version: 3.15.2 + * Date: 2022/03/01 */ -#include "../../../inc/MarlinConfigPre.h" +#include "dwin_defines.h" #include "dwinui.h" #include "../common/encoder.h" #include "../../../libs/BL24CXX.h" -#if ANY(AUTO_BED_LEVELING_BILINEAR, AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_3POINT) && DISABLED(PROBE_MANUALLY) - #define HAS_ONESTEP_LEVELING 1 -#endif - -#if !HAS_BED_PROBE && ENABLED(BABYSTEPPING) - #define JUST_BABYSTEP 1 -#endif - -#if ANY(BABYSTEPPING, HAS_BED_PROBE, HAS_WORKSPACE_OFFSET) - #define HAS_ZOFFSET_ITEM 1 -#endif - -#include "dwin_defines.h" +#include "../../../inc/MarlinConfig.h" enum processID : uint8_t { // Process ID @@ -60,23 +46,16 @@ enum processID : uint8_t { SetPFloat, SelectFile, PrintProcess, - PrintDone, - PwrlossRec, - Reboot, - Info, - ConfirmToPrint, - - // Popup Windows - Homing, + Popup, Leveling, - PidProcess, + Locked, + Reboot, + PrintDone, ESDiagProcess, - PrintStatsProcess, - PauseOrStop, - FilamentPurge, WaitResponse, - Locked, - NothingToDo, + Homing, + PidProcess, + NothingToDo }; enum pidresult_t : uint8_t { @@ -93,24 +72,18 @@ enum pidresult_t : uint8_t { typedef struct { int8_t Color[3]; // Color components - uint16_t pidgrphpoints = 0; pidresult_t pidresult = PID_DONE; int8_t Preheat = 0; // Material Select 0: PLA, 1: ABS, 2: Custom AxisEnum axis = X_AXIS; // Axis Select - int32_t MaxValue = 0; // Auxiliar max integer/scaled float value - int32_t MinValue = 0; // Auxiliar min integer/scaled float value - int8_t dp = 0; // Auxiliar decimal places - int32_t Value = 0; // Auxiliar integer / scaled float value - int16_t *P_Int = nullptr; // Auxiliar pointer to 16 bit integer variable - float *P_Float = nullptr; // Auxiliar pointer to float variable - void (*Apply)() = nullptr; // Auxiliar apply function - void (*LiveUpdate)() = nullptr; // Auxiliar live update function } HMI_value_t; typedef struct { uint8_t language; + bool remain_flag:1; // remain was override by M73 bool pause_flag:1; // printing is paused bool pause_action:1; // flag a pause action + bool abort_flag:1; // printing is aborting + bool abort_action:1; // flag a aborting action bool print_finish:1; // print was finished bool select_flag:1; // Popup button selected bool home_flag:1; // homing in course @@ -126,9 +99,6 @@ extern millis_t dwin_heat_time; #if HAS_HOTEND || HAS_HEATED_BED void DWIN_Popup_Temperature(const bool toohigh); #endif -#if HAS_HOTEND - void Popup_Window_ETempTooLow(); -#endif #if ENABLED(POWER_LOSS_RECOVERY) void Popup_PowerLossRecovery(); #endif @@ -143,50 +113,64 @@ void Goto_Main_Menu(); void Goto_Info_Menu(); void Goto_PowerLossRecovery(); void Goto_ConfirmToPrint(); -void Draw_Status_Area(const bool with_update); // Status Area +void DWIN_Draw_Dashboard(const bool with_update); // Status Area void Draw_Main_Area(); // Redraw main area; void DWIN_Redraw_screen(); // Redraw all screen elements -void HMI_StartFrame(const bool with_update); // Prepare the menu view void HMI_MainMenu(); // Main process screen void HMI_SelectFile(); // File page void HMI_Printing(); // Print page void HMI_ReturnScreen(); // Return to previous screen before popups void ApplyExtMinT(); void HMI_SetLanguageCache(); // Set the languaje image cache +void RebootPrinter(); +#if ENABLED(BAUD_RATE_GCODE) + void HMI_SetBaudRate(); + void SetBaud115K(); + void SetBaud250K(); +#endif +#if ENABLED(EEPROM_SETTINGS) + void WriteEeprom(); + void ReadEeprom(); + void ResetEeprom(); +#endif -void HMI_Init(); -void HMI_Popup(); +void HMI_WaitForUser(); void HMI_SaveProcessID(const uint8_t id); void HMI_AudioFeedback(const bool success=true); void EachMomentUpdate(); void update_variable(); +void DWIN_InitScreen(); void DWIN_HandleScreen(); -void DWIN_Update(); void DWIN_CheckStatusMessage(); -void DWIN_StartHoming(); -void DWIN_CompletedHoming(); +void DWIN_HomingStart(); +void DWIN_HomingDone(); #if HAS_MESH - void DWIN_MeshUpdate(const int8_t xpos, const int8_t ypos, const float zval); + void DWIN_MeshUpdate(const int8_t xpos, const int8_t ypos, const_float_t zval); #endif -void DWIN_MeshLevelingStart(); -void DWIN_CompletedLeveling(); +void DWIN_LevelingStart(); +void DWIN_LevelingDone(); void DWIN_PidTuning(pidresult_t result); -void DWIN_Print_Started(const bool sd = false); +void DWIN_Print_Started(const bool sd=false); +void DWIN_Print_Pause(); +void DWIN_Print_Resume(); void DWIN_Print_Finished(); +void DWIN_Print_Aborted(); #if HAS_FILAMENT_SENSOR void DWIN_FilamentRunout(const uint8_t extruder); #endif void DWIN_Progress_Update(); void DWIN_Print_Header(const char *text); void DWIN_SetColorDefaults(); +void DWIN_ApplyColor(); void DWIN_StoreSettings(char *buff); void DWIN_LoadSettings(const char *buff); void DWIN_SetDataDefaults(); void DWIN_RebootScreen(); #if ENABLED(ADVANCED_PAUSE_FEATURE) + void DWIN_Popup_Pause(FSTR_P const fmsg, uint8_t button=0); void Draw_Popup_FilamentPurge(); - void DWIN_Popup_FilamentPurge(); + void Goto_FilamentPurge(); void HMI_FilamentPurge(); #endif @@ -207,14 +191,6 @@ void HMI_LockScreen(); void Draw_PrintStats(); #endif -// HMI user control functions -void HMI_Menu(); -void HMI_SetInt(); -void HMI_SetPInt(); -void HMI_SetIntNoDraw(); -void HMI_SetFloat(); -void HMI_SetPFloat(); - // Menu drawing functions void Draw_Control_Menu(); void Draw_AdvancedSettings_Menu(); diff --git a/Marlin/src/lcd/e3v2/proui/dwin_defines.h b/Marlin/src/lcd/e3v2/proui/dwin_defines.h index 3dc2408f4a005..5065bb94d75b4 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin_defines.h +++ b/Marlin/src/lcd/e3v2/proui/dwin_defines.h @@ -22,18 +22,37 @@ #pragma once /** - * DWIN general defines and data structs + * DWIN general defines and data structs for PRO UI * Author: Miguel A. Risco-Castillo (MRISCOC) - * Version: 3.9.2 - * Date: 2021/11/21 - * - * Based on the original code provided by Creality under GPL + * Version: 3.11.2 + * Date: 2022/02/28 */ -//#define NEED_HEX_PRINT 1 //#define DEBUG_DWIN 1 +//#define NEED_HEX_PRINT 1 + +#include "../../../inc/MarlinConfigPre.h" +#include + +#if DISABLED(INDIVIDUAL_AXIS_HOMING_SUBMENU) + #error "INDIVIDUAL_AXIS_HOMING_SUBMENU is required with ProUI." +#endif +#if DISABLED(LCD_SET_PROGRESS_MANUALLY) + #error "LCD_SET_PROGRESS_MANUALLY is required with ProUI." +#endif +#if DISABLED(STATUS_MESSAGE_SCROLLING) + #error "STATUS_MESSAGE_SCROLLING is required with ProUI." +#endif +#if DISABLED(BAUD_RATE_GCODE) + #error "BAUD_RATE_GCODE is required with ProUI." +#endif +#if DISABLED(SOUND_MENU_ITEM) + #error "SOUND_MENU_ITEM is required with ProUI." +#endif +#if DISABLED(PRINTCOUNTER) + #error "PRINTCOUNTER is required with ProUI." +#endif -#include "../../../core/types.h" #include "../common/dwin_color.h" #if ENABLED(LED_CONTROL_MENU) #include "../../../feature/leds/leds.h" @@ -57,8 +76,8 @@ #define Def_Barfill_Color BarFill_Color #define Def_Indicator_Color Color_White #define Def_Coordinate_Color Color_White +#define Def_Button_Color RGB( 0, 23, 16) -//#define HAS_GCODE_PREVIEW 1 #define HAS_ESDIAG 1 #if ENABLED(LED_CONTROL_MENU, HAS_COLOR_LEDS) @@ -101,6 +120,9 @@ typedef struct { #if ENABLED(PREVENT_COLD_EXTRUSION) int16_t ExtMinT = EXTRUDE_MINTEMP; #endif + int16_t BedLevT = PREHEAT_1_TEMP_BED; + TERN_(BAUD_RATE_GCODE, bool Baud115K = false); + bool FullManualTramming = false; // Led #if BOTH(LED_CONTROL_MENU, HAS_COLOR_LEDS) LEDColor Led_Color = Def_Leds_Color; @@ -113,3 +135,8 @@ typedef struct { static constexpr size_t eeprom_data_size = 64; extern HMI_data_t HMI_data; + +#if PREHEAT_1_TEMP_BED + #undef LEVELING_BED_TEMP + #define LEVELING_BED_TEMP HMI_data.BedLevT +#endif diff --git a/Marlin/src/lcd/e3v2/proui/dwin_lcd.cpp b/Marlin/src/lcd/e3v2/proui/dwin_lcd.cpp index 105f1aaf1cd49..3da3fc808624f 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin_lcd.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin_lcd.cpp @@ -21,22 +21,68 @@ */ /** - * DWIN UI Enhanced implementation + * DWIN Enhanced implementation for PRO UI * Author: Miguel A. Risco-Castillo (MRISCOC) - * Version: 3.8.1 - * Date: 2021/11/09 - * - * Based on the original code provided by Creality under GPL + * Version: 3.9.1 + * Date: 2022/02/08 */ #include "../../../inc/MarlinConfigPre.h" -#if ENABLED(DWIN_CREALITY_LCD_ENHANCED) +#if ENABLED(DWIN_LCD_PROUI) #include "../../../inc/MarlinConfig.h" #include "dwin_lcd.h" +/*---------------------------------------- Numeric related functions ----------------------------------------*/ + +// Draw a numeric value +// bShow: true=display background color; false=don't display background color +// zeroFill: true=zero fill; false=no zero fill +// signedMode: 1=signed; 0=unsigned +// 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 +// fNum: Number of decimal digits +// x/y: Upper-left coordinate +// value: Integer value +void DWIN_Draw_Value(uint8_t bShow, bool signedMode, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, + uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, int32_t value) { + 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) | (signedMode * 0x40) | (zeroFill * 0x20) | (zeroMode * 0x10) | size); + DWIN_Word(i, color); + DWIN_Word(i, bColor); + DWIN_Byte(i, signedMode && (value >= 0) ? iNum + 1 : iNum); + DWIN_Byte(i, fNum); + DWIN_Word(i, x); + DWIN_Word(i, y); + // Write a big-endian 64 bit integer + const size_t p = i + 1; + for (size_t count = 8; count--;) { // 7..0 + ++i; + DWIN_SendBuf[p + count] = value; + value >>= 8; + } + DWIN_Send(i); +} + +// Draw a numeric value +// value: positive unscaled float value +void DWIN_Draw_Value(uint8_t bShow, bool signedMode, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, + uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value) { + const int32_t val = round(value * POW(10, fNum)); + DWIN_Draw_Value(bShow, signedMode, zeroFill, zeroMode, size, color, bColor, iNum, fNum, x, y, val); +} + /*---------------------------------------- Picture related functions ----------------------------------------*/ // Display QR code @@ -159,4 +205,4 @@ void DWIN_SRAMToPic(uint8_t picID) { // DWIN_Send(i); //} -#endif // DWIN_CREALITY_LCD_ENHANCED +#endif // DWIN_LCD_PROUI diff --git a/Marlin/src/lcd/e3v2/proui/dwin_lcd.h b/Marlin/src/lcd/e3v2/proui/dwin_lcd.h index 623a94f09e171..cdffb96f2f303 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin_lcd.h +++ b/Marlin/src/lcd/e3v2/proui/dwin_lcd.h @@ -22,16 +22,32 @@ #pragma once /** - * DWIN UI Enhanced implementation + * DWIN Enhanced implementation for PRO UI * Author: Miguel A. Risco-Castillo (MRISCOC) - * Version: 3.8.1 - * Date: 2021/11/09 - * - * Based on the original code provided by Creality under GPL + * Version: 3.9.1 + * Date: 2022/02/08 */ #include "../common/dwin_api.h" +// Draw a numeric value +// bShow: true=display background color; false=don't display background color +// zeroFill: true=zero fill; false=no zero fill +// signedMode: 1=signed; 0=unsigned +// 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 +// fNum: Number of decimal digits +// x/y: Upper-left coordinate +// value: Integer value +void DWIN_Draw_Value(uint8_t bShow, bool signedMode, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, + uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, int32_t value); +// value: positive unscaled float value +void DWIN_Draw_Value(uint8_t bShow, bool signedMode, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, + uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value); + // Display QR code // The size of the QR code is (46*QR_Pixel)*(46*QR_Pixel) dot matrix // QR_Pixel: The pixel size occupied by each point of the QR code: 0x01-0x0F (1-16) diff --git a/Marlin/src/lcd/e3v2/proui/dwin_popup.cpp b/Marlin/src/lcd/e3v2/proui/dwin_popup.cpp index 34b05328d7e9e..59b6c0d328ae6 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin_popup.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin_popup.cpp @@ -21,43 +21,75 @@ */ /** - * DWIN UI Enhanced implementation + * DWIN Enhanced implementation for PRO UI * Author: Miguel A. Risco-Castillo (MRISCOC) - * Version: 3.10.1 - * Date: 2022/01/21 - * - * Based on the original code provided by Creality under GPL + * Version: 3.11.1 + * Date: 2022/02/28 */ #include "../../../inc/MarlinConfigPre.h" -#if ENABLED(DWIN_CREALITY_LCD_ENHANCED) +#if ENABLED(DWIN_LCD_PROUI) #include "dwin.h" +#include "dwinui.h" #include "dwin_popup.h" -void Draw_Select_Highlight(const bool sel) { +#include "../../../MarlinCore.h" // for wait_for_user + +popupDrawFunc_t popupDraw = nullptr; +popupClickFunc_t popupClick = nullptr; +popupChangeFunc_t popupChange = nullptr; + +uint16_t HighlightYPos = 280; + +void Draw_Select_Highlight(const bool sel, const uint16_t ypos) { + HighlightYPos = ypos; HMI_flag.select_flag = sel; const uint16_t c1 = sel ? HMI_data.Highlight_Color : HMI_data.PopupBg_color, c2 = sel ? HMI_data.PopupBg_color : HMI_data.Highlight_Color; - DWIN_Draw_Rectangle(0, c1, 25, 279, 126, 318); - DWIN_Draw_Rectangle(0, c1, 24, 278, 127, 319); - DWIN_Draw_Rectangle(0, c2, 145, 279, 246, 318); - DWIN_Draw_Rectangle(0, c2, 144, 278, 247, 319); + DWIN_Draw_Rectangle(0, c1, 25, ypos - 1, 126, ypos + 38); + DWIN_Draw_Rectangle(0, c1, 24, ypos - 2, 127, ypos + 39); + DWIN_Draw_Rectangle(0, c2, 145, ypos - 1, 246, ypos + 38); + DWIN_Draw_Rectangle(0, c2, 144, ypos - 2, 247, ypos + 39); } void DWIN_Popup_Continue(const uint8_t icon, FSTR_P const fmsg1, FSTR_P const fmsg2) { HMI_SaveProcessID(WaitResponse); - DWIN_Draw_Popup(icon, fmsg1, fmsg2, ICON_Continue_E); // Button Continue + DWIN_Draw_Popup(icon, fmsg1, fmsg2, BTN_Continue); // Button Continue DWIN_UpdateLCD(); } void DWIN_Popup_ConfirmCancel(const uint8_t icon, FSTR_P const fmsg2) { DWIN_Draw_Popup(ICON_BLTouch, F("Please confirm"), fmsg2); - DWINUI::Draw_IconWB(ICON_Confirm_E, 26, 280); - DWINUI::Draw_IconWB(ICON_Cancel_E, 146, 280); - Draw_Select_Highlight(true); + DWINUI::Draw_Button(BTN_Confirm, 26, 280); + DWINUI::Draw_Button(BTN_Cancel, 146, 280); + Draw_Select_Highlight(HMI_flag.select_flag); DWIN_UpdateLCD(); } -#endif // DWIN_CREALITY_LCD_ENHANCED +void Goto_Popup(const popupDrawFunc_t fnDraw, const popupClickFunc_t fnClick/*=nullptr*/, const popupChangeFunc_t fnChange/*=nullptr*/) { + popupDraw = fnDraw; + popupClick = fnClick; + popupChange = fnChange; + HMI_SaveProcessID(Popup); + HMI_flag.select_flag = false; + popupDraw(); +} + +void HMI_Popup() { + if (!wait_for_user) { + if (popupClick) popupClick(); + return; + } + else { + EncoderState encoder_diffState = get_encoder_state(); + if (encoder_diffState == ENCODER_DIFF_CW || encoder_diffState == ENCODER_DIFF_CCW) { + const bool change = encoder_diffState != ENCODER_DIFF_CW; + if (popupChange) popupChange(change); else Draw_Select_Highlight(change, HighlightYPos); + DWIN_UpdateLCD(); + } + } +} + +#endif // DWIN_LCD_PROUI diff --git a/Marlin/src/lcd/e3v2/proui/dwin_popup.h b/Marlin/src/lcd/e3v2/proui/dwin_popup.h index 2e952cc1b99b9..0d864994754b7 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin_popup.h +++ b/Marlin/src/lcd/e3v2/proui/dwin_popup.h @@ -22,20 +22,26 @@ #pragma once /** - * DWIN UI Enhanced implementation + * DWIN Enhanced implementation for PRO UI * Author: Miguel A. Risco-Castillo (MRISCOC) - * Version: 3.10.1 - * Date: 2022/01/21 - * - * Based on the original code provided by Creality under GPL + * Version: 3.11.1 + * Date: 2022/02/28 */ #include "dwinui.h" #include "dwin.h" -// Popup windows +typedef void (*popupDrawFunc_t)(); +typedef void (*popupClickFunc_t)(); +typedef void (*popupChangeFunc_t)(const bool state); +extern popupDrawFunc_t popupDraw; -void Draw_Select_Highlight(const bool sel); +void Draw_Select_Highlight(const bool sel, const uint16_t ypos); +inline void Draw_Select_Highlight(const bool sel) { Draw_Select_Highlight(sel, 280); }; +void DWIN_Popup_Continue(const uint8_t icon, FSTR_P const fmsg1, FSTR_P const fmsg2); +void DWIN_Popup_ConfirmCancel(const uint8_t icon, FSTR_P const fmsg2); +void Goto_Popup(const popupDrawFunc_t fnDraw, const popupClickFunc_t fnClick=nullptr, const popupChangeFunc_t fnChange=nullptr); +void HMI_Popup(); inline void Draw_Popup_Bkgd() { DWIN_Draw_Rectangle(1, HMI_data.PopupBg_color, 14, 60, 258, 330); @@ -49,7 +55,7 @@ void DWIN_Draw_Popup(const uint8_t icon, T amsg1=nullptr, U amsg2=nullptr, uint8 if (icon) DWINUI::Draw_Icon(icon, 101, 105); if (amsg1) DWINUI::Draw_CenteredString(HMI_data.PopupTxt_Color, 210, amsg1); if (amsg2) DWINUI::Draw_CenteredString(HMI_data.PopupTxt_Color, 240, amsg2); - if (button) DWINUI::Draw_IconWB(button, 86, 280); + if (button) DWINUI::Draw_Button(button, 86, 280); } template @@ -61,10 +67,7 @@ void DWIN_Show_Popup(const uint8_t icon, T amsg1=nullptr, U amsg2=nullptr, uint8 template void DWIN_Popup_Confirm(const uint8_t icon, T amsg1, U amsg2) { HMI_SaveProcessID(WaitResponse); - DWIN_Draw_Popup(icon, amsg1, amsg2, ICON_Confirm_E); // Button Confirm + DWIN_Draw_Popup(icon, amsg1, amsg2, BTN_Confirm); // Button Confirm DWIN_UpdateLCD(); } -void DWIN_Popup_Continue(const uint8_t icon, FSTR_P const fmsg1, FSTR_P const fmsg2); - -void DWIN_Popup_ConfirmCancel(const uint8_t icon, FSTR_P const fmsg2); diff --git a/Marlin/src/lcd/e3v2/proui/dwinui.cpp b/Marlin/src/lcd/e3v2/proui/dwinui.cpp index d3cfc9a3e472b..ddc494fc84923 100644 --- a/Marlin/src/lcd/e3v2/proui/dwinui.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwinui.cpp @@ -21,17 +21,15 @@ */ /** - * DWIN UI Enhanced implementation + * DWIN Enhanced implementation for PRO UI * Author: Miguel A. Risco-Castillo (MRISCOC) - * Version: 3.8.2 - * Date: 2021/11/09 - * - * Based on the original code provided by Creality under GPL + * Version: 3.15.1 + * Date: 2022/02/25 */ #include "../../../inc/MarlinConfigPre.h" -#if ENABLED(DWIN_CREALITY_LCD_ENHANCED) +#if ENABLED(DWIN_LCD_PROUI) #include "../../../inc/MarlinConfig.h" #include "dwin_lcd.h" @@ -51,7 +49,9 @@ xy_int_t DWINUI::cursor = { 0 }; uint16_t DWINUI::pencolor = Color_White; uint16_t DWINUI::textcolor = Def_Text_Color; uint16_t DWINUI::backcolor = Def_Background_Color; +uint16_t DWINUI::buttoncolor = Def_Button_Color; uint8_t DWINUI::font = font8x16; +FSTR_P const DWINUI::Author = F(STRING_CONFIG_H_AUTHOR); void (*DWINUI::onCursorErase)(const int8_t line)=nullptr; void (*DWINUI::onCursorDraw)(const int8_t line)=nullptr; @@ -59,18 +59,16 @@ void (*DWINUI::onTitleDraw)(TitleClass* title)=nullptr; void (*DWINUI::onMenuDraw)(MenuClass* menu)=nullptr; void DWINUI::init() { - DEBUG_ECHOPGM("\r\nDWIN handshake "); - delay(750); // Delay here or init later in the boot process - const bool success = DWIN_Handshake(); - if (success) DEBUG_ECHOLNPGM("ok."); else DEBUG_ECHOLNPGM("error."); + TERN_(DEBUG_DWIN, SERIAL_ECHOPGM("\r\nDWIN handshake ")); + delay(750); // Delay for wait to wakeup screen + const bool hs = DWIN_Handshake(); + TERN(DEBUG_DWIN, SERIAL_ECHOLNF(hs ? F("ok.") : F("error.")), UNUSED(hs)); DWIN_Frame_SetDir(1); - TERN(SHOW_BOOTSCREEN,,DWIN_Frame_Clear(Color_Bg_Black)); - DWIN_UpdateLCD(); - cursor.x = 0; - cursor.y = 0; + cursor.reset(); pencolor = Color_White; textcolor = Def_Text_Color; backcolor = Def_Background_Color; + buttoncolor = Def_Button_Color; font = font8x16; } @@ -124,9 +122,10 @@ uint16_t DWINUI::RowToY(uint8_t row) { } // Set text/number color -void DWINUI::SetColors(uint16_t fgcolor, uint16_t bgcolor) { +void DWINUI::SetColors(uint16_t fgcolor, uint16_t bgcolor, uint16_t alcolor) { textcolor = fgcolor; backcolor = bgcolor; + buttoncolor = alcolor; } void DWINUI::SetTextColor(uint16_t fgcolor) { textcolor = fgcolor; @@ -159,16 +158,22 @@ void DWINUI::MoveBy(xy_int_t point) { cursor += point; } -// Draw a Centered string using DWIN_WIDTH -void DWINUI::Draw_CenteredString(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t y, const char * const string) { - const int8_t x = _MAX(0U, DWIN_WIDTH - strlen_P(string) * fontWidth(size)) / 2 - 1; +// Draw a Centered string using arbitrary x1 and x2 margins +void DWINUI::Draw_CenteredString(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x1, uint16_t x2, uint16_t y, const char * const string) { + const uint16_t x = _MAX(0U, x2 + x1 - strlen_P(string) * fontWidth(size)) / 2 - 1; DWIN_Draw_String(bShow, size, color, bColor, x, y, string); } +// // Draw a Centered string using DWIN_WIDTH +// void DWINUI::Draw_CenteredString(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t y, const char * const string) { +// const int8_t x = _MAX(0U, DWIN_WIDTH - strlen_P(string) * fontWidth(size)) / 2 - 1; +// DWIN_Draw_String(bShow, size, color, bColor, x, y, string); +// } + // Draw a char at cursor position -void DWINUI::Draw_Char(const char c) { +void DWINUI::Draw_Char(uint16_t color, const char c) { const char string[2] = { c, 0}; - DWIN_Draw_String(false, font, textcolor, backcolor, cursor.x, cursor.y, string, 1); + DWIN_Draw_String(false, font, color, backcolor, cursor.x, cursor.y, string, 1); MoveBy(fontWidth(font), 0); } @@ -185,21 +190,26 @@ void DWINUI::Draw_String(uint16_t color, const char * const string, uint16_t rli MoveBy(strlen(string) * fontWidth(font), 0); } -// Draw a signed floating point number -// bShow: true=display background color; false=don't display background color -// zeroFill: true=zero fill; false=no zero fill -// zeroMode: 1=leading 0 displayed as 0; 0=leading 0 displayed as a space -// size: Font size -// bColor: Background color -// iNum: Number of whole digits -// fNum: Number of decimal digits -// x/y: Upper-left point -// value: Float value -void DWINUI::Draw_Signed_Float(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value) { - DWIN_Draw_FloatValue(bShow, zeroFill, zeroMode, size, color, bColor, iNum, fNum, x, y, value < 0 ? -value : value); - DWIN_Draw_String(bShow, size, color, bColor, x - 6, y, value < 0 ? F("-") : F(" ")); +// ------------------------- Buttons ------------------------------// + +void DWINUI::Draw_Button(uint16_t color, uint16_t bcolor, uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2, const char * const caption) { + DWIN_Draw_Rectangle(1, bcolor, x1, y1, x2, y2); + Draw_CenteredString(0, font, color, bcolor, x1, x2, (y2 + y1 - fontHeight())/2, caption); +} + +void DWINUI::Draw_Button(uint8_t id, uint16_t x, uint16_t y) { + switch (id) { + case BTN_Cancel : Draw_Button(GET_TEXT_F(MSG_BUTTON_CANCEL), x, y); break; + case BTN_Confirm : Draw_Button(GET_TEXT_F(MSG_BUTTON_CONFIRM), x, y); break; + case BTN_Continue: Draw_Button(GET_TEXT_F(MSG_BUTTON_CONTINUE), x, y); break; + case BTN_Print : Draw_Button(GET_TEXT_F(MSG_BUTTON_PRINT), x, y); break; + case BTN_Save : Draw_Button(GET_TEXT_F(MSG_BUTTON_SAVE), x, y); break; + default: break; + } } +// -------------------------- Extra -------------------------------// + // Draw a circle // color: circle color // x: the abscissa of the center of the circle @@ -247,13 +257,12 @@ void DWINUI::Draw_FillCircle(uint16_t bcolor, uint16_t x,uint16_t y,uint8_t r) { // color1 : Start color // color2 : End color uint16_t DWINUI::ColorInt(int16_t val, int16_t minv, int16_t maxv, uint16_t color1, uint16_t color2) { - uint8_t B,G,R; - float n; - n = (float)(val-minv)/(maxv-minv); - R = (1-n)*GetRColor(color1) + n*GetRColor(color2); - G = (1-n)*GetGColor(color1) + n*GetGColor(color2); - B = (1-n)*GetBColor(color1) + n*GetBColor(color2); - return RGB(R,G,B); + uint8_t B, G, R; + const float n = (float)(val - minv) / (maxv - minv); + R = (1 - n) * GetRColor(color1) + n * GetRColor(color2); + G = (1 - n) * GetGColor(color1) + n * GetGColor(color2); + B = (1 - n) * GetBColor(color1) + n * GetBColor(color2); + return RGB(R, G, B); } // Color Interpolator through Red->Yellow->Green->Blue @@ -261,33 +270,27 @@ uint16_t DWINUI::ColorInt(int16_t val, int16_t minv, int16_t maxv, uint16_t colo // minv : Minimum value // maxv : Maximum value uint16_t DWINUI::RainbowInt(int16_t val, int16_t minv, int16_t maxv) { - uint8_t B,G,R; - const uint8_t maxB = 28; - const uint8_t maxR = 28; - const uint8_t maxG = 38; + uint8_t B, G, R; + const uint8_t maxB = 28, maxR = 28, maxG = 38; const int16_t limv = _MAX(abs(minv), abs(maxv)); - float n; - if (minv>=0) { - n = (float)(val-minv)/(maxv-minv); - } else { - n = (float)val/limv; - } - n = _MIN(1, n); - n = _MAX(-1, n); + float n = minv >= 0 ? (float)(val - minv) / (maxv - minv) : (float)val / limv; + LIMIT(n, -1, 1); if (n < 0) { R = 0; - G = (1+n)*maxG; - B = (-n)*maxB; - } else if (n < 0.5) { - R = maxR*n*2; + G = (1 + n) * maxG; + B = (-n) * maxB; + } + else if (n < 0.5) { + R = maxR * n * 2; G = maxG; B = 0; - } else { + } + else { R = maxR; - G = maxG*(1-n); + G = maxG * (1 - n); B = 0; } - return RGB(R,G,B); + return RGB(R, G, B); } // Draw a checkbox @@ -453,4 +456,4 @@ MenuItemPtrClass::MenuItemPtrClass(uint8_t cicon, const char * const text, void value = val; }; -#endif // DWIN_CREALITY_LCD_ENHANCED +#endif // DWIN_LCD_PROUI diff --git a/Marlin/src/lcd/e3v2/proui/dwinui.h b/Marlin/src/lcd/e3v2/proui/dwinui.h index 595c534356d4f..1504dcd30598f 100644 --- a/Marlin/src/lcd/e3v2/proui/dwinui.h +++ b/Marlin/src/lcd/e3v2/proui/dwinui.h @@ -22,12 +22,10 @@ #pragma once /** - * DWIN UI Enhanced implementation + * DWIN Enhanced implementation for PRO UI * Author: Miguel A. Risco-Castillo (MRISCOC) - * Version: 3.11.1 - * Date: 2022/01/19 - * - * Based on the original code provided by Creality under GPL + * Version: 3.15.1 + * Date: 2022/02/25 */ #include "dwin_lcd.h" @@ -107,6 +105,13 @@ #define ICON_CaseLight ICON_Motion #define ICON_LedControl ICON_Motion +// Buttons +#define BTN_Continue 85 +#define BTN_Cancel 87 +#define BTN_Confirm 89 +#define BTN_Print 90 +#define BTN_Save 91 + // Extended and default UI Colors #define Color_Black 0 #define Color_Green RGB(0,63,0) @@ -119,7 +124,11 @@ #define DWIN_FONT_HEAD font10x20 #define DWIN_FONT_ALERT font10x20 #define STATUS_Y 354 -#define LCD_WIDTH (DWIN_WIDTH / 8) +#define LCD_WIDTH (DWIN_WIDTH / 8) // only if the default font is font8x16 + +// Minimum unit (0.1) : multiple (10) +#define UNITFDIGITS 1 +#define MINUNITMULT POW(10, UNITFDIGITS) constexpr uint16_t TITLE_HEIGHT = 30, // Title bar height MLINE = 53, // Menu line height @@ -212,7 +221,9 @@ namespace DWINUI { extern uint16_t pencolor; extern uint16_t textcolor; extern uint16_t backcolor; + extern uint16_t buttoncolor; extern uint8_t font; + extern FSTR_P const Author; extern void (*onCursorErase)(const int8_t line); extern void (*onCursorDraw)(const int8_t line); @@ -240,7 +251,7 @@ namespace DWINUI { uint16_t RowToY(uint8_t row); // Set text/number color - void SetColors(uint16_t fgcolor, uint16_t bgcolor); + void SetColors(uint16_t fgcolor, uint16_t bgcolor, uint16_t alcolor); void SetTextColor(uint16_t fgcolor); void SetBackgroundColor(uint16_t bgcolor); @@ -268,6 +279,17 @@ namespace DWINUI { DWIN_Draw_Line(pencolor, cursor.x, cursor.y, x, y); } + // Extend a frame box + // v: value to extend + inline frame_rect_t ExtendFrame(frame_rect_t frame, uint8_t v) { + frame_rect_t t; + t.x = frame.x - v; + t.y = frame.y - v; + t.w = frame.w + 2 * v; + t.h = frame.h + 2 * v; + return t; + } + // Draw an Icon with transparent background from the library ICON // icon: Icon ID // x/y: Upper-left point @@ -293,26 +315,56 @@ namespace DWINUI { // x/y: Upper-left coordinate // value: Integer value inline void Draw_Int(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, long value) { - DWIN_Draw_IntValue(bShow, zeroFill, zeroMode, size, color, bColor, iNum, x, y, value); + DWIN_Draw_Value(bShow, 0, zeroFill, zeroMode, size, color, bColor, iNum, 0, x, y, value); } inline void Draw_Int(uint8_t iNum, long value) { - DWIN_Draw_IntValue(false, true, 0, font, textcolor, backcolor, iNum, cursor.x, cursor.y, value); + DWIN_Draw_Value(false, 0, true, 0, font, textcolor, backcolor, iNum, 0, cursor.x, cursor.y, value); MoveBy(iNum * fontWidth(font), 0); } inline void Draw_Int(uint8_t iNum, uint16_t x, uint16_t y, long value) { - DWIN_Draw_IntValue(false, true, 0, font, textcolor, backcolor, iNum, x, y, value); + DWIN_Draw_Value(false, 0, true, 0, font, textcolor, backcolor, iNum, 0, x, y, value); } inline void Draw_Int(uint16_t color, uint8_t iNum, uint16_t x, uint16_t y, long value) { - DWIN_Draw_IntValue(false, true, 0, font, color, backcolor, iNum, x, y, value); + DWIN_Draw_Value(false, 0, true, 0, font, color, backcolor, iNum, 0, x, y, value); } inline void Draw_Int(uint16_t color, uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, long value) { - DWIN_Draw_IntValue(true, true, 0, font, color, bColor, iNum, x, y, value); + DWIN_Draw_Value(true, 0, true, 0, font, color, bColor, iNum, 0, x, y, value); } inline void Draw_Int(uint8_t size, uint16_t color, uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, long value) { - DWIN_Draw_IntValue(true, true, 0, size, color, bColor, iNum, x, y, value); + DWIN_Draw_Value(true, 0, true, 0, size, color, bColor, iNum, 0, x, y, value); } - // Draw a floating point number + // Draw a signed integer + // bShow: true=display background color; false=don't display background color + // zeroFill: true=zero fill; false=no zero fill + // zeroMode: 1=leading 0 displayed as 0; 0=leading 0 displayed as a space + // size: Font size + // color: Character color + // bColor: Background color + // iNum: Number of digits + // x/y: Upper-left coordinate + // value: Integer value + inline void Draw_Signed_Int(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, long value) { + DWIN_Draw_Value(bShow, 1, zeroFill, zeroMode, size, color, bColor, iNum, 0, x, y, value); + } + inline void Draw_Signed_Int(uint8_t iNum, long value) { + DWIN_Draw_Value(false, 1, true, 0, font, textcolor, backcolor, iNum, 0, cursor.x, cursor.y, value); + MoveBy(iNum * fontWidth(font), 0); + } + inline void Draw_Signed_Int(uint8_t iNum, uint16_t x, uint16_t y, long value) { + DWIN_Draw_Value(false, 1, true, 0, font, textcolor, backcolor, iNum, 0, x, y, value); + } + inline void Draw_Signed_Int(uint16_t color, uint8_t iNum, uint16_t x, uint16_t y, long value) { + DWIN_Draw_Value(false, 1, true, 0, font, color, backcolor, iNum, 0, x, y, value); + } + inline void Draw_Signed_Int(uint16_t color, uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, long value) { + DWIN_Draw_Value(true, 1, true, 0, font, color, bColor, iNum, 0, x, y, value); + } + inline void Draw_Signed_Int(uint8_t size, uint16_t color, uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, long value) { + DWIN_Draw_Value(true, 1, true, 0, size, color, bColor, iNum, 0, x, y, value); + } + + // Draw a positive floating point number // bShow: true=display background color; false=don't display background color // zeroFill: true=zero fill; false=no zero fill // zeroMode: 1=leading 0 displayed as 0; 0=leading 0 displayed as a space @@ -324,23 +376,23 @@ namespace DWINUI { // x/y: Upper-left point // value: Float value inline void Draw_Float(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value) { - DWIN_Draw_FloatValue(bShow, zeroFill, zeroMode, size, color, bColor, iNum, fNum, x, y, value); + DWIN_Draw_Value(bShow, 0, zeroFill, zeroMode, size, color, bColor, iNum, fNum, x, y, value); } inline void Draw_Float(uint8_t iNum, uint8_t fNum, float value) { - DWIN_Draw_FloatValue(false, true, 0, font, textcolor, backcolor, iNum, fNum, cursor.x, cursor.y, value); + DWIN_Draw_Value(false, 0, true, 0, font, textcolor, backcolor, iNum, fNum, cursor.x, cursor.y, value); MoveBy((iNum + fNum + 1) * fontWidth(font), 0); } inline void Draw_Float(uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value) { - DWIN_Draw_FloatValue(false, true, 0, font, textcolor, backcolor, iNum, fNum, x, y, value); + DWIN_Draw_Value(false, 0, true, 0, font, textcolor, backcolor, iNum, fNum, x, y, value); } inline void Draw_Float(uint16_t color, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value) { - DWIN_Draw_FloatValue(false, true, 0, font, color, backcolor, iNum, fNum, x, y, value); + DWIN_Draw_Value(false, 0, true, 0, font, color, backcolor, iNum, fNum, x, y, value); } inline void Draw_Float(uint16_t color, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value) { - DWIN_Draw_FloatValue(true, true, 0, font, color, bColor, iNum, fNum, x, y, value); + DWIN_Draw_Value(true, 0, true, 0, font, color, bColor, iNum, fNum, x, y, value); } inline void Draw_Float(uint8_t size, uint16_t color, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value) { - DWIN_Draw_FloatValue(true, true, 0, size, color, bColor, iNum, fNum, x, y, value); + DWIN_Draw_Value(true, 0, true, 0, size, color, bColor, iNum, fNum, x, y, value); } // Draw a signed floating point number @@ -348,31 +400,35 @@ namespace DWINUI { // 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 Draw_Signed_Float(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value); + inline void Draw_Signed_Float(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value) { + DWIN_Draw_Value(bShow, 1, zeroFill, zeroMode, size, color, bColor, iNum, fNum, x, y, value); + } inline void Draw_Signed_Float(uint8_t iNum, uint8_t fNum, float value) { - Draw_Signed_Float(false, true, 0, font, textcolor, backcolor, iNum, fNum, cursor.x, cursor.y, value); + DWIN_Draw_Value(false, 1, true, 0, font, textcolor, backcolor, iNum, fNum, cursor.x, cursor.y, value); MoveBy((iNum + fNum + 1) * fontWidth(font), 0); } inline void Draw_Signed_Float(uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value) { - Draw_Signed_Float(false, true, 0, font, textcolor, backcolor, iNum, fNum, x, y, value); + DWIN_Draw_Value(false, 1, true, 0, font, textcolor, backcolor, iNum, fNum, x, y, value); } inline void Draw_Signed_Float(uint8_t size, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value) { - Draw_Signed_Float(false, true, 0, size, textcolor, backcolor, iNum, fNum, x, y, value); + DWIN_Draw_Value(false, 1, true, 0, size, textcolor, backcolor, iNum, fNum, x, y, value); } inline void Draw_Signed_Float(uint16_t color, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value) { - Draw_Signed_Float(true, true, 0, font, color, bColor, iNum, fNum, x, y, value); + DWIN_Draw_Value(true, 1, true, 0, font, color, bColor, iNum, fNum, x, y, value); } inline void Draw_Signed_Float(uint8_t size, uint16_t color, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value) { - Draw_Signed_Float(true, true, 0, size, color, bColor, iNum, fNum, x, y, value); + DWIN_Draw_Value(true, 1, true, 0, size, color, bColor, iNum, fNum, x, y, value); } // Draw a char at cursor position - void Draw_Char(const char c); + void Draw_Char(uint16_t color, const char c); + inline void Draw_Char(const char c) { Draw_Char(textcolor, c); } // Draw a string at cursor position // color: Character color @@ -425,7 +481,10 @@ namespace DWINUI { // bColor: Background color // y: Upper coordinate of the string // *string: The string - void Draw_CenteredString(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t y, const char * const string); + void Draw_CenteredString(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x1, uint16_t x2, uint16_t y, const char * const string); + inline void Draw_CenteredString(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t y, const char * const string) { + Draw_CenteredString(bShow, size, color, bColor, 0, DWIN_WIDTH, y, string); + } inline void Draw_CenteredString(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t y, FSTR_P string) { Draw_CenteredString(bShow, size, color, bColor, y, FTOP(string)); } @@ -487,6 +546,17 @@ namespace DWINUI { // color2 : End color uint16_t ColorInt(int16_t val, int16_t minv, int16_t maxv, uint16_t color1, uint16_t color2); + // ------------------------- Buttons ------------------------------// + + void Draw_Button(uint16_t color, uint16_t bcolor, uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2, const char * const caption); + inline void Draw_Button(uint16_t color, uint16_t bcolor, uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2, FSTR_P caption) { + Draw_Button(color, bcolor, x1, y1, x2, y2, FTOP(caption)); + } + inline void Draw_Button(FSTR_P caption, uint16_t x, uint16_t y) { + Draw_Button(textcolor, buttoncolor, x, y, x + 99, y + 37, caption); + } + void Draw_Button(uint8_t id, uint16_t x, uint16_t y); + // -------------------------- Extra -------------------------------// // Draw a circle filled with color diff --git a/Marlin/src/lcd/e3v2/proui/endstop_diag.cpp b/Marlin/src/lcd/e3v2/proui/endstop_diag.cpp index 6232c89534b30..74eb94e751afc 100644 --- a/Marlin/src/lcd/e3v2/proui/endstop_diag.cpp +++ b/Marlin/src/lcd/e3v2/proui/endstop_diag.cpp @@ -21,18 +21,15 @@ */ /** - * DWIN End Stops diagnostic page + * DWIN End Stops diagnostic page for PRO UI * Author: Miguel A. Risco-Castillo (MRISCOC) - * Version: 1.0.2 - * Date: 2021/11/06 - * - * Based on the original code provided by Creality under GPL + * Version: 1.2.2 + * Date: 2022/02/24 */ -#include "../../../inc/MarlinConfigPre.h" #include "dwin_defines.h" -#if BOTH(DWIN_CREALITY_LCD_ENHANCED, HAS_ESDIAG) +#if BOTH(DWIN_LCD_PROUI, HAS_ESDIAG) #include "endstop_diag.h" @@ -72,7 +69,7 @@ void ESDiagClass::Draw() { Title.ShowCaption(F("End-stops Diagnostic")); DWINUI::ClearMenuArea(); Draw_Popup_Bkgd(); - DWINUI::Draw_Icon(ICON_Continue_E, 86, 250); + DWINUI::Draw_Button(BTN_Continue, 86, 250); DWINUI::cursor.y = 80; #define ES_LABEL(S) draw_es_label(F(STR_##S)) #if HAS_X_MIN @@ -108,4 +105,4 @@ void ESDiagClass::Update() { DWIN_UpdateLCD(); } -#endif // DWIN_CREALITY_LCD_ENHANCED && HAS_ESDIAG +#endif // DWIN_LCD_PROUI && HAS_ESDIAG diff --git a/Marlin/src/lcd/e3v2/proui/endstop_diag.h b/Marlin/src/lcd/e3v2/proui/endstop_diag.h index 4694ddb141720..316a1e1ed3d9f 100644 --- a/Marlin/src/lcd/e3v2/proui/endstop_diag.h +++ b/Marlin/src/lcd/e3v2/proui/endstop_diag.h @@ -22,12 +22,10 @@ #pragma once /** - * DWIN End Stops diagnostic page + * DWIN End Stops diagnostic page for PRO UI * Author: Miguel A. Risco-Castillo (MRISCOC) - * Version: 1.0 - * Date: 2021/11/06 - * - * Based on the original code provided by Creality under GPL + * Version: 1.2.3 + * Date: 2022/02/24 */ class ESDiagClass { diff --git a/Marlin/src/lcd/e3v2/proui/lockscreen.cpp b/Marlin/src/lcd/e3v2/proui/lockscreen.cpp index 3f8339ad48bca..2895c01544b09 100644 --- a/Marlin/src/lcd/e3v2/proui/lockscreen.cpp +++ b/Marlin/src/lcd/e3v2/proui/lockscreen.cpp @@ -21,17 +21,15 @@ */ /** - * Lock screen implementation for DWIN UI Enhanced implementation + * Lock screen implementation for PRO UI * Author: Miguel A. Risco-Castillo (MRISCOC) * Version: 2.1 * Date: 2021/11/09 - * - * Based on the original code provided by Creality under GPL */ #include "../../../inc/MarlinConfigPre.h" -#if ENABLED(DWIN_CREALITY_LCD_ENHANCED) +#if ENABLED(DWIN_LCD_PROUI) #include "../../../core/types.h" #include "dwin_lcd.h" @@ -75,4 +73,4 @@ void LockScreenClass::onEncoder(EncoderState encoder_diffState) { DWIN_UpdateLCD(); } -#endif // DWIN_CREALITY_LCD_ENHANCED +#endif // DWIN_LCD_PROUI diff --git a/Marlin/src/lcd/e3v2/proui/lockscreen.h b/Marlin/src/lcd/e3v2/proui/lockscreen.h index bf2fdb3f4b0bd..ec967fe2db7cb 100644 --- a/Marlin/src/lcd/e3v2/proui/lockscreen.h +++ b/Marlin/src/lcd/e3v2/proui/lockscreen.h @@ -22,12 +22,10 @@ #pragma once /** - * Lock screen implementation for DWIN UI Enhanced implementation + * Lock screen implementation for PRO UI * Author: Miguel A. Risco-Castillo (MRISCOC) * Version: 2.1 * Date: 2021/11/09 - * - * Based on the original code provided by Creality under GPL */ #include "../common/encoder.h" diff --git a/Marlin/src/lcd/e3v2/proui/menus.cpp b/Marlin/src/lcd/e3v2/proui/menus.cpp new file mode 100644 index 0000000000000..6dfcb8595c87b --- /dev/null +++ b/Marlin/src/lcd/e3v2/proui/menus.cpp @@ -0,0 +1,370 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2022 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 . + * + */ + +/** + * Menu functions for ProUI + * Author: Miguel A. Risco-Castillo + * Version: 1.2.1 + * Date: 2022/02/25 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU Lesser General Public License as + * published by the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public License + * along with this program. If not, see . + * + */ + +#include "../../../inc/MarlinConfigPre.h" + +#if ENABLED(DWIN_LCD_PROUI) + +#include "../common/encoder.h" +#include "dwin_lcd.h" +#include "dwinui.h" +#include "dwin.h" +#include "menus.h" + +MenuData_t MenuData; + +// Menuitem Drawing functions ================================================= + +void Draw_Title(TitleClass* title) { + DWIN_Draw_Rectangle(1, HMI_data.TitleBg_color, 0, 0, DWIN_WIDTH - 1, TITLE_HEIGHT - 1); + if (title->frameid) + DWIN_Frame_AreaCopy(title->frameid, title->frame.left, title->frame.top, title->frame.right, title->frame.bottom, 14, (TITLE_HEIGHT - (title->frame.bottom - title->frame.top)) / 2 - 1); + else + DWIN_Draw_String(false, DWIN_FONT_HEAD, HMI_data.TitleTxt_color, HMI_data.TitleBg_color, 14, (TITLE_HEIGHT - DWINUI::fontHeight(DWIN_FONT_HEAD)) / 2 - 1, title->caption); +} + +void Draw_Menu(MenuClass* menu) { + DWINUI::SetColors(HMI_data.Text_Color, HMI_data.Background_Color, HMI_data.StatusBg_Color); + DWIN_Draw_Rectangle(1, DWINUI::backcolor, 0, TITLE_HEIGHT, DWIN_WIDTH - 1, STATUS_Y - 1); +} + +void Draw_Menu_Cursor(const int8_t line) { + DWIN_Draw_Rectangle(1, HMI_data.Cursor_color, 0, MBASE(line) - 18, 14, MBASE(line + 1) - 20); +} + +void Erase_Menu_Cursor(const int8_t line) { + DWIN_Draw_Rectangle(1, HMI_data.Background_Color, 0, MBASE(line) - 18, 14, MBASE(line + 1) - 20); +} + +void Draw_Menu_Line(const uint8_t line, const uint8_t icon /*=0*/, const char * const label /*=nullptr*/, bool more /*=false*/) { + if (icon) DWINUI::Draw_Icon(icon, ICOX, MBASE(line) - 3); + if (label) DWINUI::Draw_String(LBLX, MBASE(line) - 1, (char*)label); + if (more) DWINUI::Draw_Icon(ICON_More, VALX + 16, MBASE(line) - 3); + DWIN_Draw_HLine(HMI_data.SplitLine_Color, 16, MYPOS(line + 1), 240); +} + +void Draw_Chkb_Line(const uint8_t line, const bool checked) { + DWINUI::Draw_Checkbox(HMI_data.Text_Color, HMI_data.Background_Color, VALX + 16, MBASE(line) - 1, checked); +} + +void Draw_Menu_IntValue(uint16_t bcolor, const uint8_t line, uint8_t iNum, const int32_t value /*=0*/) { + DWINUI::Draw_Signed_Int(HMI_data.Text_Color, bcolor, iNum , VALX, MBASE(line) - 1, value); +} + +void onDrawMenuItem(MenuItemClass* menuitem, int8_t line) { + if (menuitem->icon) DWINUI::Draw_Icon(menuitem->icon, ICOX, MBASE(line) - 3); + if (menuitem->frameid) + DWIN_Frame_AreaCopy(menuitem->frameid, menuitem->frame.left, menuitem->frame.top, menuitem->frame.right, menuitem->frame.bottom, LBLX, MBASE(line)); + else if (menuitem->caption) + DWINUI::Draw_String(LBLX, MBASE(line) - 1, menuitem->caption); + DWIN_Draw_HLine(HMI_data.SplitLine_Color, 16, MYPOS(line + 1), 240); +} + +void onDrawSubMenu(MenuItemClass* menuitem, int8_t line) { + onDrawMenuItem(menuitem, line); + DWINUI::Draw_Icon(ICON_More, VALX + 16, MBASE(line) - 3); +} + +void onDrawIntMenu(MenuItemClass* menuitem, int8_t line, int32_t value) { + onDrawMenuItem(menuitem, line); + Draw_Menu_IntValue(HMI_data.Background_Color, line, 4, value); +} + +void onDrawPIntMenu(MenuItemClass* menuitem, int8_t line) { + const int16_t value = *(int16_t*)static_cast(menuitem)->value; + onDrawIntMenu(menuitem, line, value); +} + +void onDrawPInt8Menu(MenuItemClass* menuitem, int8_t line) { + const uint8_t value = *(uint8_t*)static_cast(menuitem)->value; + onDrawIntMenu(menuitem, line, value); +} + +void onDrawPInt32Menu(MenuItemClass* menuitem, int8_t line) { + const uint32_t value = *(uint32_t*)static_cast(menuitem)->value; + onDrawIntMenu(menuitem, line, value); +} + +void onDrawFloatMenu(MenuItemClass* menuitem, int8_t line, uint8_t dp, const float value) { + onDrawMenuItem(menuitem, line); + DWINUI::Draw_Signed_Float(HMI_data.Text_Color, HMI_data.Background_Color, 3, dp, VALX - dp * DWINUI::fontWidth(DWIN_FONT_MENU), MBASE(line), value); +} + +void onDrawPFloatMenu(MenuItemClass* menuitem, int8_t line) { + const float value = *(float*)static_cast(menuitem)->value; + const int8_t dp = UNITFDIGITS; + onDrawFloatMenu(menuitem, line, dp, value); +} + +void onDrawPFloat2Menu(MenuItemClass* menuitem, int8_t line) { + const float value = *(float*)static_cast(menuitem)->value; + onDrawFloatMenu(menuitem, line, 2, value); +} + +void onDrawChkbMenu(MenuItemClass* menuitem, int8_t line, bool checked) { + onDrawMenuItem(menuitem, line); + Draw_Chkb_Line(line, checked); +} + +//----------------------------------------------------------------------------- +// On click functions +//----------------------------------------------------------------------------- + +// Generic onclick event without draw +// process: process id HMI destiny +// lo: low limit +// hi: high limit +// dp: decimal places, 0 for integers +// val: value / scaled value +// LiveUpdate: live update function when the encoder changes +// Apply: update function when the encoder is pressed +void SetOnClick(uint8_t process, const int32_t lo, const int32_t hi, uint8_t dp, const int32_t val, void (*Apply)() /*= nullptr*/, void (*LiveUpdate)() /*= nullptr*/) { + checkkey = process; + MenuData.MinValue = lo; + MenuData.MaxValue = hi; + MenuData.dp = dp; + MenuData.Apply = Apply; + MenuData.LiveUpdate = LiveUpdate; + MenuData.Value = val; + EncoderRate.enabled = true; +} + +// Generic onclick event for integer values +// process: process id HMI destiny +// lo: scaled low limit +// hi: scaled high limit +// val: value +// LiveUpdate: live update function when the encoder changes +// Apply: update function when the encoder is pressed +void SetValueOnClick(uint8_t process, const int32_t lo, const int32_t hi, const int32_t val, void (*Apply)() /*= nullptr*/, void (*LiveUpdate)() /*= nullptr*/) { + SetOnClick(process, lo, hi, 0, val, Apply, LiveUpdate); + Draw_Menu_IntValue(HMI_data.Selected_Color, CurrentMenu->line(), 4, MenuData.Value); +} + +// Generic onclick event for float values +// process: process id HMI destiny +// lo: scaled low limit +// hi: scaled high limit +// val: value +// LiveUpdate: live update function when the encoder changes +// Apply: update function when the encoder is pressed +void SetValueOnClick(uint8_t process, const float lo, const float hi, uint8_t dp, const float val, void (*Apply)() /*= nullptr*/, void (*LiveUpdate)() /*= nullptr*/) { + const int32_t value = round(val * POW(10, dp)); + SetOnClick(process, lo * POW(10, dp), hi * POW(10, dp), dp, value, Apply, LiveUpdate); + DWINUI::Draw_Signed_Float(HMI_data.Text_Color, HMI_data.Selected_Color, 3, dp, VALX - dp * DWINUI::fontWidth(DWIN_FONT_MENU), MBASE(CurrentMenu->line()), val); +} + +// Generic onclick event for integer values +// lo: scaled low limit +// hi: scaled high limit +// val: value +// LiveUpdate: live update function when the encoder changes +// Apply: update function when the encoder is pressed +void SetIntOnClick(const int32_t lo, const int32_t hi, const int32_t val, void (*Apply)() /*= nullptr*/, void (*LiveUpdate)() /*= nullptr*/) { + SetValueOnClick(SetInt, lo, hi, val, Apply, LiveUpdate); +} + +// Generic onclick event for set pointer to 16 bit uinteger values +// lo: low limit +// hi: high limit +// LiveUpdate: live update function when the encoder changes +// Apply: update function when the encoder is pressed +void SetPIntOnClick(const int32_t lo, const int32_t hi, void (*Apply)() /*= nullptr*/, void (*LiveUpdate)() /*= nullptr*/) { + MenuData.P_Int = (int16_t*)static_cast(CurrentMenu->SelectedItem())->value; + const int32_t value = *MenuData.P_Int; + SetValueOnClick(SetPInt, lo, hi, value, Apply, LiveUpdate); +} + +// Generic onclick event for float values +// process: process id HMI destiny +// lo: low limit +// hi: high limit +// dp: decimal places +// val: value +void SetFloatOnClick(const float lo, const float hi, uint8_t dp, const float val, void (*Apply)() /*= nullptr*/, void (*LiveUpdate)() /*= nullptr*/) { + SetValueOnClick(SetFloat, lo, hi, dp, val, Apply, LiveUpdate); +} + +// Generic onclick event for set pointer to float values +// lo: low limit +// hi: high limit +// LiveUpdate: live update function when the encoder changes +// Apply: update function when the encoder is pressed +void SetPFloatOnClick(const float lo, const float hi, uint8_t dp, void (*Apply)() /*= nullptr*/, void (*LiveUpdate)() /*= nullptr*/) { + MenuData.P_Float = (float*)static_cast(CurrentMenu->SelectedItem())->value; + SetValueOnClick(SetPFloat, lo, hi, dp, *MenuData.P_Float, Apply, LiveUpdate); +} + +// HMI Control functions ====================================================== + +// Generic menu control using the encoder +void HMI_Menu() { + EncoderState encoder_diffState = get_encoder_state(); + if (encoder_diffState == ENCODER_DIFF_NO) return; + if (CurrentMenu) { + if (encoder_diffState == ENCODER_DIFF_ENTER) + CurrentMenu->onClick(); + else + CurrentMenu->onScroll(encoder_diffState == ENCODER_DIFF_CW); + } +} + +// Get an integer value using the encoder without draw anything +// lo: low limit +// hi: high limit +// Return value: +// 0 : no change +// 1 : live change +// 2 : apply change +int8_t HMI_GetIntNoDraw(const int32_t lo, const int32_t hi) { + EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState != ENCODER_DIFF_NO) { + if (Apply_Encoder(encoder_diffState, MenuData.Value)) { + EncoderRate.enabled = false; + checkkey = Menu; + return 2; + } + LIMIT(MenuData.Value, lo, hi); + return 1; + } + return 0; +} + +// Get an integer value using the encoder +// lo: low limit +// hi: high limit +// Return value: +// 0 : no change +// 1 : live change +// 2 : apply change +int8_t HMI_GetInt(const int32_t lo, const int32_t hi) { + EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState != ENCODER_DIFF_NO) { + if (Apply_Encoder(encoder_diffState, MenuData.Value)) { + EncoderRate.enabled = false; + DWINUI::Draw_Signed_Int(HMI_data.Text_Color, HMI_data.Background_Color, 4 , VALX, MBASE(CurrentMenu->line()) - 1, MenuData.Value); + checkkey = Menu; + return 2; + } + LIMIT(MenuData.Value, lo, hi); + DWINUI::Draw_Signed_Int(HMI_data.Text_Color, HMI_data.Selected_Color, 4 , VALX, MBASE(CurrentMenu->line()) - 1, MenuData.Value); + return 1; + } + return 0; +} + +// Set an integer using the encoder +void HMI_SetInt() { + int8_t val = HMI_GetInt(MenuData.MinValue, MenuData.MaxValue); + switch (val) { + case 0: return; break; + case 1: if (MenuData.LiveUpdate) MenuData.LiveUpdate(); break; + case 2: if (MenuData.Apply) MenuData.Apply(); break; + } +} + +// Set an integer without drawing +void HMI_SetIntNoDraw() { + int8_t val = HMI_GetIntNoDraw(MenuData.MinValue, MenuData.MaxValue); + switch (val) { + case 0: return; break; + case 1: if (MenuData.LiveUpdate) MenuData.LiveUpdate(); break; + case 2: if (MenuData.Apply) MenuData.Apply(); break; + } +} + +// Set an integer pointer variable using the encoder +void HMI_SetPInt() { + int8_t val = HMI_GetInt(MenuData.MinValue, MenuData.MaxValue); + switch (val) { + case 0: return; + case 1: if (MenuData.LiveUpdate) MenuData.LiveUpdate(); break; + case 2: *MenuData.P_Int = MenuData.Value; if (MenuData.Apply) MenuData.Apply(); break; + } +} + +// Get a scaled float value using the encoder +// dp: decimal places +// lo: scaled low limit +// hi: scaled high limit +// Return value: +// 0 : no change +// 1 : live change +// 2 : apply change +int8_t HMI_GetFloat(uint8_t dp, int32_t lo, int32_t hi) { + EncoderState encoder_diffState = Encoder_ReceiveAnalyze(); + if (encoder_diffState != ENCODER_DIFF_NO) { + if (Apply_Encoder(encoder_diffState, MenuData.Value)) { + EncoderRate.enabled = false; + DWINUI::Draw_Signed_Float(HMI_data.Text_Color, HMI_data.Background_Color, 3, dp, VALX - dp * DWINUI::fontWidth(DWIN_FONT_MENU), MBASE(CurrentMenu->line()), MenuData.Value / POW(10, dp)); + checkkey = Menu; + return 2; + } + LIMIT(MenuData.Value, lo, hi); + DWINUI::Draw_Signed_Float(HMI_data.Text_Color, HMI_data.Selected_Color, 3, dp, VALX - dp * DWINUI::fontWidth(DWIN_FONT_MENU), MBASE(CurrentMenu->line()), MenuData.Value / POW(10, dp)); + return 1; + } + return 0; +} + +// Set a scaled float using the encoder +void HMI_SetFloat() { + const int8_t val = HMI_GetFloat(MenuData.dp, MenuData.MinValue, MenuData.MaxValue); + switch (val) { + case 0: return; + case 1: if (MenuData.LiveUpdate) MenuData.LiveUpdate(); break; + case 2: if (MenuData.Apply) MenuData.Apply(); break; + } +} + +// Set a scaled float pointer variable using the encoder +void HMI_SetPFloat() { + const int8_t val = HMI_GetFloat(MenuData.dp, MenuData.MinValue, MenuData.MaxValue); + switch (val) { + case 0: return; + case 1: if (MenuData.LiveUpdate) MenuData.LiveUpdate(); break; + case 2: *MenuData.P_Float = MenuData.Value / POW(10, MenuData.dp); if (MenuData.Apply) MenuData.Apply(); break; + } +} + +#endif // DWIN_LCD_PROUI diff --git a/Marlin/src/lcd/e3v2/proui/menus.h b/Marlin/src/lcd/e3v2/proui/menus.h new file mode 100644 index 0000000000000..0147c1616b31d --- /dev/null +++ b/Marlin/src/lcd/e3v2/proui/menus.h @@ -0,0 +1,94 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2022 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 . + * + */ + +/** + * Menu functions for ProUI + * Author: Miguel A. Risco-Castillo + * Version: 1.2.1 + * Date: 2022/02/25 + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU Lesser General Public License as + * published by the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#include "dwinui.h" + +typedef struct { + int32_t MaxValue = 0; // Auxiliar max integer/scaled float value + int32_t MinValue = 0; // Auxiliar min integer/scaled float value + int8_t dp = 0; // Auxiliar decimal places + int32_t Value = 0; // Auxiliar integer / scaled float value + int16_t *P_Int = nullptr; // Auxiliar pointer to 16 bit integer variable + float *P_Float = nullptr; // Auxiliar pointer to float variable + void (*Apply)() = nullptr; // Auxiliar apply function + void (*LiveUpdate)() = nullptr; // Auxiliar live update function +} MenuData_t; + +extern MenuData_t MenuData; + +// Menuitem Drawing functions ================================================= +void Draw_Title(TitleClass* title); +void Draw_Menu(MenuClass* menu); +void Draw_Menu_Cursor(const int8_t line); +void Erase_Menu_Cursor(const int8_t line); +void Draw_Menu_Line(const uint8_t line, const uint8_t icon=0, const char * const label=nullptr, bool more=false); +void Draw_Chkb_Line(const uint8_t line, const bool checked); +void Draw_Menu_IntValue(uint16_t bcolor, const uint8_t line, uint8_t iNum, const int32_t value=0); +void onDrawMenuItem(MenuItemClass* menuitem, int8_t line); +void onDrawSubMenu(MenuItemClass* menuitem, int8_t line); +void onDrawIntMenu(MenuItemClass* menuitem, int8_t line, int32_t value); +void onDrawPIntMenu(MenuItemClass* menuitem, int8_t line); +void onDrawPInt8Menu(MenuItemClass* menuitem, int8_t line); +void onDrawPInt32Menu(MenuItemClass* menuitem, int8_t line); +void onDrawFloatMenu(MenuItemClass* menuitem, int8_t line, uint8_t dp, const float value); +void onDrawPFloatMenu(MenuItemClass* menuitem, int8_t line); +void onDrawPFloat2Menu(MenuItemClass* menuitem, int8_t line); +void onDrawChkbMenu(MenuItemClass* menuitem, int8_t line, bool checked); + +// On click functions ========================================================= +void SetOnClick(uint8_t process, const int32_t lo, const int32_t hi, uint8_t dp, const int32_t val, void (*Apply)() = nullptr, void (*LiveUpdate)() = nullptr); +void SetValueOnClick(uint8_t process, const int32_t lo, const int32_t hi, const int32_t val, void (*Apply)() = nullptr, void (*LiveUpdate)() = nullptr); +void SetValueOnClick(uint8_t process, const float lo, const float hi, uint8_t dp, const float val, void (*Apply)() = nullptr, void (*LiveUpdate)() = nullptr); +void SetIntOnClick(const int32_t lo, const int32_t hi, const int32_t val, void (*Apply)() = nullptr, void (*LiveUpdate)() = nullptr); +void SetPIntOnClick(const int32_t lo, const int32_t hi, void (*Apply)() = nullptr, void (*LiveUpdate)() = nullptr); +void SetFloatOnClick(const float lo, const float hi, uint8_t dp, const float val, void (*Apply)() = nullptr, void (*LiveUpdate)() = nullptr); +void SetPFloatOnClick(const float lo, const float hi, uint8_t dp, void (*Apply)() = nullptr, void (*LiveUpdate)() = nullptr); + +// HMI user control functions ================================================= +void HMI_Menu(); +void HMI_SetInt(); +void HMI_SetPInt(); +void HMI_SetIntNoDraw(); +void HMI_SetFloat(); +void HMI_SetPFloat(); diff --git a/Marlin/src/lcd/e3v2/proui/meshviewer.cpp b/Marlin/src/lcd/e3v2/proui/meshviewer.cpp index 0f63f77b9930a..0b22ae98d5ef8 100644 --- a/Marlin/src/lcd/e3v2/proui/meshviewer.cpp +++ b/Marlin/src/lcd/e3v2/proui/meshviewer.cpp @@ -21,17 +21,15 @@ */ /** - * DWIN Mesh Viewer + * Mesh Viewer for PRO UI * Author: Miguel A. Risco-Castillo (MRISCOC) - * Version: 3.9.1 - * Date: 2021/11/09 - * - * Based on the original code provided by Creality under GPL + * version: 3.12.1 + * Date: 2022/02/24 */ #include "../../../inc/MarlinConfigPre.h" -#if BOTH(DWIN_CREALITY_LCD_ENHANCED, HAS_MESH) +#if BOTH(DWIN_LCD_PROUI, HAS_MESH) #include "meshviewer.h" @@ -40,49 +38,53 @@ #include "dwin_lcd.h" #include "dwinui.h" #include "dwin.h" +#include "dwin_popup.h" #include "../../../feature/bedlevel/bedlevel.h" MeshViewerClass MeshViewer; -void MeshViewerClass::Draw() { +void MeshViewerClass::DrawMesh(bed_mesh_t zval, const uint8_t sizex, const uint8_t sizey) { const int8_t mx = 25, my = 25; // Margins - const int16_t stx = (DWIN_WIDTH - 2 * mx) / (GRID_MAX_POINTS_X - 1), // Steps - sty = (DWIN_WIDTH - 2 * my) / (GRID_MAX_POINTS_Y - 1); + const int16_t stx = (DWIN_WIDTH - 2 * mx) / (sizex - 1), // Steps + sty = (DWIN_WIDTH - 2 * my) / (sizey - 1); const int8_t rmax = _MIN(mx - 2, stx / 2); const int8_t rmin = 7; - int16_t zmesh[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y], maxz =-32000, minz = 32000; + int16_t zmesh[sizex][sizey]; #define px(xp) (mx + (xp) * stx) #define py(yp) (30 + DWIN_WIDTH - my - (yp) * sty) #define rm(z) ((z - minz) * (rmax - rmin) / _MAX(1, (maxz - minz)) + rmin) - #define DrawMeshValue(xp, yp, zv) DWINUI::Draw_Signed_Float(font6x12, 1, 2, px(xp) - 12, py(yp) - 6, zv) + #define DrawMeshValue(xp, yp, zv) DWINUI::Draw_Signed_Float(font6x12, 1, 2, px(xp) - 18, py(yp) - 6, zv) #define DrawMeshHLine(yp) DWIN_Draw_HLine(HMI_data.SplitLine_Color, px(0), py(yp), DWIN_WIDTH - 2 * mx) - #define DrawMeshVLine(xp) DWIN_Draw_VLine(HMI_data.SplitLine_Color, px(xp), py(GRID_MAX_POINTS_Y - 1), DWIN_WIDTH - 2 * my) - GRID_LOOP(x, y) { - const float v = isnan(Z_VALUES(x,y)) ? 0 : round(Z_VALUES(x,y) * 100); + #define DrawMeshVLine(xp) DWIN_Draw_VLine(HMI_data.SplitLine_Color, px(xp), py(sizey - 1), DWIN_WIDTH - 2 * my) + int16_t maxz =-32000; int16_t minz = 32000; avg = 0; + LOOP_L_N(y, sizey) LOOP_L_N(x, sizex) { + const float v = isnan(zval[x][y]) ? 0 : round(zval[x][y] * 100); zmesh[x][y] = v; + avg += v; NOLESS(maxz, v); NOMORE(minz, v); } - Title.ShowCaption(F("Mesh Viewer")); + max = (float)maxz / 100; + min = (float)minz / 100; + avg = avg / (100 * sizex * sizey); DWINUI::ClearMenuArea(); - DWINUI::Draw_Icon(ICON_Continue_E, 86, 305); - DWIN_Draw_Rectangle(0, HMI_data.SplitLine_Color, px(0), py(0), px(GRID_MAX_POINTS_X - 1), py(GRID_MAX_POINTS_Y - 1)); - LOOP_S_L_N(x, 1, GRID_MAX_POINTS_X - 1) DrawMeshVLine(x); - LOOP_S_L_N(y, 1, GRID_MAX_POINTS_Y - 1) DrawMeshHLine(y); - LOOP_L_N(y, GRID_MAX_POINTS_Y) { + DWIN_Draw_Rectangle(0, HMI_data.SplitLine_Color, px(0), py(0), px(sizex - 1), py(sizey - 1)); + LOOP_S_L_N(x, 1, sizex - 1) DrawMeshVLine(x); + LOOP_S_L_N(y, 1, sizey - 1) DrawMeshHLine(y); + LOOP_L_N(y, sizey) { watchdog_refresh(); - LOOP_L_N(x, GRID_MAX_POINTS_X) { + LOOP_L_N(x, sizex) { uint16_t color = DWINUI::RainbowInt(zmesh[x][y], _MIN(-5, minz), _MAX(5, maxz)); uint8_t radius = rm(zmesh[x][y]); DWINUI::Draw_FillCircle(color, px(x), py(y), radius); - if (GRID_MAX_POINTS_X < 9) - DWINUI::Draw_Signed_Float(font6x12, 1, 2, px(x) - 12, py(y) - 6, Z_VALUES(x,y)); + if (sizex < 9) + DWINUI::Draw_Signed_Float(font6x12, 1, 2, px(x) - 18, py(y) - 6, zval[x][y]); else { char str_1[9]; str_1[0] = 0; switch (zmesh[x][y]) { case -999 ... -100: - DWINUI::Draw_Signed_Float(font6x12, 1, 1, px(x) - 12, py(y) - 6, Z_VALUES(x,y)); + DWINUI::Draw_Signed_Float(font6x12, 1, 1, px(x) - 18, py(y) - 6, zval[x][y]); break; case -99 ... -1: sprintf_P(str_1, PSTR("-.%02i"), -zmesh[x][y]); @@ -94,7 +96,7 @@ void MeshViewerClass::Draw() { sprintf_P(str_1, PSTR(".%02i"), zmesh[x][y]); break; case 100 ... 999: - DWINUI::Draw_Signed_Float(font6x12, 1, 1, px(x) - 12, py(y) - 6, Z_VALUES(x,y)); + DWINUI::Draw_Signed_Float(font6x12, 1, 1, px(x) - 18, py(y) - 6, zval[x][y]); break; } if (str_1[0]) @@ -102,11 +104,25 @@ void MeshViewerClass::Draw() { } } } +} + +void MeshViewerClass::Draw(bool withsave /*= false*/) { + Title.ShowCaption(F("Mesh Viewer")); + DrawMesh(Z_VALUES_ARR, GRID_MAX_POINTS_X, GRID_MAX_POINTS_Y); + if (withsave) { + DWINUI::Draw_Button(BTN_Save, 26, 305); + DWINUI::Draw_Button(BTN_Continue, 146, 305); + Draw_Select_Highlight(HMI_flag.select_flag, 305); + } else DWINUI::Draw_Button(BTN_Continue, 86, 305); char str_1[6], str_2[6] = ""; ui.status_printf(0, F("Mesh minZ: %s, maxZ: %s"), - dtostrf((float)minz / 100, 1, 2, str_1), - dtostrf((float)maxz / 100, 1, 2, str_2) + dtostrf(min, 1, 2, str_1), + dtostrf(max, 1, 2, str_2) ); } -#endif // DWIN_CREALITY_LCD_ENHANCED && HAS_MESH +void Draw_MeshViewer() { MeshViewer.Draw(true); } +void onClick_MeshViewer() { if (HMI_flag.select_flag) WriteEeprom(); HMI_ReturnScreen(); } +void Goto_MeshViewer() { if (leveling_is_valid()) Goto_Popup(Draw_MeshViewer, onClick_MeshViewer); else HMI_ReturnScreen(); } + +#endif // DWIN_LCD_PROUI && HAS_MESH diff --git a/Marlin/src/lcd/e3v2/proui/meshviewer.h b/Marlin/src/lcd/e3v2/proui/meshviewer.h index acd5f0d5c4653..f914bab4ae23a 100644 --- a/Marlin/src/lcd/e3v2/proui/meshviewer.h +++ b/Marlin/src/lcd/e3v2/proui/meshviewer.h @@ -21,18 +21,23 @@ */ #pragma once +#include "../../../core/types.h" +#include "../../../feature/bedlevel/bedlevel.h" + /** - * DWIN Mesh Viewer + * Mesh Viewer for PRO UI * Author: Miguel A. Risco-Castillo (MRISCOC) - * Version: 3.9.1 - * Date: 2021/11/09 - * - * Based on the original code provided by Creality under GPL + * version: 3.12.1 + * Date: 2022/02/24 */ class MeshViewerClass { public: - void Draw(); + float avg, max, min; + void Draw(bool withsave = false); + void DrawMesh(bed_mesh_t zval, const uint8_t sizex, const uint8_t sizey); }; extern MeshViewerClass MeshViewer; + +void Goto_MeshViewer(); diff --git a/Marlin/src/lcd/e3v2/proui/printstats.cpp b/Marlin/src/lcd/e3v2/proui/printstats.cpp index ec14ebb8bf6eb..d4ca4ca2255fb 100644 --- a/Marlin/src/lcd/e3v2/proui/printstats.cpp +++ b/Marlin/src/lcd/e3v2/proui/printstats.cpp @@ -21,21 +21,20 @@ */ /** - * DWIN Print Stats page + * Print Stats page for PRO UI * Author: Miguel A. Risco-Castillo (MRISCOC) - * Version: 1.1 - * Date: 2022/01/09 - * - * Based on the original code provided by Creality under GPL + * Version: 1.3.0 + * Date: 2022/02/24 */ #include "../../../inc/MarlinConfigPre.h" -#if BOTH(DWIN_CREALITY_LCD_ENHANCED, PRINTCOUNTER) +#if BOTH(DWIN_LCD_PROUI, PRINTCOUNTER) #include "printstats.h" #include "../../../core/types.h" +#include "../../../MarlinCore.h" #include "../../marlinui.h" #include "../../../module/printcounter.h" #include "dwin_lcd.h" @@ -53,7 +52,7 @@ void PrintStatsClass::Draw() { Title.ShowCaption(GET_TEXT_F(MSG_INFO_STATS_MENU)); DWINUI::ClearMenuArea(); Draw_Popup_Bkgd(); - DWINUI::Draw_Icon(ICON_Continue_E, 86, 250); + DWINUI::Draw_Button(BTN_Continue, 86, 250); printStatistics ps = print_job_timer.getStats(); sprintf_P(buf, PSTR(S_FMT ": %i"), GET_TEXT(MSG_INFO_PRINT_COUNT), ps.totalPrints); @@ -75,4 +74,9 @@ void PrintStatsClass::Reset() { HMI_AudioFeedback(); } -#endif // DWIN_CREALITY_LCD_ENHANCED && PRINTCOUNTER +void Goto_PrintStats() { + PrintStats.Draw(); + HMI_SaveProcessID(WaitResponse); +} + +#endif // DWIN_LCD_PROUI && PRINTCOUNTER diff --git a/Marlin/src/lcd/e3v2/proui/printstats.h b/Marlin/src/lcd/e3v2/proui/printstats.h index f17e4dc9dd60f..705c923da41bf 100644 --- a/Marlin/src/lcd/e3v2/proui/printstats.h +++ b/Marlin/src/lcd/e3v2/proui/printstats.h @@ -22,18 +22,18 @@ #pragma once /** - * DWIN Print Stats page + * Print Stats page for PRO UI * Author: Miguel A. Risco-Castillo (MRISCOC) - * Version: 1.1 - * Date: 2022/01/09 - * - * Based on the original code provided by Creality under GPL + * Version: 1.3.0 + * Date: 2022/02/24 */ class PrintStatsClass { public: - void Draw(); + static void Draw(); static void Reset(); }; extern PrintStatsClass PrintStats; + +void Goto_PrintStats(); diff --git a/Marlin/src/lcd/extui/anycubic_chiron/FileNavigator.cpp b/Marlin/src/lcd/extui/anycubic_chiron/FileNavigator.cpp index f49b17acc1906..0ef8186668371 100644 --- a/Marlin/src/lcd/extui/anycubic_chiron/FileNavigator.cpp +++ b/Marlin/src/lcd/extui/anycubic_chiron/FileNavigator.cpp @@ -155,7 +155,7 @@ void FileNavigator::skiptofileindex(uint16_t skip) { if (currentindex == 0 && currentfolderdepth > 0) { // Add a link to go up a folder // The new panel ignores entries that don't end in .GCO or .gcode so add and pad them. - if (paneltype == AC_panel_new) { + if (paneltype <= AC_panel_new) { TFTSer.println("<<.GCO"); Chiron.SendtoTFTLN(F(".. .gcode")); } @@ -177,7 +177,7 @@ void FileNavigator::skiptofileindex(uint16_t skip) { void FileNavigator::sendFile(panel_type_t paneltype) { if (filelist.isDir()) { // Add mandatory tags for new panel otherwise lines are ignored. - if (paneltype == AC_panel_new) { + if (paneltype <= AC_panel_new) { TFTSer.print(filelist.shortFilename()); TFTSer.println(".GCO"); TFTSer.print(filelist.shortFilename()); diff --git a/Marlin/src/lcd/extui/anycubic_chiron/chiron_extui.cpp b/Marlin/src/lcd/extui/anycubic_chiron/chiron_extui.cpp index 7a58963c11feb..b9fe8f967c0d9 100644 --- a/Marlin/src/lcd/extui/anycubic_chiron/chiron_extui.cpp +++ b/Marlin/src/lcd/extui/anycubic_chiron/chiron_extui.cpp @@ -57,14 +57,16 @@ namespace ExtUI { void onPrintTimerStarted() { Chiron.TimerEvent(AC_timer_started); } void onPrintTimerPaused() { Chiron.TimerEvent(AC_timer_paused); } - void onPrintTimerStopped() { Chiron.TimerEvent(AC_timer_stopped); } + void onPrintTimerStopped() { Chiron.TimerEvent(AC_timer_stopped); } + void onPrintDone() {} + 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 onHomingStart() {} - void onHomingComplete() {} - void onPrintFinished() {} + void onHomingDone() {} void onFactoryReset() {} @@ -103,7 +105,8 @@ namespace ExtUI { } #if HAS_MESH - void onMeshLevelingStart() {} + void onLevelingStart() {} + void onLevelingDone() {} void onMeshUpdate(const int8_t xpos, const int8_t ypos, const_float_t zval) { // Called when any mesh points are updated diff --git a/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp index c56d8aa7fbb31..fa85de2a8e840 100644 --- a/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp +++ b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp @@ -86,13 +86,23 @@ void ChironTFT::Startup() { TFTSer.begin(115200); // wait for the TFT panel to initialise and finish the animation - delay_ms(250); + safe_delay(1000); // There are different panels for the Chiron with slightly different commands // So we need to know what we are working with. - // Panel type can be defined otherwise detect it automatically - if (panel_type == AC_panel_unknown) DetectPanelType(); + switch (panel_type) { + case AC_panel_new: + SERIAL_ECHOLNF(AC_msg_new_panel_set); + break; + case AC_panel_standard: + SERIAL_ECHOLNF(AC_msg_old_panel_set); + break; + default: + SERIAL_ECHOLNF(AC_msg_auto_panel_detection); + DetectPanelType(); + break; + } // Signal Board has reset SendtoTFTLN(AC_msg_main_board_has_reset); @@ -358,15 +368,14 @@ bool ChironTFT::ReadTFTCommand() { } int8_t ChironTFT::FindToken(char c) { - int8_t pos = 0; - do { + for (int8_t pos = 0; pos < command_len; pos++) { if (panel_command[pos] == c) { #if ACDEBUG(AC_INFO) SERIAL_ECHOLNPGM("Tpos:", pos, " ", c); #endif return pos; } - } while (++pos < command_len); + } #if ACDEBUG(AC_INFO) SERIAL_ECHOLNPGM("Not found: ", c); #endif @@ -433,7 +442,7 @@ void ChironTFT::SendFileList(int8_t startindex) { } void ChironTFT::SelectFile() { - if (panel_type == AC_panel_new) { + if (panel_type <= AC_panel_new) { strncpy(selectedfile, panel_command + 4, command_len - 3); selectedfile[command_len - 4] = '\0'; } @@ -456,7 +465,7 @@ void ChironTFT::SelectFile() { break; default: // enter sub folder // for new panel remove the '.GCO' tag that was added to the end of the path - if (panel_type == AC_panel_new) + if (panel_type <= AC_panel_new) selectedfile[strlen(selectedfile) - 4] = '\0'; filenavigator.changeDIR(selectedfile); SendtoTFTLN(AC_msg_sd_file_open_failed); @@ -469,8 +478,8 @@ void ChironTFT::ProcessPanelRequest() { // Break these up into logical blocks // as its easier to navigate than one huge switch case! int8_t tpos = FindToken('A'); // Panel request are 'A0' - 'A36' - if (tpos != -1) { - const int8_t req = atoi(&panel_command[tpos+1]); + if (tpos >= 0) { + const int8_t req = atoi(&panel_command[tpos + 1]); // Information requests A0 - A8 and A33 if (req <= 8 || req == 33) PanelInfo(req); @@ -486,16 +495,18 @@ void ChironTFT::ProcessPanelRequest() { // This may be a response to a panel type detection query if (panel_type == AC_panel_unknown) { tpos = FindToken('S'); // old panel will respond to 'SIZE' with 'SXY 480 320' - if (tpos != -1) { - if (panel_command[tpos+1]== 'X' && panel_command[tpos+2]=='Y') { + if (tpos >= 0) { + if (panel_command[tpos + 1] == 'X' && panel_command[tpos + 2] =='Y') { panel_type = AC_panel_standard; SERIAL_ECHOLNF(AC_msg_old_panel_detected); } } else { - tpos = FindToken('['); // new panel will respond to 'J200' with '[0]=0' - if (tpos != -1) { - if (panel_command[tpos+1]== '0' && panel_command[tpos+2]==']') { + // new panel will respond to 'J200' with '[0]=0' + // it seems only after a power cycle so detection assumes a new panel + tpos = FindToken('['); + if (tpos >= 0) { + if (panel_command[tpos + 1] == '0' && panel_command[tpos + 2] ==']') { panel_type = AC_panel_new; SERIAL_ECHOLNF(AC_msg_new_panel_detected); } @@ -623,18 +634,18 @@ void ChironTFT::PanelAction(uint8_t req) { SelectFile(); break; - case 14: { // A14 Start Printing + case 14: // A14 Start Printing // Allows printer to restart the job if we don't want to recover if (printer_state == AC_printer_resuming_from_power_outage) { injectCommands(F("M1000 C")); // Cancel recovery printer_state = AC_printer_idle; } #if ACDebugLevel >= 1 - SERIAL_ECHOLNPAIR_F("Print: ", selectedfile); + SERIAL_ECHOLNPGM("Print: ", selectedfile); #endif printFile(selectedfile); SendtoTFTLN(AC_msg_print_from_sd_card); - } break; + break; case 15: // A15 Resuming from outage if (printer_state == AC_printer_resuming_from_power_outage) { @@ -801,28 +812,25 @@ void ChironTFT::PanelProcess(uint8_t req) { } } break; - case 30: { // A30 Auto leveling - if (FindToken('S') != -1) { // Start probing New panel adds spaces.. + case 30: // A30 Auto leveling + if (FindToken('S') >= 0) { // Start probing New panel adds spaces.. // Ignore request if printing if (isPrinting()) SendtoTFTLN(AC_msg_probing_not_allowed); // forbid auto leveling else { - - SendtoTFTLN(AC_msg_start_probing); injectCommands(F("G28\nG29")); printer_state = AC_printer_probing; } } - else { + else SendtoTFTLN(AC_msg_start_probing); // Just enter levelling menu - } - } break; + break; - case 31: { // A31 Adjust all Probe Points + case 31: // A31 Adjust all Probe Points // The tokens can occur in different places on the new panel so we need to find it. - if (FindToken('C') != -1) { // Restore and apply original offsets + if (FindToken('C') >= 0) { // Restore and apply original offsets if (!isPrinting()) { injectCommands(F("M501\nM420 S1")); selectedmeshpoint.x = selectedmeshpoint.y = 99; @@ -830,7 +838,7 @@ void ChironTFT::PanelProcess(uint8_t req) { } } - else if (FindToken('D') != -1) { // Save Z Offset tables and restore leveling state + else if (FindToken('D') >= 0) { // Save Z Offset tables and restore leveling state if (!isPrinting()) { setAxisPosition_mm(1.0,Z); // Lift nozzle before any further movements are made injectCommands(F("M500")); @@ -839,7 +847,7 @@ void ChironTFT::PanelProcess(uint8_t req) { } } - else if (FindToken('G') != -1) { // Get current offset + else if (FindToken('G') >= 0) { // Get current offset SendtoTFT(F("A31V ")); // When printing use the live z Offset position // we will use babystepping to move the print head @@ -853,7 +861,7 @@ void ChironTFT::PanelProcess(uint8_t req) { else { int8_t tokenpos = FindToken('S'); - if (tokenpos != -1) { // Set offset (adjusts all points by value) + if (tokenpos >= 0) { // Set offset (adjusts all points by value) float Zshift = atof(&panel_command[tokenpos+1]); setSoftEndstopState(false); // disable endstops // Allow temporary Z position nudging during print @@ -907,18 +915,18 @@ void ChironTFT::PanelProcess(uint8_t req) { } } } - } break; + break; - case 32: { // A32 clean leveling beep flag + case 32: // A32 clean leveling beep flag // Ignore request if printing //if (isPrinting()) break; //injectCommands(F("M500\nM420 S1\nG1 Z10 F240\nG1 X0 Y0 F6000")); //TFTSer.println(); - } break; + break; // A33 firmware info request see PanelInfo() - case 34: { // A34 Adjust single mesh point A34 C/S X1 Y1 V123 + case 34: // A34 Adjust single mesh point A34 C/S X1 Y1 V123 if (panel_command[3] == 'C') { // Restore original offsets injectCommands(F("M501\nM420 S1")); selectedmeshpoint.x = selectedmeshpoint.y = 99; @@ -950,7 +958,7 @@ void ChironTFT::PanelProcess(uint8_t req) { } } } - } break; + break; case 36: // A36 Auto leveling for new TFT bet that was a typo in the panel code! SendtoTFTLN(AC_msg_start_probing); diff --git a/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft_defs.h b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft_defs.h index 0fd7770cddfb8..e3609b5408dfe 100644 --- a/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft_defs.h +++ b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft_defs.h @@ -89,6 +89,10 @@ #define AC_msg_mesh_changes_saved F("Mesh changes saved.") #define AC_msg_old_panel_detected F("Standard TFT panel detected!") #define AC_msg_new_panel_detected F("New TFT panel detected!") +#define AC_msg_auto_panel_detection F("Auto detect panel type (assuming new panel)") +#define AC_msg_old_panel_set F("Set for standard TFT panel.") +#define AC_msg_new_panel_set F("Set for new TFT panel.") + #define AC_msg_powerloss_recovery F("Resuming from power outage! select the same SD file then press resume") // Error messages must not contain spaces #define AC_msg_error_bed_temp F("Abnormal_bed_temp") @@ -161,10 +165,10 @@ namespace Anycubic { AC_menu_change_to_file, AC_menu_change_to_command }; - enum panel_type_t : uint8_t { + enum panel_type_t : uint8_t { // order is important here as we assume new panel if type is unknown AC_panel_unknown, - AC_panel_standard, - AC_panel_new + AC_panel_new, + AC_panel_standard }; enum last_error_t : uint8_t { AC_error_none, diff --git a/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_extui.cpp b/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_extui.cpp index c0e1b4457897b..da8f4e26a0ff0 100644 --- a/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_extui.cpp +++ b/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_extui.cpp @@ -54,8 +54,8 @@ namespace ExtUI { void onStatusChanged(const char * const msg) {} void onHomingStart() {} - void onHomingComplete() {} - void onPrintFinished() {} + void onHomingDone() {} + void onPrintDone() {} void onFactoryReset() {} @@ -95,7 +95,8 @@ namespace ExtUI { #if HAS_MESH - void onMeshLevelingStart() {} + void onLevelingStart() {} + void onLevelingDone() {} void onMeshUpdate(const int8_t xpos, const int8_t ypos, const_float_t zval) { // Called when any mesh points are updated diff --git a/Marlin/src/lcd/extui/dgus/DGUSDisplay.cpp b/Marlin/src/lcd/extui/dgus/DGUSDisplay.cpp index 262dcea364833..e2f11502e7d83 100644 --- a/Marlin/src/lcd/extui/dgus/DGUSDisplay.cpp +++ b/Marlin/src/lcd/extui/dgus/DGUSDisplay.cpp @@ -46,6 +46,12 @@ DGUSDisplay dgusdisplay; +#ifdef DEBUG_DGUSLCD_COMM + #define DEBUGLCDCOMM_ECHOPGM DEBUG_ECHOPGM +#else + #define DEBUGLCDCOMM_ECHOPGM(...) NOOP +#endif + // Preamble... 2 Bytes, usually 0x5A 0xA5, but configurable constexpr uint8_t DGUS_HEADER1 = 0x5A; constexpr uint8_t DGUS_HEADER2 = 0xA5; @@ -154,19 +160,19 @@ void DGUSDisplay::ProcessRx() { case DGUS_IDLE: // Waiting for the first header byte receivedbyte = LCD_SERIAL.read(); - //DEBUG_ECHOPGM("< ",x); + //DEBUGLCDCOMM_ECHOPGM("< ", receivedbyte); if (DGUS_HEADER1 == receivedbyte) rx_datagram_state = DGUS_HEADER1_SEEN; break; case DGUS_HEADER1_SEEN: // Waiting for the second header byte receivedbyte = LCD_SERIAL.read(); - //DEBUG_ECHOPGM(" ",x); + //DEBUGLCDCOMM_ECHOPGM(" ", receivedbyte); rx_datagram_state = (DGUS_HEADER2 == receivedbyte) ? DGUS_HEADER2_SEEN : DGUS_IDLE; break; case DGUS_HEADER2_SEEN: // Waiting for the length byte rx_datagram_len = LCD_SERIAL.read(); - DEBUG_ECHOPGM(" (", rx_datagram_len, ") "); + //DEBUGLCDCOMM_ECHOPGM(" (", rx_datagram_len, ") "); // Telegram min len is 3 (command and one word of payload) rx_datagram_state = WITHIN(rx_datagram_len, 3, DGUS_RX_BUFFER_SIZE) ? DGUS_WAIT_TELEGRAM : DGUS_IDLE; @@ -178,20 +184,20 @@ void DGUSDisplay::ProcessRx() { Initialized = true; // We've talked to it, so we defined it as initialized. uint8_t command = LCD_SERIAL.read(); - DEBUG_ECHOPGM("# ", command); + //DEBUGLCDCOMM_ECHOPGM("# ", command); uint8_t readlen = rx_datagram_len - 1; // command is part of len. unsigned char tmp[rx_datagram_len - 1]; unsigned char *ptmp = tmp; while (readlen--) { receivedbyte = LCD_SERIAL.read(); - DEBUG_ECHOPGM(" ", receivedbyte); + //DEBUGLCDCOMM_ECHOPGM(" ", receivedbyte); *ptmp++ = receivedbyte; } - DEBUG_ECHOPGM(" # "); + //DEBUGLCDCOMM_ECHOPGM(" # "); // mostly we'll get this: 5A A5 03 82 4F 4B -- ACK on 0x82, so discard it. if (command == DGUS_CMD_WRITEVAR && 'O' == tmp[0] && 'K' == tmp[1]) { - DEBUG_ECHOLNPGM(">"); + //DEBUGLCDCOMM_ECHOPGM(">"); rx_datagram_state = DGUS_IDLE; break; } @@ -253,16 +259,16 @@ void DGUSDisplay::loop() { rx_datagram_state_t DGUSDisplay::rx_datagram_state = DGUS_IDLE; uint8_t DGUSDisplay::rx_datagram_len = 0; -bool DGUSDisplay::Initialized = false; -bool DGUSDisplay::no_reentrance = false; +bool DGUSDisplay::Initialized = false, + DGUSDisplay::no_reentrance = false; // A SW memory barrier, to ensure GCC does not overoptimize loops #define sw_barrier() asm volatile("": : :"memory"); bool populate_VPVar(const uint16_t VP, DGUS_VP_Variable * const ramcopy) { - // DEBUG_ECHOPGM("populate_VPVar ", VP); + //DEBUG_ECHOPGM("populate_VPVar ", VP); const DGUS_VP_Variable *pvp = DGUSLCD_FindVPVar(VP); - // DEBUG_ECHOLNPGM(" pvp ", (uint16_t )pvp); + //DEBUG_ECHOLNPGM(" pvp ", (uint16_t )pvp); if (!pvp) return false; memcpy_P(ramcopy, pvp, sizeof(DGUS_VP_Variable)); return true; diff --git a/Marlin/src/lcd/extui/dgus/DGUSDisplay.h b/Marlin/src/lcd/extui/dgus/DGUSDisplay.h index 3040225d071aa..17303c689bb99 100644 --- a/Marlin/src/lcd/extui/dgus/DGUSDisplay.h +++ b/Marlin/src/lcd/extui/dgus/DGUSDisplay.h @@ -29,6 +29,9 @@ #include // size_t +//#define DEBUG_DGUSLCD +//#define DEBUG_DGUSLCD_COMM + #if HAS_BED_PROBE #include "../../../module/probe.h" #endif diff --git a/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp index 70bcca1859601..9b25f8aeb13f1 100644 --- a/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp @@ -55,14 +55,14 @@ void (*DGUSScreenHandler::confirm_action_cb)() = nullptr; #if ENABLED(SDSUPPORT) int16_t DGUSScreenHandler::top_file = 0, DGUSScreenHandler::file_to_print = 0; - static ExtUI::FileList filelist; + ExtUI::FileList filelist; #endif #if ENABLED(DGUS_FILAMENT_LOADUNLOAD) filament_data_t filament_data; #endif -void DGUSScreenHandler::sendinfoscreen(const char *line1, const char *line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool l4inflash) { +void DGUSScreenHandler::sendinfoscreen(PGM_P const line1, PGM_P const line2, PGM_P const line3, PGM_P const line4, bool l1inflash, bool l2inflash, bool l3inflash, bool l4inflash) { DGUS_VP_Variable ramcopy; if (populate_VPVar(VP_MSGSTR1, &ramcopy)) { ramcopy.memadr = (void*) line1; @@ -76,13 +76,15 @@ void DGUSScreenHandler::sendinfoscreen(const char *line1, const char *line2, con ramcopy.memadr = (void*) line3; l3inflash ? DGUSScreenHandler::DGUSLCD_SendStringToDisplayPGM(ramcopy) : DGUSScreenHandler::DGUSLCD_SendStringToDisplay(ramcopy); } - if (populate_VPVar(VP_MSGSTR4, &ramcopy)) { - ramcopy.memadr = (void*) line4; - l4inflash ? DGUSScreenHandler::DGUSLCD_SendStringToDisplayPGM(ramcopy) : DGUSScreenHandler::DGUSLCD_SendStringToDisplay(ramcopy); - } + #ifdef VP_MSGSTR4 + if (populate_VPVar(VP_MSGSTR4, &ramcopy)) { + ramcopy.memadr = (void*) line4; + l4inflash ? DGUSScreenHandler::DGUSLCD_SendStringToDisplayPGM(ramcopy) : DGUSScreenHandler::DGUSLCD_SendStringToDisplay(ramcopy); + } + #endif } -void DGUSScreenHandler::HandleUserConfirmationPopUp(uint16_t VP, const char *line1, const char *line2, const char *line3, const char *line4, bool l1, bool l2, bool l3, bool l4) { +void DGUSScreenHandler::HandleUserConfirmationPopUp(uint16_t VP, PGM_P const line1, PGM_P const line2, PGM_P const line3, PGM_P const line4, bool l1, bool l2, bool l3, bool l4) { if (current_screen == DGUSLCD_SCREEN_CONFIRM) // Already showing a pop up, so we need to cancel that first. PopToOldScreen(); @@ -344,6 +346,7 @@ void DGUSScreenHandler::DGUSLCD_SendHeaterStatusToDisplay(DGUS_VP_Variable &var) SetupConfirmAction(nullptr); GotoScreen(DGUSLCD_SCREEN_POPUP); } + #endif // SDSUPPORT void DGUSScreenHandler::ScreenConfirmedOK(DGUS_VP_Variable &var, void *val_ptr) { diff --git a/Marlin/src/lcd/extui/dgus/dgus_extui.cpp b/Marlin/src/lcd/extui/dgus/dgus_extui.cpp index 04ba6b95c2c75..0041be82769f9 100644 --- a/Marlin/src/lcd/extui/dgus/dgus_extui.cpp +++ b/Marlin/src/lcd/extui/dgus/dgus_extui.cpp @@ -73,8 +73,8 @@ namespace ExtUI { void onStatusChanged(const char * const msg) { ScreenHandler.setstatusmessage(msg); } void onHomingStart() {} - void onHomingComplete() {} - void onPrintFinished() {} + void onHomingDone() {} + void onPrintDone() {} void onFactoryReset() {} @@ -113,7 +113,8 @@ namespace ExtUI { } #if HAS_MESH - void onMeshLevelingStart() {} + void onLevelingStart() {} + void onLevelingDone() {} void onMeshUpdate(const int8_t xpos, const int8_t ypos, const_float_t zval) { // Called when any mesh points are updated diff --git a/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp index eba4b153f135c..e7466bfe087f0 100644 --- a/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp @@ -42,7 +42,7 @@ #if ENABLED(SDSUPPORT) - static ExtUI::FileList filelist; + extern ExtUI::FileList filelist; void DGUSScreenHandler::DGUSLCD_SD_FileSelected(DGUS_VP_Variable &var, void *val_ptr) { uint16_t touched_nr = (int16_t)swap16(*(uint16_t*)val_ptr) + top_file; diff --git a/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.h index d4fdf1d27e2ad..0bdf06ed7d57f 100644 --- a/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.h +++ b/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.h @@ -37,15 +37,15 @@ class DGUSScreenHandler { // Send all 4 strings that are displayed on the infoscreen, confirmation screen and kill screen // The bools specifying whether the strings are in RAM or FLASH. - static void sendinfoscreen(const char *line1, const char *line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); - static void sendinfoscreen(FSTR_P const line1, FSTR_P const line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash) { + static void sendinfoscreen(PGM_P const line1, PGM_P const line2, PGM_P const line3, PGM_P const line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); + static void sendinfoscreen(FSTR_P const line1, FSTR_P const line2, PGM_P const line3, PGM_P const line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash) { sendinfoscreen(FTOP(line1), FTOP(line2), line3, line4, l1inflash, l2inflash, l3inflash, liinflash); } static void sendinfoscreen(FSTR_P const line1, FSTR_P const line2, FSTR_P const line3, FSTR_P const line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash) { sendinfoscreen(FTOP(line1), FTOP(line2), FTOP(line3), FTOP(line4), l1inflash, l2inflash, l3inflash, liinflash); } - static void HandleUserConfirmationPopUp(uint16_t ConfirmVP, const char *line1, const char *line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); + static void HandleUserConfirmationPopUp(uint16_t ConfirmVP, PGM_P const line1, PGM_P const line2, PGM_P const line3, PGM_P const line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); // "M117" Message -- msg is a RAM ptr. static void setstatusmessage(const char *msg); diff --git a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp index 88b3255b66e2b..d64ac143b0312 100644 --- a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp @@ -42,7 +42,7 @@ #if ENABLED(SDSUPPORT) - static ExtUI::FileList filelist; + extern ExtUI::FileList filelist; void DGUSScreenHandler::DGUSLCD_SD_FileSelected(DGUS_VP_Variable &var, void *val_ptr) { uint16_t touched_nr = (int16_t)swap16(*(uint16_t*)val_ptr) + top_file; diff --git a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.h index d4fdf1d27e2ad..0bdf06ed7d57f 100644 --- a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.h +++ b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.h @@ -37,15 +37,15 @@ class DGUSScreenHandler { // Send all 4 strings that are displayed on the infoscreen, confirmation screen and kill screen // The bools specifying whether the strings are in RAM or FLASH. - static void sendinfoscreen(const char *line1, const char *line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); - static void sendinfoscreen(FSTR_P const line1, FSTR_P const line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash) { + static void sendinfoscreen(PGM_P const line1, PGM_P const line2, PGM_P const line3, PGM_P const line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); + static void sendinfoscreen(FSTR_P const line1, FSTR_P const line2, PGM_P const line3, PGM_P const line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash) { sendinfoscreen(FTOP(line1), FTOP(line2), line3, line4, l1inflash, l2inflash, l3inflash, liinflash); } static void sendinfoscreen(FSTR_P const line1, FSTR_P const line2, FSTR_P const line3, FSTR_P const line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash) { sendinfoscreen(FTOP(line1), FTOP(line2), FTOP(line3), FTOP(line4), l1inflash, l2inflash, l3inflash, liinflash); } - static void HandleUserConfirmationPopUp(uint16_t ConfirmVP, const char *line1, const char *line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); + static void HandleUserConfirmationPopUp(uint16_t ConfirmVP, PGM_P const line1, PGM_P const line2, PGM_P const line3, PGM_P const line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); // "M117" Message -- msg is a RAM ptr. static void setstatusmessage(const char *msg); diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp index 88f26ab42d88c..bfa070df87362 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp @@ -48,7 +48,7 @@ #endif #if ENABLED(SDSUPPORT) - static ExtUI::FileList filelist; + extern ExtUI::FileList filelist; #endif bool DGUSAutoTurnOff = false; @@ -65,7 +65,7 @@ void DGUSScreenHandler::sendinfoscreen_ch_mks(const uint16_t *line1, const uint1 dgusdisplay.WriteVariable(VP_MSGSTR4, line4, 32, true); } -void DGUSScreenHandler::sendinfoscreen_en_mks(const char *line1, const char *line2, const char *line3, const char *line4) { +void DGUSScreenHandler::sendinfoscreen_en_mks(PGM_P const line1, PGM_P const line2, PGM_P const line3, PGM_P const line4) { dgusdisplay.WriteVariable(VP_MSGSTR1, line1, 32, true); dgusdisplay.WriteVariable(VP_MSGSTR2, line2, 32, true); dgusdisplay.WriteVariable(VP_MSGSTR3, line3, 32, true); diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h index 05a4b47b17b0f..dbd124cbe9d9b 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h @@ -37,19 +37,19 @@ class DGUSScreenHandler { // Send all 4 strings that are displayed on the infoscreen, confirmation screen and kill screen // The bools specifying whether the strings are in RAM or FLASH. - static void sendinfoscreen(const char *line1, const char *line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); - static void sendinfoscreen(FSTR_P const line1, FSTR_P const line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash) { + static void sendinfoscreen(PGM_P const line1, PGM_P const line2, PGM_P const line3, PGM_P const line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); + static void sendinfoscreen(FSTR_P const line1, FSTR_P const line2, PGM_P const line3, PGM_P const line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash) { sendinfoscreen(FTOP(line1), FTOP(line2), line3, line4, l1inflash, l2inflash, l3inflash, liinflash); } static void sendinfoscreen(FSTR_P const line1, FSTR_P const line2, FSTR_P const line3, FSTR_P const line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash) { sendinfoscreen(FTOP(line1), FTOP(line2), FTOP(line3), FTOP(line4), l1inflash, l2inflash, l3inflash, liinflash); } - static void HandleUserConfirmationPopUp(uint16_t ConfirmVP, const char *line1, const char *line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); + static void HandleUserConfirmationPopUp(uint16_t ConfirmVP, PGM_P const line1, PGM_P const line2, PGM_P const line3, PGM_P const line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); #if 0 static void sendinfoscreen_ch_mks(const uint16_t *line1, const uint16_t *line2, const uint16_t *line3, const uint16_t *line4); - static void sendinfoscreen_en_mks(const char *line1, const char *line2, const char *line3, const char *line4) ; + static void sendinfoscreen_en_mks(PGM_P const line1, PGM_P const line2, PGM_P const line3, PGM_P const line4); static void sendinfoscreen_mks(const void *line1, const void *line2, const void *line3, const void *line4, uint16_t language); #endif diff --git a/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp index fb08fbf849192..aaa8b72e11822 100644 --- a/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp @@ -42,7 +42,7 @@ #if ENABLED(SDSUPPORT) - static ExtUI::FileList filelist; + extern ExtUI::FileList filelist; void DGUSScreenHandler::DGUSLCD_SD_FileSelected(DGUS_VP_Variable &var, void *val_ptr) { uint16_t touched_nr = (int16_t)swap16(*(uint16_t*)val_ptr) + top_file; diff --git a/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.h index d4fdf1d27e2ad..0bdf06ed7d57f 100644 --- a/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.h +++ b/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.h @@ -37,15 +37,15 @@ class DGUSScreenHandler { // Send all 4 strings that are displayed on the infoscreen, confirmation screen and kill screen // The bools specifying whether the strings are in RAM or FLASH. - static void sendinfoscreen(const char *line1, const char *line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); - static void sendinfoscreen(FSTR_P const line1, FSTR_P const line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash) { + static void sendinfoscreen(PGM_P const line1, PGM_P const line2, PGM_P const line3, PGM_P const line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); + static void sendinfoscreen(FSTR_P const line1, FSTR_P const line2, PGM_P const line3, PGM_P const line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash) { sendinfoscreen(FTOP(line1), FTOP(line2), line3, line4, l1inflash, l2inflash, l3inflash, liinflash); } static void sendinfoscreen(FSTR_P const line1, FSTR_P const line2, FSTR_P const line3, FSTR_P const line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash) { sendinfoscreen(FTOP(line1), FTOP(line2), FTOP(line3), FTOP(line4), l1inflash, l2inflash, l3inflash, liinflash); } - static void HandleUserConfirmationPopUp(uint16_t ConfirmVP, const char *line1, const char *line2, const char *line3, const char *line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); + static void HandleUserConfirmationPopUp(uint16_t ConfirmVP, PGM_P const line1, PGM_P const line2, PGM_P const line3, PGM_P const line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); // "M117" Message -- msg is a RAM ptr. static void setstatusmessage(const char *msg); diff --git a/Marlin/src/lcd/extui/dgus_reloaded/dgus_reloaded_extui.cpp b/Marlin/src/lcd/extui/dgus_reloaded/dgus_reloaded_extui.cpp index 61b072a3f783e..5c330bd6b4725 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/dgus_reloaded_extui.cpp +++ b/Marlin/src/lcd/extui/dgus_reloaded/dgus_reloaded_extui.cpp @@ -83,8 +83,8 @@ namespace ExtUI { } void onHomingStart() {} - void onHomingComplete() {} - void onPrintFinished() {} + void onHomingDone() {} + void onPrintDone() {} void onFactoryReset() { dgus_screen_handler.SettingsReset(); @@ -109,7 +109,8 @@ namespace ExtUI { } #if HAS_MESH - void onMeshLevelingStart() {} + void onLevelingStart() {} + void onLevelingDone() {} void onMeshUpdate(const int8_t xpos, const int8_t ypos, const_float_t zval) { dgus_screen_handler.MeshUpdate(xpos, ypos); diff --git a/Marlin/src/lcd/extui/example/example.cpp b/Marlin/src/lcd/extui/example/example.cpp index 8f38d2aba6d8c..dd0f8e401e91a 100644 --- a/Marlin/src/lcd/extui/example/example.cpp +++ b/Marlin/src/lcd/extui/example/example.cpp @@ -59,8 +59,8 @@ namespace ExtUI { void onStatusChanged(const char * const msg) {} void onHomingStart() {} - void onHomingComplete() {} - void onPrintFinished() {} + void onHomingDone() {} + void onPrintDone() {} void onFactoryReset() {} @@ -99,7 +99,8 @@ namespace ExtUI { } #if HAS_MESH - void onMeshLevelingStart() {} + void onLevelingStart() {} + void onLevelingDone() {} void onMeshUpdate(const int8_t xpos, const int8_t ypos, const_float_t zval) { // Called when any mesh points are updated diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp index 8b0c0f877c2b5..dbee1e034b070 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/flash_storage.cpp @@ -421,7 +421,7 @@ bool UIFlashStorage::is_present = false; uint32_t addr; uint8_t buff[write_page_size]; - strcpy_P( (char*) buff, (const char*) filename); + strcpy_P((char*)buff, FTOP(filename)); MediaFileReader reader; if (!reader.open((char*) buff)) { diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/printing_dialog_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/printing_dialog_box.cpp index f0c0a59d36586..6d177c5a7b4c9 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/printing_dialog_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/printing_dialog_box.cpp @@ -106,8 +106,8 @@ bool BioPrintingDialogBox::onTouchEnd(uint8_t tag) { } void BioPrintingDialogBox::setStatusMessage(FSTR_P message) { - char buff[strlen_P((const char*)message)+1]; - strcpy_P(buff, (const char*) message); + char buff[strlen_P(FTOP(message)) + 1]; + strcpy_P(buff, FTOP(message)); setStatusMessage(buff); } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_extui.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_extui.cpp index f2ee1e5639e4d..1c7b3621f2b4d 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_extui.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_extui.cpp @@ -80,7 +80,7 @@ namespace ExtUI { } void onPrintTimerPaused() {} - void onPrintFinished() {} + void onPrintDone() {} void onFilamentRunout(const extruder_t extruder) { char lcd_msg[30]; @@ -90,7 +90,7 @@ namespace ExtUI { } void onHomingStart() {} - void onHomingComplete() {} + void onHomingDone() {} void onFactoryReset() { InterfaceSettingsScreen::defaultSettings(); } void onStoreSettings(char *buff) { InterfaceSettingsScreen::saveSettings(buff); } @@ -118,7 +118,8 @@ namespace ExtUI { } #if HAS_LEVELING && HAS_MESH - void onMeshLevelingStart() {} + void onLevelingStart() {} + void onLevelingDone() {} void onMeshUpdate(const int8_t x, const int8_t y, const_float_t val) { BedMeshViewScreen::onMeshUpdate(x, y, val); } void onMeshUpdate(const int8_t x, const int8_t y, const ExtUI::probe_state_t state) { BedMeshViewScreen::onMeshUpdate(x, y, state); } #endif diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.h index 24e93982c22a0..648ed5330a980 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.h @@ -242,10 +242,10 @@ class CommandProcessor : public CLCD::CommandFifo { } CommandProcessor& toggle2(int16_t x, int16_t y, int16_t w, int16_t h, FSTR_P no, FSTR_P yes, bool state, uint16_t options = FTDI::OPT_3D) { - char text[strlen_P((const char *)no) + strlen_P((const char *)yes) + 2]; - strcpy_P(text, (const char *)no); + char text[strlen_P(FTOP(no)) + strlen_P(FTOP(yes)) + 2]; + strcpy_P(text, FTOP(no)); strcat(text, "\xFF"); - strcat_P(text, (const char *)yes); + strcat_P(text, FTOP(yes)); return toggle(x, y, w, h, text, state, options); } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp index b4d8156b39d8b..c75cdf18121ad 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp @@ -135,9 +135,9 @@ namespace FTDI { } } - void draw_text_box(CommandProcessor& cmd, int x, int y, int w, int h, FSTR_P pstr, uint16_t options, uint8_t font) { - char str[strlen_P((const char*)pstr) + 1]; - strcpy_P(str, (const char*)pstr); + void draw_text_box(CommandProcessor& cmd, int x, int y, int w, int h, FSTR_P fstr, uint16_t options, uint8_t font) { + char str[strlen_P(FTOP(fstr)) + 1]; + strcpy_P(str, FTOP(fstr)); draw_text_box(cmd, x, y, w, h, (const char*) str, options, font); } } // namespace FTDI diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.cpp index 698bcdb150627..a6d014b56e3bf 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_ellipsis.cpp @@ -33,6 +33,7 @@ namespace FTDI { const bool use_utf8 = has_utf8_chars(str); #define CHAR_WIDTH(c) use_utf8 ? utf8_fm.get_char_width(c) : clcd_fm.char_widths[(uint8_t)c] #else + constexpr bool use_utf8 = false; #define CHAR_WIDTH(c) utf8_fm.get_char_width(c) #endif FontMetrics utf8_fm(font); @@ -53,21 +54,17 @@ namespace FTDI { breakPoint = (char*)next; } - if (lineWidth > w) { - *breakPoint = '\0'; - strcpy_P(breakPoint,PSTR("...")); - } + if (lineWidth > w) + strcpy_P(breakPoint, PSTR("...")); cmd.apply_text_alignment(x, y, w, h, options); - #if ENABLED(TOUCH_UI_USE_UTF8) - if (use_utf8) { - 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); - } + if (use_utf8) { + TERN_(TOUCH_UI_USE_UTF8, draw_utf8_text(cmd, x, y, str, font_size_t::from_romfont(font), options)); + } + else { + cmd.CLCD::CommandFifo::text(x, y, font, options); + cmd.CLCD::CommandFifo::str(str); + } } /** @@ -80,9 +77,9 @@ namespace FTDI { _draw_text_with_ellipsis(cmd, x, y, w, h, tmp, options, font); } - void draw_text_with_ellipsis(CommandProcessor& cmd, int x, int y, int w, int h, FSTR_P pstr, uint16_t options, uint8_t font) { - char tmp[strlen_P((const char*)pstr) + 3]; - strcpy_P(tmp, (const char*)pstr); + void draw_text_with_ellipsis(CommandProcessor& cmd, int x, int y, int w, int h, FSTR_P fstr, uint16_t options, uint8_t font) { + char tmp[strlen_P(FTOP(fstr)) + 3]; + strcpy_P(tmp, FTOP(fstr)); _draw_text_with_ellipsis(cmd, x, y, w, h, tmp, options, font); } } // namespace FTDI diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp index ca25dea3ca9dc..d428f686b7bb4 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp @@ -191,9 +191,9 @@ return render_utf8_text(nullptr, 0, 0, str, fs, maxlen); } - uint16_t FTDI::get_utf8_text_width(FSTR_P pstr, font_size_t fs) { - char str[strlen_P((const char*)pstr) + 1]; - strcpy_P(str, (const char*)pstr); + uint16_t FTDI::get_utf8_text_width(FSTR_P fstr, font_size_t fs) { + char str[strlen_P(FTOP(fstr)) + 1]; + strcpy_P(str, FTOP(fstr)); return get_utf8_text_width(str, fs); } @@ -234,9 +234,9 @@ cmd.cmd(RESTORE_CONTEXT()); } - void FTDI::draw_utf8_text(CommandProcessor& cmd, int x, int y, FSTR_P pstr, font_size_t fs, uint16_t options) { - char str[strlen_P((const char*)pstr) + 1]; - strcpy_P(str, (const char*)pstr); + void FTDI::draw_utf8_text(CommandProcessor& cmd, int x, int y, FSTR_P fstr, font_size_t fs, uint16_t options) { + char str[strlen_P(FTOP(fstr)) + 1]; + strcpy_P(str, FTOP(fstr)); draw_utf8_text(cmd, x, y, (const char*) str, fs, options); } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_numeric_adjustment_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_numeric_adjustment_screen.cpp index 4415ed50fceec..ce3066ae41f24 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_numeric_adjustment_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_numeric_adjustment_screen.cpp @@ -245,8 +245,8 @@ void BaseNumericAdjustmentScreen::widgets_t::adjuster(uint8_t tag, FSTR_P label, } if (_what & FOREGROUND) { - char b[strlen_P(value)+1]; - strcpy_P(b,value); + char b[strlen(value) + 1]; + strcpy(b, value); adjuster_sram_val(tag, label, b, is_enabled); } } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.cpp index 4e76450683e9b..7310577995e5c 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.cpp @@ -345,8 +345,8 @@ void StatusScreen::draw_status_message(draw_mode_t what, const char *message) { } void StatusScreen::setStatusMessage(FSTR_P message) { - char buff[strlen_P((const char * const)message)+1]; - strcpy_P(buff, (const char * const) message); + char buff[strlen_P(FTOP(message)) + 1]; + strcpy_P(buff, FTOP(message)); setStatusMessage((const char *) buff); } diff --git a/Marlin/src/lcd/extui/malyan/malyan_extui.cpp b/Marlin/src/lcd/extui/malyan/malyan_extui.cpp index f323728e27479..2d36a4e737dc1 100644 --- a/Marlin/src/lcd/extui/malyan/malyan_extui.cpp +++ b/Marlin/src/lcd/extui/malyan/malyan_extui.cpp @@ -141,8 +141,8 @@ namespace ExtUI { void onFilamentRunout(const extruder_t extruder) {} void onUserConfirmRequired(const char * const) {} void onHomingStart() {} - void onHomingComplete() {} - void onPrintFinished() {} + void onHomingDone() {} + void onPrintDone() {} void onFactoryReset() {} void onStoreSettings(char*) {} void onLoadSettings(const char*) {} @@ -151,7 +151,8 @@ namespace ExtUI { void onConfigurationStoreRead(bool) {} #if HAS_MESH - void onMeshLevelingStart() {} + void onLevelingStart() {} + void onLevelingDone() {} void onMeshUpdate(const int8_t xpos, const int8_t ypos, const_float_t zval) {} void onMeshUpdate(const int8_t xpos, const int8_t ypos, const ExtUI::probe_state_t state) {} #endif diff --git a/Marlin/src/lcd/extui/mks_ui/draw_ready_print.cpp b/Marlin/src/lcd/extui/mks_ui/draw_ready_print.cpp index 1596944bd8996..39f270840be4e 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_ready_print.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_ready_print.cpp @@ -196,7 +196,7 @@ void lv_draw_ready_print() { buttonExt2 = lv_big_button_create(scr, "F:/bmp_ext2_state.bin", " ", 180, ICON_POS_Y, event_handler, ID_INFO_EXT); #endif #if HAS_HEATED_BED - buttonBedstate = lv_big_button_create(scr, "F:/bmp_bed_state.bin", " ", TERN(HAS_MULTI_HOTEND, 271, 210), ICON_POS_Y, event_handler, ID_INFO_BED); + buttonBedstate = lv_big_button_create(scr, "F:/bmp_bed_state.bin", " ", TERN(HAS_MULTI_HOTEND, 340, 210), ICON_POS_Y, event_handler, ID_INFO_BED); #endif TERN_(HAS_HOTEND, labelExt1 = lv_label_create_empty(scr)); diff --git a/Marlin/src/lcd/extui/nextion/nextion_extui.cpp b/Marlin/src/lcd/extui/nextion/nextion_extui.cpp index c19d3aee46f0a..c15175a28d9ad 100644 --- a/Marlin/src/lcd/extui/nextion/nextion_extui.cpp +++ b/Marlin/src/lcd/extui/nextion/nextion_extui.cpp @@ -50,8 +50,8 @@ namespace ExtUI { void onStatusChanged(const char * const msg) { nextion.StatusChange(msg); } void onHomingStart() {} - void onHomingComplete() {} - void onPrintFinished() { nextion.PrintFinished(); } + void onHomingDone() {} + void onPrintDone() { nextion.PrintFinished(); } void onFactoryReset() {} @@ -90,7 +90,8 @@ namespace ExtUI { } #if HAS_MESH - void onMeshLevelingStart() {} + void onLevelingStart() {} + void onLevelingDone() {} void onMeshUpdate(const int8_t xpos, const int8_t ypos, const float zval) { // Called when any mesh points are updated diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index f44e8bf72032e..bfcbc39d7bf0e 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -861,16 +861,16 @@ namespace ExtUI { #endif #if ENABLED(BACKLASH_GCODE) - float getAxisBacklash_mm(const axis_t axis) { return backlash.distance_mm[axis]; } + float getAxisBacklash_mm(const axis_t axis) { return backlash.get_distance_mm((AxisEnum)axis); } void setAxisBacklash_mm(const_float_t value, const axis_t axis) - { backlash.distance_mm[axis] = constrain(value,0,5); } + { backlash.set_distance_mm((AxisEnum)axis, constrain(value,0,5)); } - float getBacklashCorrection_percent() { return ui8_to_percent(backlash.correction); } - void setBacklashCorrection_percent(const_float_t value) { backlash.correction = map(constrain(value, 0, 100), 0, 100, 0, 255); } + float getBacklashCorrection_percent() { return backlash.get_correction() * 100.0f; } + void setBacklashCorrection_percent(const_float_t value) { backlash.set_correction(constrain(value, 0, 100) / 100.0f); } #ifdef BACKLASH_SMOOTHING_MM - float getBacklashSmoothing_mm() { return backlash.smoothing_mm; } - void setBacklashSmoothing_mm(const_float_t value) { backlash.smoothing_mm = constrain(value, 0, 999); } + float getBacklashSmoothing_mm() { return backlash.get_smoothing_mm(); } + void setBacklashSmoothing_mm(const_float_t value) { backlash.set_smoothing_mm(constrain(value, 0, 999)); } #endif #endif diff --git a/Marlin/src/lcd/extui/ui_api.h b/Marlin/src/lcd/extui/ui_api.h index 6753c53740f89..b575684a039d6 100644 --- a/Marlin/src/lcd/extui/ui_api.h +++ b/Marlin/src/lcd/extui/ui_api.h @@ -172,7 +172,8 @@ namespace ExtUI { float getMeshPoint(const xy_uint8_t &pos); void setMeshPoint(const xy_uint8_t &pos, const_float_t zval); void moveToMeshPoint(const xy_uint8_t &pos, const_float_t z); - void onMeshLevelingStart(); + void onLevelingStart(); + void onLevelingDone(); void onMeshUpdate(const int8_t xpos, const int8_t ypos, const_float_t zval); inline void onMeshUpdate(const xy_int8_t &pos, const_float_t zval) { onMeshUpdate(pos.x, pos.y, zval); } @@ -403,14 +404,14 @@ namespace ExtUI { void onPrintTimerStarted(); void onPrintTimerPaused(); void onPrintTimerStopped(); - void onPrintFinished(); + void onPrintDone(); void onFilamentRunout(const extruder_t extruder); void onUserConfirmRequired(const char * const msg); void onUserConfirmRequired(FSTR_P const fstr); void onStatusChanged(const char * const msg); void onStatusChanged(FSTR_P const fstr); void onHomingStart(); - void onHomingComplete(); + void onHomingDone(); void onSteppersDisabled(); void onSteppersEnabled(); void onFactoryReset(); diff --git a/Marlin/src/lcd/fontutils.h b/Marlin/src/lcd/fontutils.h index 3901d4439fde7..21aee1e93919e 100644 --- a/Marlin/src/lcd/fontutils.h +++ b/Marlin/src/lcd/fontutils.h @@ -63,6 +63,7 @@ uint8_t* get_utf8_value_cb(uint8_t *pstart, read_byte_cb_t cb_read_byte, wchar_t /* Returns length of string in CHARACTERS, NOT BYTES */ uint8_t utf8_strlen(const char *pstart); uint8_t utf8_strlen_P(PGM_P pstart); +inline uint8_t utf8_strlen(FSTR_P fstart) { return utf8_strlen_P(FTOP(fstart)); } /* Returns start byte position of desired char number */ uint8_t utf8_byte_pos_by_char_num(const char *pstart, const uint8_t charnum); diff --git a/Marlin/src/lcd/language/language_de.h b/Marlin/src/lcd/language/language_de.h index 6a5f504e911d9..393d5b58bc1a8 100644 --- a/Marlin/src/lcd/language/language_de.h +++ b/Marlin/src/lcd/language/language_de.h @@ -56,19 +56,42 @@ namespace Language_de { LSTR MSG_DISABLE_STEPPERS = _UxGT("Motoren deaktivieren"); // M84 :: Max length 19 characters LSTR MSG_DEBUG_MENU = _UxGT("Debug-Menü"); LSTR MSG_PROGRESS_BAR_TEST = _UxGT("Statusbalken-Test"); + LSTR MSG_HOMING = _UxGT("Homing"); LSTR MSG_AUTO_HOME = _UxGT("Auto Home"); + LSTR MSG_AUTO_HOME_A = _UxGT("Home @"); LSTR MSG_AUTO_HOME_X = _UxGT("Home X"); LSTR MSG_AUTO_HOME_Y = _UxGT("Home Y"); LSTR MSG_AUTO_HOME_Z = _UxGT("Home Z"); + LSTR MSG_FILAMENT_SET = _UxGT("Fila. Einstellungen"); + LSTR MSG_FILAMENT_MAN = _UxGT("Filament Management"); + LSTR MSG_LEVBED_FL = _UxGT("Vorne Links"); + LSTR MSG_LEVBED_FR = _UxGT("Vorne Rechts"); + LSTR MSG_LEVBED_C = _UxGT("Mitte"); + LSTR MSG_LEVBED_BL = _UxGT("Hinten Links"); + LSTR MSG_LEVBED_BR = _UxGT("Hinten Rechts"); + LSTR MSG_MANUAL_MESH = _UxGT("manuelles Netz"); + LSTR MSG_AUTO_MESH = _UxGT("Netz auto. erstellen"); LSTR MSG_AUTO_Z_ALIGN = _UxGT("Z-Achsen ausgleichen"); + LSTR MSG_ITERATION = _UxGT("G34 Iteration: %i"); + LSTR MSG_DECREASING_ACCURACY = _UxGT("Genauigkeit sinkt!"); + LSTR MSG_ACCURACY_ACHIEVED = _UxGT("Genauigkeit erreicht"); LSTR MSG_LEVEL_BED_HOMING = _UxGT("XYZ homen"); LSTR MSG_LEVEL_BED_WAITING = _UxGT("Klick zum Starten"); LSTR MSG_LEVEL_BED_NEXT_POINT = _UxGT("Nächste Koordinate"); LSTR MSG_LEVEL_BED_DONE = _UxGT("Nivellieren fertig!"); LSTR MSG_Z_FADE_HEIGHT = _UxGT("Ausblendhöhe"); LSTR MSG_SET_HOME_OFFSETS = _UxGT("Setze Homeversatz"); + LSTR MSG_HOME_OFFSET_X = _UxGT("Homeversatz X"); + LSTR MSG_HOME_OFFSET_Y = _UxGT("Homeversatz Y"); + LSTR MSG_HOME_OFFSET_Z = _UxGT("Homeversatz Z"); + LSTR MSG_HOME_OFFSET_I = _UxGT("Homeversatz ") STR_I; + LSTR MSG_HOME_OFFSET_J = _UxGT("Homeversatz ") STR_J; + LSTR MSG_HOME_OFFSET_K = _UxGT("Homeversatz ") STR_K; LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Homeversatz aktiv"); LSTR MSG_SET_ORIGIN = _UxGT("Setze Nullpunkte"); //"G92 X0 Y0 Z0" commented out in marlinui.cpp + LSTR MSG_TRAMMING_WIZARD = _UxGT("Tramming Assistent"); + LSTR MSG_SELECT_ORIGIN = _UxGT("Wählen Sie Ursprung"); + LSTR MSG_LAST_VALUE_SP = _UxGT("Letzter Wert "); #if HAS_PREHEAT LSTR MSG_PREHEAT_1 = PREHEAT_1_LABEL _UxGT(" Vorwärmen"); LSTR MSG_PREHEAT_1_H = PREHEAT_1_LABEL _UxGT(" Vorwärmen ~"); @@ -88,11 +111,21 @@ namespace Language_de { #endif LSTR MSG_PREHEAT_CUSTOM = _UxGT("benutzerdef. Heizen"); LSTR MSG_COOLDOWN = _UxGT("Abkühlen"); + LSTR MSG_CUTTER_FREQUENCY = _UxGT("Frequenz"); LSTR MSG_LASER_MENU = _UxGT("Laser"); - LSTR MSG_LASER_POWER = _UxGT("Laserleistung"); LSTR MSG_SPINDLE_MENU = _UxGT("Spindel-Steuerung"); + LSTR MSG_LASER_POWER = _UxGT("Laserleistung"); LSTR MSG_SPINDLE_POWER = _UxGT("Spindelleistung"); + LSTR MSG_LASER_TOGGLE = _UxGT("Laser umschalten"); + LSTR MSG_LASER_EVAC_TOGGLE = _UxGT("Gebläse umschalten"); + LSTR MSG_LASER_ASSIST_TOGGLE = _UxGT("Luftunterstützung"); + LSTR MSG_LASER_PULSE_MS = _UxGT("Test Impuls ms"); + LSTR MSG_LASER_FIRE_PULSE = _UxGT("Fire Impuls"); + LSTR MSG_FLOWMETER_FAULT = _UxGT("Feh. Kühlmittelfluss"); + LSTR MSG_SPINDLE_TOGGLE = _UxGT("Spindel umschalten"); + LSTR MSG_SPINDLE_EVAC_TOGGLE = _UxGT("Vakuum umschalten"); + LSTR MSG_SPINDLE_FORWARD = _UxGT("Spindel vorwärts"); LSTR MSG_SPINDLE_REVERSE = _UxGT("Spindelrichtung"); LSTR MSG_SWITCH_PS_ON = _UxGT("Netzteil ein"); LSTR MSG_SWITCH_PS_OFF = _UxGT("Netzteil aus"); @@ -102,10 +135,18 @@ namespace Language_de { LSTR MSG_BED_LEVELING = _UxGT("Bett-Nivellierung"); LSTR MSG_LEVEL_BED = _UxGT("Bett nivellieren"); LSTR MSG_BED_TRAMMING = _UxGT("Bett ausrichten"); + LSTR MSG_BED_TRAMMING_MANUAL = _UxGT("Manuelles ausrichten"); + LSTR MSG_BED_TRAMMING_RAISE = _UxGT("Das Bett anpassen, bis zum auslösen."); + LSTR MSG_BED_TRAMMING_IN_RANGE = _UxGT("Ecken in der Toleranz. Bett ausger."); + LSTR MSG_BED_TRAMMING_GOOD_POINTS = _UxGT("Gute Punkte: "); + LSTR MSG_BED_TRAMMING_LAST_Z = _UxGT("Letztes Z: "); LSTR MSG_NEXT_CORNER = _UxGT("Nächste Ecke"); LSTR MSG_MESH_EDITOR = _UxGT("Netz Editor"); + LSTR MSG_MESH_VIEWER = _UxGT("Netzbetrachter"); LSTR MSG_EDIT_MESH = _UxGT("Netz bearbeiten"); + LSTR MSG_MESH_VIEW = _UxGT("Netz ansehen"); LSTR MSG_EDITING_STOPPED = _UxGT("Netzbearb. angeh."); + LSTR MSG_NO_VALID_MESH = _UxGT("Kein gültiges Netz"); LSTR MSG_PROBING_POINT = _UxGT("Messpunkt"); LSTR MSG_MESH_X = _UxGT("Index X"); LSTR MSG_MESH_Y = _UxGT("Index Y"); @@ -121,6 +162,7 @@ namespace Language_de { LSTR MSG_IDEX_MODE_DUPLICATE = _UxGT("Duplizieren"); LSTR MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Spiegelkopie"); LSTR MSG_IDEX_MODE_FULL_CTRL = _UxGT("vollstä. Kontrolle"); + LSTR MSG_IDEX_DUPE_GAP = _UxGT("X-Lücke duplizieren"); LSTR MSG_HOTEND_OFFSET_Z = _UxGT("2. Düse Z"); LSTR MSG_HOTEND_OFFSET_A = _UxGT("2. Düse @"); LSTR MSG_UBL_DOING_G29 = _UxGT("G29 ausführen"); @@ -128,6 +170,7 @@ namespace Language_de { LSTR MSG_UBL_LEVEL_BED = _UxGT("Unified Bed Leveling"); LSTR MSG_LCD_TILTING_MESH = _UxGT("Berührungspunkt"); LSTR MSG_UBL_MANUAL_MESH = _UxGT("Netz manuell erst."); + LSTR MSG_UBL_MESH_WIZARD = _UxGT("UBL Netz Assistent"); LSTR MSG_UBL_BC_INSERT = _UxGT("Unterlegen & messen"); LSTR MSG_UBL_BC_INSERT2 = _UxGT("Messen"); LSTR MSG_UBL_BC_REMOVE = _UxGT("Entfernen & messen"); @@ -212,6 +255,10 @@ namespace Language_de { LSTR MSG_SET_LEDS_VIOLET = _UxGT("Violett"); LSTR MSG_SET_LEDS_WHITE = _UxGT("Weiß"); LSTR MSG_SET_LEDS_DEFAULT = _UxGT("Standard"); + LSTR MSG_LED_CHANNEL_N = _UxGT("Kanal ="); + LSTR MSG_LEDS2 = _UxGT("Lichter #2"); + LSTR MSG_NEO2_PRESETS = _UxGT("Licht #2 Voreinst."); + LSTR MSG_NEO2_BRIGHTNESS = _UxGT("Helligkeit"); LSTR MSG_CUSTOM_LEDS = _UxGT("Benutzerdefiniert"); LSTR MSG_INTENSITY_R = _UxGT("Intensität Rot"); LSTR MSG_INTENSITY_G = _UxGT("Intensität Grün"); @@ -224,6 +271,9 @@ namespace Language_de { LSTR MSG_MOVE_X = _UxGT("Bewege X"); LSTR MSG_MOVE_Y = _UxGT("Bewege Y"); LSTR MSG_MOVE_Z = _UxGT("Bewege Z"); + LSTR MSG_MOVE_I = _UxGT("Bewege ") STR_I; + LSTR MSG_MOVE_J = _UxGT("Bewege ") STR_J; + LSTR MSG_MOVE_K = _UxGT("Bewege ") STR_K; LSTR MSG_MOVE_E = _UxGT("Bewege Extruder"); LSTR MSG_MOVE_EN = _UxGT("Bewege Extruder *"); LSTR MSG_HOTEND_TOO_COLD = _UxGT("Hotend zu kalt"); @@ -232,7 +282,17 @@ namespace Language_de { LSTR MSG_MOVE_1MM = _UxGT(" 1,0 mm"); LSTR MSG_MOVE_10MM = _UxGT(" 10,0 mm"); LSTR MSG_MOVE_100MM = _UxGT("100,0 mm"); + LSTR MSG_MOVE_0001IN = _UxGT("0.001 in"); + LSTR MSG_MOVE_001IN = _UxGT("0.010 in"); + LSTR MSG_MOVE_01IN = _UxGT("0.100 in"); + LSTR MSG_MOVE_1IN = _UxGT("1.000 in"); LSTR MSG_SPEED = _UxGT("Geschw."); + LSTR MSG_MAXSPEED = _UxGT("Max Geschw. (mm/s)"); + LSTR MSG_MAXSPEED_X = _UxGT("Max ") STR_A _UxGT(" Geschw."); + LSTR MSG_MAXSPEED_Y = _UxGT("Max ") STR_B _UxGT(" Geschw."); + LSTR MSG_MAXSPEED_Z = _UxGT("Max ") STR_C _UxGT(" Geschw."); + LSTR MSG_MAXSPEED_E = _UxGT("Max ") STR_E _UxGT(" Geschw."); + LSTR MSG_MAXSPEED_A = _UxGT("Max @ Geschw."); LSTR MSG_BED_Z = _UxGT("Bett Z"); LSTR MSG_NOZZLE = _UxGT("Düse"); LSTR MSG_NOZZLE_N = _UxGT("Düse ~"); @@ -240,6 +300,10 @@ namespace Language_de { LSTR MSG_NOZZLE_STANDBY = _UxGT("Düse bereit"); LSTR MSG_BED = _UxGT("Bett"); LSTR MSG_CHAMBER = _UxGT("Gehäuse"); + LSTR MSG_COOLER = _UxGT("Laser-Kühlmittel"); + LSTR MSG_COOLER_TOGGLE = _UxGT("Kühler umschalten"); + LSTR MSG_FLOWMETER_SAFETY = _UxGT("Durchflusssicherheit"); + LSTR MSG_LASER = _UxGT("Laser"); LSTR MSG_FAN_SPEED = _UxGT("Lüfter"); LSTR MSG_FAN_SPEED_N = _UxGT("Lüfter ~"); LSTR MSG_STORED_FAN_N = _UxGT("Gespeich. Lüfter ~"); @@ -261,6 +325,7 @@ namespace Language_de { LSTR MSG_LCD_OFF = _UxGT("aus"); LSTR MSG_PID_AUTOTUNE = _UxGT("PID Autotune"); LSTR MSG_PID_AUTOTUNE_E = _UxGT("PID Autotune *"); + LSTR MSG_PID_CYCLE = _UxGT("PID Zyklus"); LSTR MSG_PID_AUTOTUNE_DONE = _UxGT("PID Tuning fertig"); LSTR MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Autotune fehlge. Falscher Extruder"); LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("Autotune fehlge. Temperatur zu hoch."); @@ -289,7 +354,6 @@ namespace Language_de { LSTR MSG_VMIN = _UxGT("V min "); LSTR MSG_VTRAV_MIN = _UxGT("V min Leerfahrt"); LSTR MSG_ACCELERATION = _UxGT("Beschleunigung"); - LSTR MSG_AMAX = _UxGT("A max "); // space intentional LSTR MSG_AMAX_A = _UxGT("A max ") STR_A; LSTR MSG_AMAX_B = _UxGT("A max ") STR_B; LSTR MSG_AMAX_C = _UxGT("A max ") STR_C; @@ -324,6 +388,9 @@ namespace Language_de { LSTR MSG_ADVANCE_K = _UxGT("Vorschubfaktor"); LSTR MSG_ADVANCE_K_E = _UxGT("Vorschubfaktor *"); LSTR MSG_CONTRAST = _UxGT("LCD-Kontrast"); + LSTR MSG_BRIGHTNESS = _UxGT("LCD Helligkeit"); + LSTR MSG_LCD_BKL_TIMEOUT = _UxGT("LCD-Ruhezustand (s)"); + LSTR MSG_BRIGHTNESS_OFF = _UxGT("LCD ausschalten"); LSTR MSG_STORE_EEPROM = _UxGT("Konfig. speichern"); LSTR MSG_LOAD_EEPROM = _UxGT("Konfig. laden"); LSTR MSG_RESTORE_DEFAULTS = _UxGT("Standardwerte laden"); @@ -350,23 +417,38 @@ namespace Language_de { LSTR MSG_BUTTON_RESET = _UxGT("Reseten"); LSTR MSG_BUTTON_IGNORE = _UxGT("Ignorieren"); LSTR MSG_BUTTON_CANCEL = _UxGT("Abbrechen"); + LSTR MSG_BUTTON_CONFIRM = _UxGT("Bestätigen"); + LSTR MSG_BUTTON_CONTINUE = _UxGT("Fortsetzen"); LSTR MSG_BUTTON_DONE = _UxGT("Fertig"); LSTR MSG_BUTTON_BACK = _UxGT("Zurück"); LSTR MSG_BUTTON_PROCEED = _UxGT("Weiter"); + LSTR MSG_BUTTON_SKIP = _UxGT("Überspringen"); + LSTR MSG_BUTTON_INFO = _UxGT("Info"); + LSTR MSG_BUTTON_LEVEL = _UxGT("Level"); + LSTR MSG_BUTTON_PAUSE = _UxGT("Pause"); + LSTR MSG_BUTTON_RESUME = _UxGT("Fortsetzen"); + LSTR MSG_BUTTON_ADVANCED = _UxGT("Erweitert"); + LSTR MSG_BUTTON_SAVE = _UxGT("Speichern"); LSTR MSG_PAUSING = _UxGT("Pause..."); LSTR MSG_PAUSE_PRINT = _UxGT("SD-Druck pausieren"); + LSTR MSG_ADVANCED_PAUSE = _UxGT("Erweiterte Pause"); LSTR MSG_RESUME_PRINT = _UxGT("SD-Druck fortsetzen"); + LSTR MSG_HOST_START_PRINT = _UxGT("Host-Druck starten"); LSTR MSG_STOP_PRINT = _UxGT("SD-Druck abbrechen"); + LSTR MSG_END_LOOPS = _UxGT("Wiederholung beenden"); LSTR MSG_PRINTING_OBJECT = _UxGT("Objekt drucken"); LSTR MSG_CANCEL_OBJECT = _UxGT("Objekt abbrechen"); LSTR MSG_CANCEL_OBJECT_N = _UxGT("Objekt abbrechen ="); LSTR MSG_OUTAGE_RECOVERY = _UxGT("Wiederh. n. Stroma."); + LSTR MSG_CONTINUE_PRINT_JOB = _UxGT("Druckauftrag fortset."); LSTR MSG_MEDIA_MENU = _UxGT("Druck vom Medium"); LSTR MSG_NO_MEDIA = _UxGT("Kein Medium"); LSTR MSG_DWELL = _UxGT("Warten..."); LSTR MSG_USERWAIT = _UxGT("Klick zum Fortsetzen"); LSTR MSG_PRINT_PAUSED = _UxGT("Druck pausiert..."); LSTR MSG_PRINTING = _UxGT("Druckt..."); + LSTR MSG_STOPPING = _UxGT("Stoppen..."); + LSTR MSG_REMAINING_TIME = _UxGT("Verbleiben"); LSTR MSG_PRINT_ABORTED = _UxGT("Druck abgebrochen"); LSTR MSG_PRINT_DONE = _UxGT("Druck fertig"); LSTR MSG_NO_MOVE = _UxGT("Motoren angeschaltet"); @@ -416,6 +498,7 @@ namespace Language_de { LSTR MSG_BLTOUCH_STOW = _UxGT("Einfahren"); LSTR MSG_BLTOUCH_DEPLOY = _UxGT("Ausfahren"); LSTR MSG_BLTOUCH_SW_MODE = _UxGT("SW-Modus"); + LSTR MSG_BLTOUCH_SPEED_MODE = _UxGT("High Speed"); LSTR MSG_BLTOUCH_5V_MODE = _UxGT("5V-Modus"); LSTR MSG_BLTOUCH_OD_MODE = _UxGT("OD-Modus"); LSTR MSG_BLTOUCH_MODE_STORE = _UxGT("Mode-Store"); @@ -431,33 +514,43 @@ namespace Language_de { LSTR MSG_MANUAL_DEPLOY = _UxGT("Z-Sonde ausfahren"); LSTR MSG_MANUAL_STOW = _UxGT("Z-Sonde einfahren"); LSTR MSG_HOME_FIRST = _UxGT("Vorher %s%s%s homen"); + LSTR MSG_ZPROBE_SETTINGS = _UxGT("Sondeneinstellungen"); LSTR MSG_ZPROBE_OFFSETS = _UxGT("Sondenversatz"); LSTR MSG_ZPROBE_XOFFSET = _UxGT("Sondenversatz X"); LSTR MSG_ZPROBE_YOFFSET = _UxGT("Sondenversatz Y"); LSTR MSG_ZPROBE_ZOFFSET = _UxGT("Sondenversatz Z"); + LSTR MSG_MOVE_NOZZLE_TO_BED = _UxGT("Bewege Düse zum Bett"); LSTR MSG_BABYSTEP_X = _UxGT("Babystep X"); LSTR MSG_BABYSTEP_Y = _UxGT("Babystep Y"); LSTR MSG_BABYSTEP_Z = _UxGT("Babystep Z"); + LSTR MSG_BABYSTEP_I = _UxGT("Babystep ") STR_I; + LSTR MSG_BABYSTEP_J = _UxGT("Babystep ") STR_J; + LSTR MSG_BABYSTEP_K = _UxGT("Babystep ") STR_K; LSTR MSG_BABYSTEP_TOTAL = _UxGT("Total"); LSTR MSG_ENDSTOP_ABORT = _UxGT("Abbr. mit Endstopp"); LSTR MSG_HEATING_FAILED_LCD = _UxGT("HEIZEN ERFOLGLOS"); LSTR MSG_ERR_REDUNDANT_TEMP = _UxGT("REDUND. TEMP-ABWEI."); LSTR MSG_THERMAL_RUNAWAY = " " LCD_STR_THERMOMETER _UxGT(" NICHT ERREICHT"); + LSTR MSG_TEMP_MALFUNCTION = _UxGT("TEMP-FEHLER"); LSTR MSG_THERMAL_RUNAWAY_BED = _UxGT("BETT") " " LCD_STR_THERMOMETER _UxGT(" NICHT ERREICHT"); LSTR MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("GEH.") " " LCD_STR_THERMOMETER _UxGT(" NICHT ERREICHT"); + LSTR MSG_THERMAL_RUNAWAY_COOLER = _UxGT("Kühler Runaway"); + LSTR MSG_COOLING_FAILED = _UxGT("Kühlung fehlgeschla."); LSTR MSG_ERR_MAXTEMP = " " LCD_STR_THERMOMETER _UxGT(" ÜBERSCHRITTEN"); LSTR MSG_ERR_MINTEMP = " " LCD_STR_THERMOMETER _UxGT(" UNTERSCHRITTEN"); LSTR MSG_HALTED = _UxGT("DRUCKER GESTOPPT"); + LSTR MSG_PLEASE_WAIT = _UxGT("Bitte warten..."); LSTR MSG_PLEASE_RESET = _UxGT("Bitte neustarten"); - LSTR MSG_SHORT_DAY = _UxGT("t"); // One character only - LSTR MSG_SHORT_HOUR = _UxGT("h"); // One character only - LSTR MSG_SHORT_MINUTE = _UxGT("m"); // One character only + LSTR MSG_PREHEATING = _UxGT("vorheizen..."); LSTR MSG_HEATING = _UxGT("heizt..."); LSTR MSG_COOLING = _UxGT("kühlt..."); LSTR MSG_BED_HEATING = _UxGT("Bett heizt..."); LSTR MSG_BED_COOLING = _UxGT("Bett kühlt..."); + LSTR MSG_PROBE_HEATING = _UxGT("Sonde heizt..."); + LSTR MSG_PROBE_COOLING = _UxGT("Sonde kühlt..."); LSTR MSG_CHAMBER_HEATING = _UxGT("Gehäuse heizt..."); LSTR MSG_CHAMBER_COOLING = _UxGT("Gehäuse kühlt..."); + LSTR MSG_LASER_COOLING = _UxGT("Laser kühlt..."); LSTR MSG_DELTA_CALIBRATE = _UxGT("Delta kalibrieren"); LSTR MSG_DELTA_CALIBRATE_X = _UxGT("Kalibriere X"); LSTR MSG_DELTA_CALIBRATE_Y = _UxGT("Kalibriere Y"); @@ -475,8 +568,9 @@ namespace Language_de { LSTR MSG_3POINT_LEVELING = _UxGT("3-Punkt-Nivellierung"); LSTR MSG_LINEAR_LEVELING = _UxGT("Lineare Nivellierung"); LSTR MSG_BILINEAR_LEVELING = _UxGT("Bilineare Nivell."); - LSTR MSG_UBL_LEVELING = _UxGT("Unified Bed Leveling"); + LSTR MSG_UBL_LEVELING = _UxGT("Einheit. Bettnivell."); LSTR MSG_MESH_LEVELING = _UxGT("Netz-Nivellierung"); + LSTR MSG_MESH_DONE = _UxGT("Nivellierung fertig"); LSTR MSG_INFO_STATS_MENU = _UxGT("Drucker-Statistik"); LSTR MSG_INFO_BOARD_MENU = _UxGT("Board-Info"); LSTR MSG_INFO_THERMISTOR_MENU = _UxGT("Thermistoren"); @@ -486,23 +580,39 @@ namespace Language_de { LSTR MSG_INFO_RUNAWAY_OFF = _UxGT("Runaway Watch: AUS"); LSTR MSG_INFO_RUNAWAY_ON = _UxGT("Runaway Watch: AN"); LSTR MSG_HOTEND_IDLE_TIMEOUT = _UxGT("Hotend Idle Timeout"); + LSTR MSG_FAN_SPEED_FAULT = _UxGT("Fehler Lüftergeschw."); + LSTR MSG_CASE_LIGHT = _UxGT("Beleuchtung"); LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Helligkeit"); - LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("Falscher Drucker"); #if LCD_WIDTH >= 20 || HAS_DWIN_E3V2 + LSTR MSG_MEDIA_NOT_INSERTED = _UxGT("Kein Medium eingelegt."); + LSTR MSG_PLEASE_WAIT_REBOOT = _UxGT("Bitte auf Neustart warten. "); + LSTR MSG_PLEASE_PREHEAT = _UxGT("Bitte das Hot-End vorheizen."); + LSTR MSG_INFO_PRINT_COUNT_RESET = _UxGT("Druckzähler zurücksetzen"); LSTR MSG_INFO_PRINT_COUNT = _UxGT("Gesamte Drucke"); LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Komplette Drucke"); LSTR MSG_INFO_PRINT_TIME = _UxGT("Gesamte Druckzeit"); LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Längste Druckzeit"); LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Gesamt Extrudiert"); + LSTR MSG_COLORS_GET = _UxGT("Farbe"); + LSTR MSG_COLORS_SELECT = _UxGT("Farben auswählen"); + LSTR MSG_COLORS_APPLIED = _UxGT("Farben verwenden"); + LSTR MSG_COLORS_RED = _UxGT("Rot"); + LSTR MSG_COLORS_GREEN = _UxGT("Grün"); + LSTR MSG_COLORS_BLUE = _UxGT("Blau"); + LSTR MSG_COLORS_WHITE = _UxGT("Weiß"); + LSTR MSG_UI_LANGUAGE = _UxGT("UI Sprache"); + LSTR MSG_SOUND_ENABLE = _UxGT("Ton aktivieren"); + LSTR MSG_LOCKSCREEN = _UxGT("Bildschirm sperren"); #else LSTR MSG_INFO_PRINT_COUNT = _UxGT("Drucke"); LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Komplette"); LSTR MSG_INFO_PRINT_TIME = _UxGT("Gesamte"); LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Längste"); LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Extrud."); + LSTR MSG_PLEASE_PREHEAT = _UxGT("Bitte vorheizen"); #endif LSTR MSG_INFO_MIN_TEMP = _UxGT("Min Temp"); @@ -528,6 +638,8 @@ namespace Language_de { LSTR MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Düse: "); LSTR MSG_RUNOUT_SENSOR = _UxGT("Runout-Sensor"); LSTR MSG_RUNOUT_DISTANCE_MM = _UxGT("Runout-Weg mm"); + LSTR MSG_RUNOUT_ENABLE = _UxGT("Runout aktivieren"); + LSTR MSG_FANCHECK = _UxGT("Lüftergeschw. prüfen"); LSTR MSG_KILL_HOMING_FAILED = _UxGT("Homing gescheitert"); LSTR MSG_LCD_PROBING_FAILED = _UxGT("Probing gescheitert"); @@ -639,4 +751,33 @@ namespace Language_de { #endif LSTR MSG_REHEAT = _UxGT("Erneut aufheizen"); LSTR MSG_REHEATING = _UxGT("Erneut aufhei. ..."); + LSTR MSG_REHEATDONE = _UxGT("Aufwärmen fertig"); + + LSTR MSG_PROBE_WIZARD = _UxGT("Sonden-Assistent"); + LSTR MSG_PROBE_WIZARD_PROBING = _UxGT("Sonden-Bezug"); + LSTR MSG_PROBE_WIZARD_MOVING = _UxGT("Bewege zur Position"); + + LSTR MSG_XATC = _UxGT("X-Verdreh-Assistent"); + LSTR MSG_XATC_DONE = _UxGT("X-Verdreh-Assi fertig!"); + LSTR MSG_XATC_UPDATE_Z_OFFSET = _UxGT("Z-Versatz Sonde akt. auf "); + + LSTR MSG_SOUND = _UxGT("Ton"); + + LSTR MSG_TOP_LEFT = _UxGT("Oben Links"); + LSTR MSG_BOTTOM_LEFT = _UxGT("Unten Links"); + LSTR MSG_TOP_RIGHT = _UxGT("Oben Rechts"); + LSTR MSG_BOTTOM_RIGHT = _UxGT("Unten Rechts"); + LSTR MSG_CALIBRATION_COMPLETED = _UxGT("Kalibrierung beendet"); + LSTR MSG_CALIBRATION_FAILED = _UxGT("Kalibrierung geschei."); + + LSTR MSG_DRIVER_BACKWARD = _UxGT(" Driver zurück"); + + LSTR MSG_SD_CARD = _UxGT("SD Karte"); + LSTR MSG_USB_DISK = _UxGT("USB Disk"); + + LSTR MSG_HOST_SHUTDOWN = _UxGT("Host abschalten"); + + LSTR MSG_SHORT_DAY = _UxGT("t"); // One character only + LSTR MSG_SHORT_HOUR = _UxGT("h"); // One character only + LSTR MSG_SHORT_MINUTE = _UxGT("m"); // One character only } diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index d8d161701fdb3..43bbd90210fd9 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -151,6 +151,7 @@ namespace Language_en { LSTR MSG_BED_LEVELING = _UxGT("Bed Leveling"); LSTR MSG_LEVEL_BED = _UxGT("Level Bed"); LSTR MSG_BED_TRAMMING = _UxGT("Bed Tramming"); + LSTR MSG_BED_TRAMMING_MANUAL = _UxGT("Manual Tramming"); LSTR MSG_BED_TRAMMING_RAISE = _UxGT("Adjust bed until the probe triggers."); LSTR MSG_BED_TRAMMING_IN_RANGE = _UxGT("Corners within tolerance. Bed trammed."); LSTR MSG_BED_TRAMMING_GOOD_POINTS = _UxGT("Good Points: "); @@ -402,6 +403,8 @@ namespace Language_en { LSTR MSG_ADVANCE_K_E = _UxGT("Advance K *"); LSTR MSG_CONTRAST = _UxGT("LCD Contrast"); LSTR MSG_BRIGHTNESS = _UxGT("LCD Brightness"); + LSTR MSG_LCD_BKL_TIMEOUT = _UxGT("LCD Timeout (s)"); + LSTR MSG_BRIGHTNESS_OFF = _UxGT("Backlight Off"); LSTR MSG_STORE_EEPROM = _UxGT("Store Settings"); LSTR MSG_LOAD_EEPROM = _UxGT("Load Settings"); LSTR MSG_RESTORE_DEFAULTS = _UxGT("Restore Defaults"); @@ -428,6 +431,8 @@ namespace Language_en { LSTR MSG_BUTTON_RESET = _UxGT("Reset"); LSTR MSG_BUTTON_IGNORE = _UxGT("Ignore"); LSTR MSG_BUTTON_CANCEL = _UxGT("Cancel"); + LSTR MSG_BUTTON_CONFIRM = _UxGT("Confirm"); + LSTR MSG_BUTTON_CONTINUE = _UxGT("Continue"); LSTR MSG_BUTTON_DONE = _UxGT("Done"); LSTR MSG_BUTTON_BACK = _UxGT("Back"); LSTR MSG_BUTTON_PROCEED = _UxGT("Proceed"); @@ -437,6 +442,7 @@ namespace Language_en { LSTR MSG_BUTTON_PAUSE = _UxGT("Pause"); LSTR MSG_BUTTON_RESUME = _UxGT("Resume"); LSTR MSG_BUTTON_ADVANCED = _UxGT("Advanced"); + LSTR MSG_BUTTON_SAVE = _UxGT("Save"); LSTR MSG_PAUSING = _UxGT("Pausing..."); LSTR MSG_PAUSE_PRINT = _UxGT("Pause Print"); LSTR MSG_ADVANCED_PAUSE = _UxGT("Advanced Pause"); diff --git a/Marlin/src/lcd/language/language_fr.h b/Marlin/src/lcd/language/language_fr.h index 2eb64fc2c228f..ca3757f704d69 100644 --- a/Marlin/src/lcd/language/language_fr.h +++ b/Marlin/src/lcd/language/language_fr.h @@ -335,6 +335,8 @@ namespace Language_fr { LSTR MSG_ADVANCE_K_E = _UxGT("Avance K *"); LSTR MSG_BRIGHTNESS = _UxGT("Luminosité LCD"); LSTR MSG_CONTRAST = _UxGT("Contraste LCD"); + LSTR MSG_LCD_BKL_TIMEOUT = _UxGT("Veille LCD (s)"); + LSTR MSG_BRIGHTNESS_OFF = _UxGT("Éteindre l'écran LCD"); LSTR MSG_STORE_EEPROM = _UxGT("Enregistrer config."); LSTR MSG_LOAD_EEPROM = _UxGT("Charger config."); LSTR MSG_RESTORE_DEFAULTS = _UxGT("Restaurer défauts"); diff --git a/Marlin/src/lcd/language/language_jp_kana.h b/Marlin/src/lcd/language/language_jp_kana.h index 3a876a07e383f..164dca8fcfe2a 100644 --- a/Marlin/src/lcd/language/language_jp_kana.h +++ b/Marlin/src/lcd/language/language_jp_kana.h @@ -137,7 +137,6 @@ namespace Language_jp_kana { LSTR MSG_VMIN = _UxGT("サイショウオクリソクド"); // "Vmin" LSTR MSG_VTRAV_MIN = _UxGT("サイショウイドウソクド"); // "VTrav min" LSTR MSG_ACCELERATION = _UxGT("カソクド mm/s") SUPERSCRIPT_TWO; // "Accel" - LSTR MSG_AMAX = _UxGT("サイダイカソクド "); // "Amax " LSTR MSG_A_RETRACT = _UxGT("ヒキコミカソクド"); // "A-retract" LSTR MSG_A_TRAVEL = _UxGT("イドウカソクド"); // "A-travel" LSTR MSG_TEMPERATURE = _UxGT("オンド"); // "Temperature" diff --git a/Marlin/src/lcd/lcdprint.cpp b/Marlin/src/lcd/lcdprint.cpp index 498b478b1258b..8ca0c8ee9e3e6 100644 --- a/Marlin/src/lcd/lcdprint.cpp +++ b/Marlin/src/lcd/lcdprint.cpp @@ -26,7 +26,7 @@ #include "../inc/MarlinConfigPre.h" -#if HAS_WIRED_LCD && !HAS_GRAPHICAL_TFT && !IS_DWIN_MARLINUI +#if HAS_LCDPRINT #include "marlinui.h" #include "lcdprint.h" @@ -103,4 +103,4 @@ int calculateWidth(PGM_P const pstr) { return n * MENU_FONT_WIDTH; } -#endif // HAS_WIRED_LCD +#endif // HAS_LCDPRINT diff --git a/Marlin/src/lcd/lcdprint.h b/Marlin/src/lcd/lcdprint.h index c701a59568f55..d716d035caf6e 100644 --- a/Marlin/src/lcd/lcdprint.h +++ b/Marlin/src/lcd/lcdprint.h @@ -190,6 +190,9 @@ inline lcd_uint_t lcd_put_u8str_ind_P(const lcd_uint_t col, const lcd_uint_t row lcd_moveto(col, row); return lcd_put_u8str_ind_P(pstr, ind, inStr, maxlen); } +inline lcd_uint_t lcd_put_u8str_ind(FSTR_P const fstr, const int8_t ind, FSTR_P const inFstr=nullptr, const lcd_uint_t maxlen=LCD_WIDTH) { + return lcd_put_u8str_ind_P(FTOP(fstr), ind, FTOP(inFstr), maxlen); +} inline lcd_uint_t lcd_put_u8str_ind(const lcd_uint_t col, const lcd_uint_t row, FSTR_P const fstr, const int8_t ind, FSTR_P const inFstr=nullptr, const lcd_uint_t maxlen=LCD_WIDTH) { return lcd_put_u8str_ind_P(col, row, FTOP(fstr), ind, FTOP(inFstr), maxlen); } diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 27965c1bd4283..f0677afd2d1d4 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -47,8 +47,7 @@ MarlinUI ui; #if ENABLED(DWIN_CREALITY_LCD) #include "e3v2/creality/dwin.h" -#elif ENABLED(DWIN_CREALITY_LCD_ENHANCED) - #include "fontutils.h" +#elif ENABLED(DWIN_LCD_PROUI) #include "e3v2/proui/dwin.h" #elif ENABLED(DWIN_CREALITY_LCD_JYERSUI) #include "e3v2/jyersui/dwin.h" @@ -69,7 +68,7 @@ MarlinUI ui; constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; #if HAS_STATUS_MESSAGE - #if ENABLED(STATUS_MESSAGE_SCROLLING) && EITHER(HAS_WIRED_LCD, DWIN_CREALITY_LCD_ENHANCED) + #if ENABLED(STATUS_MESSAGE_SCROLLING) && EITHER(HAS_WIRED_LCD, DWIN_LCD_PROUI) uint8_t MarlinUI::status_scroll_offset; // = 0 #endif char MarlinUI::status_message[MAX_MESSAGE_LENGTH + 1]; @@ -180,6 +179,15 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; volatile int8_t encoderDiff; // Updated in update_buttons, added to encoderPosition every LCD update #endif +#if LCD_BACKLIGHT_TIMEOUT + uint16_t MarlinUI::lcd_backlight_timeout; // Initialized by settings.load() + millis_t MarlinUI::backlight_off_ms = 0; + void MarlinUI::refresh_backlight_timeout() { + backlight_off_ms = lcd_backlight_timeout ? millis() + lcd_backlight_timeout * 1000UL : 0; + WRITE(LCD_BACKLIGHT_PIN, HIGH); + } +#endif + void MarlinUI::init() { init_lcd(); @@ -625,7 +633,7 @@ void MarlinUI::init() { next_filament_display = millis() + 5000UL; // Show status message for 5s #endif goto_screen(menu_main); - IF_DISABLED(NO_LCD_REINIT, init_lcd()); // May revive the LCD if static electricity killed it + reinit_lcd(); // Revive a noisy shared SPI LCD return; } @@ -1033,14 +1041,18 @@ void MarlinUI::init() { reset_status_timeout(ms); + #if LCD_BACKLIGHT_TIMEOUT + refresh_backlight_timeout(); + #endif + refresh(LCDVIEW_REDRAW_NOW); #if LED_POWEROFF_TIMEOUT > 0 if (!powerManager.psu_on) leds.reset_timeout(ms); #endif - } + } // encoder activity - #endif + #endif // HAS_ENCODER_ACTION // This runs every ~100ms when idling often enough. // Instead of tracking changes just redraw the Status Screen once per second. @@ -1137,6 +1149,13 @@ void MarlinUI::init() { return_to_status(); #endif + #if LCD_BACKLIGHT_TIMEOUT + if (backlight_off_ms && ELAPSED(ms, backlight_off_ms)) { + WRITE(LCD_BACKLIGHT_PIN, LOW); // Backlight off + backlight_off_ms = 0; + } + #endif + // Change state of drawing flag between screen updates if (!drawing_screen) switch (lcdDrawUpdate) { case LCDVIEW_CLEAR_CALL_REDRAW: @@ -1421,8 +1440,10 @@ void MarlinUI::init() { else if (print_job_timer.needsService(3)) msg = FPSTR(service3); #endif - else if (!no_welcome) - msg = GET_TEXT_F(WELCOME_MSG); + else if (!no_welcome) msg = GET_TEXT_F(WELCOME_MSG); + + else if (ENABLED(DWIN_LCD_PROUI)) + msg = F(""); else return; @@ -1502,13 +1523,13 @@ void MarlinUI::init() { #endif - #if ENABLED(STATUS_MESSAGE_SCROLLING) && EITHER(HAS_WIRED_LCD, DWIN_CREALITY_LCD_ENHANCED) + #if ENABLED(STATUS_MESSAGE_SCROLLING) && EITHER(HAS_WIRED_LCD, DWIN_LCD_PROUI) status_scroll_offset = 0; #endif TERN_(EXTENSIBLE_UI, ExtUI::onStatusChanged(status_message)); TERN_(DWIN_CREALITY_LCD, DWIN_StatusChanged(status_message)); - TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_CheckStatusMessage()); + TERN_(DWIN_LCD_PROUI, DWIN_CheckStatusMessage()); TERN_(DWIN_CREALITY_LCD_JYERSUI, CrealityDWIN.Update_Status(status_message)); } @@ -1697,9 +1718,7 @@ void MarlinUI::init() { } } - #if PIN_EXISTS(SD_DETECT) && DISABLED(NO_LCD_REINIT) - init_lcd(); // Revive a noisy shared SPI LCD - #endif + reinit_lcd(); // Revive a noisy shared SPI LCD refresh(); diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index 5885866e5bd63..83eb332105d65 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -57,7 +57,7 @@ #if ENABLED(DWIN_CREALITY_LCD) #include "e3v2/creality/dwin.h" -#elif ENABLED(DWIN_CREALITY_LCD_ENHANCED) +#elif ENABLED(DWIN_LCD_PROUI) #include "e3v2/proui/dwin.h" #endif @@ -209,6 +209,8 @@ class MarlinUI { static void init_lcd() {} #endif + static void reinit_lcd() { TERN_(REINIT_NOISY_LCD, init_lcd()); } + #if HAS_WIRED_LCD static bool detected(); #else @@ -273,6 +275,14 @@ class MarlinUI { FORCE_INLINE static void refresh_brightness() { set_brightness(brightness); } #endif + #if LCD_BACKLIGHT_TIMEOUT + #define LCD_BKL_TIMEOUT_MIN 1 + #define LCD_BKL_TIMEOUT_MAX (60*60*18) // 18 hours max within uint16_t + static uint16_t lcd_backlight_timeout; + static millis_t backlight_off_ms; + static void refresh_backlight_timeout(); + #endif + #if HAS_DWIN_E3V2_BASIC static void refresh(); #else @@ -323,7 +333,7 @@ class MarlinUI { #if HAS_STATUS_MESSAGE - #if EITHER(HAS_WIRED_LCD, DWIN_CREALITY_LCD_ENHANCED) + #if EITHER(HAS_WIRED_LCD, DWIN_LCD_PROUI) #if ENABLED(STATUS_MESSAGE_SCROLLING) #define MAX_MESSAGE_LENGTH _MAX(LONG_FILENAME_LENGTH, MAX_LANG_CHARSIZE * 2 * (LCD_WIDTH)) #else @@ -357,15 +367,6 @@ class MarlinUI { static void set_status(FSTR_P const fstr, const int8_t level=0); static void status_printf(const uint8_t level, FSTR_P const fmt, ...); - #if EITHER(HAS_DISPLAY, DWIN_CREALITY_LCD_ENHANCED) - static void kill_screen(FSTR_P const lcd_error, FSTR_P const lcd_component); - #if DISABLED(LIGHTWEIGHT_UI) - static void draw_status_message(const bool blink); - #endif - #else - static void kill_screen(FSTR_P const, FSTR_P const) {} - #endif - #if HAS_DISPLAY static void update(); @@ -479,11 +480,16 @@ class MarlinUI { #endif static void draw_kill_screen(); + static void kill_screen(FSTR_P const lcd_error, FSTR_P const lcd_component); + #if DISABLED(LIGHTWEIGHT_UI) + static void draw_status_message(const bool blink); + #endif #else // No LCD static void update() {} static void return_to_status() {} + static void kill_screen(FSTR_P const, FSTR_P const) {} #endif @@ -609,7 +615,7 @@ class MarlinUI { static bool use_click() { return false; } #endif - #if ENABLED(ADVANCED_PAUSE_FEATURE) && ANY(HAS_MARLINUI_MENU, EXTENSIBLE_UI, DWIN_CREALITY_LCD_ENHANCED, DWIN_CREALITY_LCD_JYERSUI) + #if ENABLED(ADVANCED_PAUSE_FEATURE) && ANY(HAS_MARLINUI_MENU, EXTENSIBLE_UI, DWIN_LCD_PROUI, DWIN_CREALITY_LCD_JYERSUI) static void pause_show_message(const PauseMessage message, const PauseMode mode=PAUSE_MODE_SAME, const uint8_t extruder=active_extruder); #else static void _pause_show_message() {} diff --git a/Marlin/src/lcd/menu/menu.cpp b/Marlin/src/lcd/menu/menu.cpp index 2dca6c1b826ce..52c43ec5e90fb 100644 --- a/Marlin/src/lcd/menu/menu.cpp +++ b/Marlin/src/lcd/menu/menu.cpp @@ -276,11 +276,7 @@ void scroll_screen(const uint8_t limit, const bool is_menu) { #if HAS_BUZZER void MarlinUI::completion_feedback(const bool good/*=true*/) { TERN_(HAS_TOUCH_SLEEP, wakeup_screen()); // Wake up on rotary encoder click... - if (good) { - BUZZ(100, 659); - BUZZ(100, 698); - } - else BUZZ(20, 440); + if (good) OKAY_BUZZ(); else ERR_BUZZ(); } #endif diff --git a/Marlin/src/lcd/menu/menu.h b/Marlin/src/lcd/menu/menu.h index 72826262f456a..b111236d69cde 100644 --- a/Marlin/src/lcd/menu/menu.h +++ b/Marlin/src/lcd/menu/menu.h @@ -114,8 +114,8 @@ class MenuItem_confirm : public MenuItemBase { selectFunc_t yesFunc, selectFunc_t noFunc, PGM_P const pref, FSTR_P const string, PGM_P const suff=nullptr ) { - char str[strlen_P((PGM_P)string) + 1]; - strcpy_P(str, (PGM_P)string); + char str[strlen_P(FTOP(string)) + 1]; + strcpy_P(str, FTOP(string)); select_screen(yes, no, yesFunc, noFunc, pref, str, suff); } // Shortcut for prompt with "NO"/ "YES" labels diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index d2c9b30c04d4d..1bc9b9e88ed83 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -523,7 +523,7 @@ void menu_advanced_steps_per_mm() { START_MENU(); BACK_ITEM(MSG_ADVANCED_SETTINGS); - #define EDIT_QSTEPS(Q) EDIT_ITEM_FAST(float51, MSG_##Q##_STEPS, &planner.settings.axis_steps_per_mm[_AXIS(Q)], 5, 9999, []{ planner.refresh_positioning(); }) + #define EDIT_QSTEPS(Q) EDIT_ITEM_FAST(float61, MSG_##Q##_STEPS, &planner.settings.axis_steps_per_mm[_AXIS(Q)], 5, 9999, []{ planner.refresh_positioning(); }) LINEAR_AXIS_CODE( EDIT_QSTEPS(A), EDIT_QSTEPS(B), EDIT_QSTEPS(C), EDIT_QSTEPS(I), EDIT_QSTEPS(J), EDIT_QSTEPS(K) @@ -531,7 +531,7 @@ void menu_advanced_steps_per_mm() { #if ENABLED(DISTINCT_E_FACTORS) LOOP_L_N(n, E_STEPPERS) - EDIT_ITEM_FAST_N(float51, n, MSG_EN_STEPS, &planner.settings.axis_steps_per_mm[E_AXIS_N(n)], 5, 9999, []{ + EDIT_ITEM_FAST_N(float61, n, MSG_EN_STEPS, &planner.settings.axis_steps_per_mm[E_AXIS_N(n)], 5, 9999, []{ const uint8_t e = MenuItemBase::itemIndex; if (e == active_extruder) planner.refresh_positioning(); @@ -539,7 +539,7 @@ void menu_advanced_steps_per_mm() { planner.mm_per_step[E_AXIS_N(e)] = 1.0f / planner.settings.axis_steps_per_mm[E_AXIS_N(e)]; }); #elif E_STEPPERS - EDIT_ITEM_FAST(float51, MSG_E_STEPS, &planner.settings.axis_steps_per_mm[E_AXIS], 5, 9999, []{ planner.refresh_positioning(); }); + EDIT_ITEM_FAST(float61, MSG_E_STEPS, &planner.settings.axis_steps_per_mm[E_AXIS], 5, 9999, []{ planner.refresh_positioning(); }); #endif END_MENU(); diff --git a/Marlin/src/lcd/menu/menu_backlash.cpp b/Marlin/src/lcd/menu/menu_backlash.cpp index 5776234f72dcc..faed8cf777639 100644 --- a/Marlin/src/lcd/menu/menu_backlash.cpp +++ b/Marlin/src/lcd/menu/menu_backlash.cpp @@ -36,14 +36,20 @@ void menu_backlash() { START_MENU(); BACK_ITEM(MSG_MAIN); - EDIT_ITEM_FAST(percent, MSG_BACKLASH_CORRECTION, &backlash.correction, all_off, all_on); + editable.uint8 = backlash.get_correction_uint8(); + EDIT_ITEM_FAST(percent, MSG_BACKLASH_CORRECTION, &editable.uint8, backlash.all_off, backlash.all_on, []{ backlash.set_correction_uint8(editable.uint8); }); #if DISABLED(CORE_BACKLASH) || EITHER(MARKFORGED_XY, MARKFORGED_YX) #define _CAN_CALI AXIS_CAN_CALIBRATE #else #define _CAN_CALI(A) true #endif - #define EDIT_BACKLASH_DISTANCE(N) EDIT_ITEM_FAST(float43, MSG_BACKLASH_##N, &backlash.distance_mm[_AXIS(N)], 0.0f, 9.9f); + + #define EDIT_BACKLASH_DISTANCE(N) do { \ + editable.decimal = backlash.get_distance_mm(_AXIS(N)); \ + EDIT_ITEM_FAST(float43, MSG_BACKLASH_##N, &editable.decimal, 0.0f, 9.9f, []{ backlash.set_distance_mm(_AXIS(N), editable.decimal); }); \ + } while (0); + if (_CAN_CALI(A)) EDIT_BACKLASH_DISTANCE(A); #if HAS_Y_AXIS && _CAN_CALI(B) EDIT_BACKLASH_DISTANCE(B); @@ -62,7 +68,8 @@ void menu_backlash() { #endif #ifdef BACKLASH_SMOOTHING_MM - EDIT_ITEM_FAST(float43, MSG_BACKLASH_SMOOTHING, &backlash.smoothing_mm, 0.0f, 9.9f); + editable.decimal = backlash.get_smoothing_mm(); + EDIT_ITEM_FAST(float43, MSG_BACKLASH_SMOOTHING, &editable.decimal, 0.0f, 9.9f, []{ backlash.set_smoothing_mm(editable.decimal); }); #endif END_MENU(); diff --git a/Marlin/src/lcd/menu/menu_configuration.cpp b/Marlin/src/lcd/menu/menu_configuration.cpp index 33e43b08ebda1..b4e9287bd4a34 100644 --- a/Marlin/src/lcd/menu/menu_configuration.cpp +++ b/Marlin/src/lcd/menu/menu_configuration.cpp @@ -541,6 +541,10 @@ void menu_configuration() { #if HAS_LCD_CONTRAST && LCD_CONTRAST_MIN < LCD_CONTRAST_MAX EDIT_ITEM_FAST(uint8, MSG_CONTRAST, &ui.contrast, LCD_CONTRAST_MIN, LCD_CONTRAST_MAX, ui.refresh_contrast, true); #endif + #if LCD_BACKLIGHT_TIMEOUT && LCD_BKL_TIMEOUT_MIN < LCD_BKL_TIMEOUT_MAX + EDIT_ITEM(uint16_4, MSG_LCD_BKL_TIMEOUT, &ui.lcd_backlight_timeout, LCD_BKL_TIMEOUT_MIN, LCD_BKL_TIMEOUT_MAX, ui.refresh_backlight_timeout); + #endif + #if ENABLED(FWRETRACT) SUBMENU(MSG_RETRACT, menu_config_retract); #endif diff --git a/Marlin/src/lcd/menu/menu_item.h b/Marlin/src/lcd/menu/menu_item.h index 1834b56a88759..fcde9f5801939 100644 --- a/Marlin/src/lcd/menu/menu_item.h +++ b/Marlin/src/lcd/menu/menu_item.h @@ -150,7 +150,7 @@ DEFINE_MENU_EDIT_ITEM_TYPE(float43 ,float ,ftostr43sign ,1000 ); DEFINE_MENU_EDIT_ITEM_TYPE(float4 ,float ,ftostr4sign , 1 ); // 1234 right-justified DEFINE_MENU_EDIT_ITEM_TYPE(float5 ,float ,ftostr5rj , 1 ); // 12345 right-justified DEFINE_MENU_EDIT_ITEM_TYPE(float5_25 ,float ,ftostr5rj , 0.04f ); // 12345 right-justified (25 increment) -DEFINE_MENU_EDIT_ITEM_TYPE(float51 ,float ,ftostr51rj , 10 ); // 1234.5 right-justified +DEFINE_MENU_EDIT_ITEM_TYPE(float61 ,float ,ftostr61rj , 10 ); // 12345.6 right-justified DEFINE_MENU_EDIT_ITEM_TYPE(float31sign ,float ,ftostr31sign , 10 ); // +12.3 DEFINE_MENU_EDIT_ITEM_TYPE(float41sign ,float ,ftostr41sign , 10 ); // +123.4 DEFINE_MENU_EDIT_ITEM_TYPE(float51sign ,float ,ftostr51sign , 10 ); // +1234.5 diff --git a/Marlin/src/lcd/menu/menu_probe_offset.cpp b/Marlin/src/lcd/menu/menu_probe_offset.cpp index ae785fa641cbc..79db47005d0a4 100644 --- a/Marlin/src/lcd/menu/menu_probe_offset.cpp +++ b/Marlin/src/lcd/menu/menu_probe_offset.cpp @@ -62,7 +62,7 @@ void probe_offset_wizard_menu() { if (LCD_HEIGHT >= 4) STATIC_ITEM(MSG_MOVE_NOZZLE_TO_BED, SS_CENTER|SS_INVERT); - STATIC_ITEM_P(PSTR("Z="), SS_CENTER, ftostr42_52(current_position.z)); + STATIC_ITEM_P(PSTR("Z"), SS_CENTER, ftostr42_52(current_position.z)); STATIC_ITEM(MSG_ZPROBE_ZOFFSET, SS_LEFT, ftostr42_52(calculated_z_offset)); SUBMENU(MSG_MOVE_1MM, []{ _goto_manual_move_z( 1); }); diff --git a/Marlin/src/lcd/menu/menu_x_twist.cpp b/Marlin/src/lcd/menu/menu_x_twist.cpp index 288f16603a886..ce46053dfc346 100644 --- a/Marlin/src/lcd/menu/menu_x_twist.cpp +++ b/Marlin/src/lcd/menu/menu_x_twist.cpp @@ -27,6 +27,7 @@ #include "menu_addon.h" #include "../../module/planner.h" #include "../../feature/bedlevel/bedlevel.h" +#include "../../feature/x_twist.h" #include "../../module/motion.h" #include "../../gcode/queue.h" #include "../../module/probe.h" @@ -77,7 +78,7 @@ void xatc_wizard_update_z_offset() { // void xatc_wizard_set_offset_and_go_to_next_point() { // Set Z-offset at probed point - xatc.z_values[manual_probe_index++] = probe.offset.z + current_position.z - measured_z; + xatc.z_offset[manual_probe_index++] = probe.offset.z + current_position.z - measured_z; // Go to next point ui.goto_screen(xatc_wizard_goto_next_point); } @@ -148,9 +149,11 @@ void xatc_wizard_goto_next_point() { // Deploy certain probes before starting probing TERN_(BLTOUCH, do_z_clearance(Z_CLEARANCE_DEPLOY_PROBE)); + xatc.set_enabled(false); measured_z = probe.probe_at_point(x, XATC_Y_POSITION, PROBE_PT_STOW); + xatc.set_enabled(true); current_position += probe.offset_xy; - current_position.z = XATC_START_Z - probe.offset.z + measured_z; + current_position.z = (XATC_START_Z) - probe.offset.z + measured_z; line_to_current_position(MMM_TO_MMS(XY_PROBE_FEEDRATE)); ui.wait_for_move = false; } @@ -160,12 +163,12 @@ void xatc_wizard_goto_next_point() { else { // Compute the z-offset by averaging the values found with this wizard z_offset = 0; - LOOP_L_N(i, XATC_MAX_POINTS) z_offset += xatc.z_values[i]; + LOOP_L_N(i, XATC_MAX_POINTS) z_offset += xatc.z_offset[i]; z_offset /= XATC_MAX_POINTS; // Subtract the average from the values found with this wizard. // This way they are indipendent from the z-offset - LOOP_L_N(i, XATC_MAX_POINTS) xatc.z_values[i] -= z_offset; + LOOP_L_N(i, XATC_MAX_POINTS) xatc.z_offset[i] -= z_offset; ui.goto_screen(xatc_wizard_update_z_offset); } @@ -186,8 +189,7 @@ void xatc_wizard_homing_done() { } if (ui.use_click()) { - xatc.spacing = (probe.max_x() - probe.min_x()) / (XATC_MAX_POINTS - 1); - xatc.start = probe.min_x(); + xatc.reset(); SET_SOFT_ENDSTOP_LOOSE(true); // Disable soft endstops for free Z movement diff --git a/Marlin/src/libs/buzzer.h b/Marlin/src/libs/buzzer.h index db5e3ee4ca795..9fc46ff6296c4 100644 --- a/Marlin/src/libs/buzzer.h +++ b/Marlin/src/libs/buzzer.h @@ -127,3 +127,8 @@ #define BUZZ(d,f) NOOP #endif + +#define ERR_BUZZ() BUZZ(400, 40); +#define ATTN_BUZZ() do{ BUZZ(198, 404); BUZZ(4, 0); BUZZ(198, 404); }while(0) +#define OKAY_BUZZ() do{ BUZZ(100, 659); BUZZ(10, 0); BUZZ(100, 698); }while(0) +#define DONE_BUZZ(OK) do{ if (OK) OKAY_BUZZ(); else ERR_BUZZ(); }while(0) diff --git a/Marlin/src/libs/nozzle.cpp b/Marlin/src/libs/nozzle.cpp index e277216ab4e57..4ca8fa2cae1e0 100644 --- a/Marlin/src/libs/nozzle.cpp +++ b/Marlin/src/libs/nozzle.cpp @@ -254,11 +254,18 @@ Nozzle nozzle; break; } - do_blocking_move_to_xy( - TERN(NOZZLE_PARK_Y_ONLY, current_position, park).x, - TERN(NOZZLE_PARK_X_ONLY, current_position, park).y, - fr_xy - ); + #ifndef NOZZLE_PARK_MOVE + #define NOZZLE_PARK_MOVE 0 + #endif + switch (NOZZLE_PARK_MOVE) { + case 0: do_blocking_move_to_xy(park, fr_xy); break; + case 1: do_blocking_move_to_x(park.x, fr_xy); break; + case 2: do_blocking_move_to_y(park.y, fr_xy); break; + case 3: do_blocking_move_to_x(park.x, fr_xy); + do_blocking_move_to_y(park.y, fr_xy); break; + case 4: do_blocking_move_to_y(park.y, fr_xy); + do_blocking_move_to_x(park.x, fr_xy); break; + } report_current_position(); } diff --git a/Marlin/src/libs/numtostr.cpp b/Marlin/src/libs/numtostr.cpp index 1e1ac05710122..f4d47983d2252 100644 --- a/Marlin/src/libs/numtostr.cpp +++ b/Marlin/src/libs/numtostr.cpp @@ -377,10 +377,10 @@ const char* ftostr53sign(const_float_t f) { return conv; } -// Convert unsigned float to string with ____4.5, __34.5, _234.5, 1234.5 format -const char* ftostr51rj(const_float_t f) { +// Convert unsigned float to string with ____5.6, ___45.6, __345.6, _2345.6, 12345.6 format +const char* ftostr61rj(const_float_t f) { const long i = UINTFLOAT(f, 1); - conv[0] = ' '; + conv[0] = RJDIGIT(i, 100000); conv[1] = RJDIGIT(i, 10000); conv[2] = RJDIGIT(i, 1000); conv[3] = RJDIGIT(i, 100); diff --git a/Marlin/src/libs/numtostr.h b/Marlin/src/libs/numtostr.h index b058f3cdf6c6d..1704d35e889d8 100644 --- a/Marlin/src/libs/numtostr.h +++ b/Marlin/src/libs/numtostr.h @@ -113,8 +113,8 @@ const char* ftostr52sign(const_float_t x); // Convert signed float to string with +12.345 format const char* ftostr53sign(const_float_t f); -// Convert unsigned float to string with 1234.5 format omitting trailing zeros -const char* ftostr51rj(const_float_t x); +// Convert unsigned float to string with 12345.6 format omitting trailing zeros +const char* ftostr61rj(const_float_t x); // Convert float to rj string with 123 or -12 format FORCE_INLINE const char* ftostr3(const_float_t x) { return i16tostr3rj(int16_t(x + (x < 0 ? -0.5f : 0.5f))); } diff --git a/Marlin/src/libs/vector_3.cpp b/Marlin/src/libs/vector_3.cpp index 614d2121b8934..02945fe6871a5 100644 --- a/Marlin/src/libs/vector_3.cpp +++ b/Marlin/src/libs/vector_3.cpp @@ -141,8 +141,7 @@ void matrix_3x3::debug(FSTR_P const title) { if (title) SERIAL_ECHOLNF(title); LOOP_L_N(i, 3) { LOOP_L_N(j, 3) { - if (vectors[i][j] >= 0.0) SERIAL_CHAR('+'); - SERIAL_ECHO_F(vectors[i][j], 6); + serial_offset(vectors[i][j], 2); SERIAL_CHAR(' '); } SERIAL_EOL(); diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index bce27dc88a159..3dd6d8aeb6855 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -1348,7 +1348,7 @@ void Endstops::update() { ES_REPORT_CHANGE(K_MAX); #endif SERIAL_ECHOLNPGM("\n"); - set_pwm_duty(pin_t(LED_PIN), local_LED_status); + hal.set_pwm_duty(pin_t(LED_PIN), local_LED_status); local_LED_status ^= 255; old_live_state_local = live_state_local; } diff --git a/Marlin/src/module/motion.h b/Marlin/src/module/motion.h index ca206bf89ac4e..1dd6d8c4ede22 100644 --- a/Marlin/src/module/motion.h +++ b/Marlin/src/module/motion.h @@ -265,9 +265,11 @@ void report_current_position_projected(); void report_current_position_moving(); #if ENABLED(FULL_REPORT_TO_HOST_FEATURE) - inline void set_and_report_grblstate(const M_StateEnum state) { - M_State_grbl = state; - report_current_grblstate_moving(); + inline void set_and_report_grblstate(const M_StateEnum state, const bool force=true) { + if (force || M_State_grbl != state) { + M_State_grbl = state; + report_current_grblstate_moving(); + } } #endif diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 8d8f44dc7805b..51440aac262e4 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -703,7 +703,7 @@ void Planner::init() { // All other 32-bit MPUs can easily do inverse using hardware division, // so we don't need to reduce precision or to use assembly language at all. // This routine, for all other archs, returns 0x100000000 / d ~= 0xFFFFFFFF / d - static FORCE_INLINE uint32_t get_period_inverse(const uint32_t d) { + FORCE_INLINE static uint32_t get_period_inverse(const uint32_t d) { return d ? 0xFFFFFFFF / d : 0xFFFFFFFF; } #endif @@ -1260,7 +1260,7 @@ void Planner::recalculate() { #if ENABLED(FAN_SOFT_PWM) #define _FAN_SET(F) thermalManager.soft_pwm_amount_fan[F] = CALC_FAN_SPEED(F); #else - #define _FAN_SET(F) set_pwm_duty(pin_t(FAN##F##_PIN), CALC_FAN_SPEED(F)); + #define _FAN_SET(F) hal.set_pwm_duty(pin_t(FAN##F##_PIN), CALC_FAN_SPEED(F)); #endif #define FAN_SET(F) do{ kickstart_fan(fan_speed, ms, F); _FAN_SET(F); }while(0) @@ -1397,8 +1397,8 @@ void Planner::check_axes_activity() { TERN_(AUTOTEMP, autotemp_task()); #if ENABLED(BARICUDA) - TERN_(HAS_HEATER_1, set_pwm_duty(pin_t(HEATER_1_PIN), tail_valve_pressure)); - TERN_(HAS_HEATER_2, set_pwm_duty(pin_t(HEATER_2_PIN), tail_e_to_p_pressure)); + TERN_(HAS_HEATER_1, hal.set_pwm_duty(pin_t(HEATER_1_PIN), tail_valve_pressure)); + TERN_(HAS_HEATER_2, hal.set_pwm_duty(pin_t(HEATER_2_PIN), tail_e_to_p_pressure)); #endif } @@ -1706,7 +1706,8 @@ void Planner::endstop_triggered(const AxisEnum axis) { } float Planner::triggered_position_mm(const AxisEnum axis) { - return stepper.triggered_position(axis) * mm_per_step[axis]; + const float result = DIFF_TERN(BACKLASH_COMPENSATION, stepper.triggered_position(axis), backlash.get_applied_steps(axis)); + return result * mm_per_step[axis]; } void Planner::finish_and_disable() { @@ -1728,8 +1729,8 @@ float Planner::get_axis_position_mm(const AxisEnum axis) { // 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); + const int32_t p1 = DIFF_TERN(BACKLASH_COMPENSATION, stepper.position(CORE_AXIS_1), backlash.get_applied_steps(CORE_AXIS_1)), + p2 = DIFF_TERN(BACKLASH_COMPENSATION, stepper.position(CORE_AXIS_2), backlash.get_applied_steps(CORE_AXIS_2)); if (was_enabled) stepper.wake_up(); @@ -1738,7 +1739,7 @@ float Planner::get_axis_position_mm(const AxisEnum axis) { axis_steps = (axis == CORE_AXIS_2 ? CORESIGN(p1 - p2) : p1 + p2) * 0.5f; } else - axis_steps = stepper.position(axis); + axis_steps = DIFF_TERN(BACKLASH_COMPENSATION, stepper.position(axis), backlash.get_applied_steps(axis)); #elif EITHER(MARKFORGED_XY, MARKFORGED_YX) @@ -1755,11 +1756,12 @@ float Planner::get_axis_position_mm(const AxisEnum axis) { axis_steps = ((axis == CORE_AXIS_1) ? p1 - p2 : p2); } else - axis_steps = stepper.position(axis); + axis_steps = DIFF_TERN(BACKLASH_COMPENSATION, stepper.position(axis), backlash.get_applied_steps(axis)); #else axis_steps = stepper.position(axis); + TERN_(BACKLASH_COMPENSATION, axis_steps -= backlash.get_applied_steps(axis)); #endif @@ -2809,9 +2811,13 @@ bool Planner::_populate_block(block_t * const block, bool split_move, position = target; // Update the position + #if ENABLED(POWER_LOSS_RECOVERY) + block->sdpos = recovery.command_sdpos(); + block->start_position = position_float.asLogical(); + #endif + TERN_(HAS_POSITION_FLOAT, position_float = target_float); TERN_(GRADIENT_MIX, mixer.gradient_control(target_float.z)); - TERN_(POWER_LOSS_RECOVERY, block->sdpos = recovery.command_sdpos()); return true; // Movement was accepted @@ -2837,6 +2843,9 @@ void Planner::buffer_sync_block(TERN_(LASER_SYNCHRONOUS_M106_M107, uint8_t sync_ block->flag = sync_flag; block->position = position; + #if ENABLED(BACKLASH_COMPENSATION) + LOOP_LINEAR_AXES(axis) block->position[axis] += backlash.get_applied_steps((AxisEnum)axis); + #endif #if BOTH(HAS_FAN, LASER_SYNCHRONOUS_M106_M107) FANS_LOOP(i) block->fan_speed[i] = thermalManager.fan_speed[i]; @@ -3104,13 +3113,21 @@ void Planner::set_machine_position_mm(const abce_pos_t &abce) { LROUND(abce.k * settings.axis_steps_per_mm[K_AXIS]) ) ); + if (has_blocks_queued()) { //previous_nominal_speed_sqr = 0.0; // Reset planner junction speeds. Assume start from rest. //previous_speed.reset(); buffer_sync_block(); } - else - stepper.set_position(position); + else { + #if ENABLED(BACKLASH_COMPENSATION) + abce_long_t stepper_pos = position; + LOOP_LINEAR_AXES(axis) stepper_pos[axis] += backlash.get_applied_steps((AxisEnum)axis); + stepper.set_position(stepper_pos); + #else + stepper.set_position(position); + #endif + } } void Planner::set_position_mm(const xyze_pos_t &xyze) { diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index 380c35755c964..f29604bea86ae 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -244,6 +244,7 @@ typedef struct block_t { #if ENABLED(POWER_LOSS_RECOVERY) uint32_t sdpos; + xyze_pos_t start_position; #endif #if ENABLED(LASER_POWER_INLINE) @@ -252,7 +253,7 @@ typedef struct block_t { } block_t; -#if ANY(LIN_ADVANCE, SCARA_FEEDRATE_SCALING, GRADIENT_MIX, LCD_SHOW_E_TOTAL) +#if ANY(LIN_ADVANCE, SCARA_FEEDRATE_SCALING, GRADIENT_MIX, LCD_SHOW_E_TOTAL, POWER_LOSS_RECOVERY) #define HAS_POSITION_FLOAT 1 #endif diff --git a/Marlin/src/module/printcounter.cpp b/Marlin/src/module/printcounter.cpp index affb6087802c2..c35b722cf4c66 100644 --- a/Marlin/src/module/printcounter.cpp +++ b/Marlin/src/module/printcounter.cpp @@ -151,7 +151,7 @@ void PrintCounter::loadStats() { if (data.nextService3 == 0) doBuzz = _service_warn(PSTR(" " SERVICE_NAME_3)); #endif #if HAS_BUZZER && SERVICE_WARNING_BUZZES > 0 - if (doBuzz) for (int i = 0; i < SERVICE_WARNING_BUZZES; i++) BUZZ(200, 404); + if (doBuzz) for (int i = 0; i < SERVICE_WARNING_BUZZES; i++) { BUZZ(200, 404); BUZZ(10, 0); } #else UNUSED(doBuzz); #endif diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index fdd6897192a2a..ee6323518a2f4 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -77,9 +77,17 @@ #include "servo.h" #endif +#if HAS_PTC + #include "../feature/probe_temp_comp.h" +#endif + +#if ENABLED(X_AXIS_TWIST_COMPENSATION) + #include "../feature/x_twist.h" +#endif + #if ENABLED(EXTENSIBLE_UI) #include "../lcd/extui/ui_api.h" -#elif ENABLED(DWIN_CREALITY_LCD_ENHANCED) +#elif ENABLED(DWIN_LCD_PROUI) #include "../lcd/e3v2/proui/dwin.h" #endif @@ -298,8 +306,7 @@ FORCE_INLINE void probe_specific_action(const bool deploy) { if (deploy != PROBE_TRIGGERED()) break; #endif - BUZZ(100, 659); - BUZZ(100, 698); + OKAY_BUZZ(); FSTR_P const ds_str = deploy ? GET_TEXT_F(MSG_MANUAL_DEPLOY) : GET_TEXT_F(MSG_MANUAL_STOW); ui.return_to_status(); // To display the new status message @@ -308,7 +315,7 @@ FORCE_INLINE void probe_specific_action(const bool deploy) { TERN_(HOST_PROMPT_SUPPORT, hostui.prompt_do(PROMPT_USER_CONTINUE, F("Stow Probe"), FPSTR(CONTINUE_STR))); TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired(F("Stow Probe"))); - TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_Popup_Confirm(ICON_BLTouch, F("Stow Probe"), FPSTR(CONTINUE_STR))); + TERN_(DWIN_LCD_PROUI, DWIN_Popup_Confirm(ICON_BLTouch, F("Stow Probe"), FPSTR(CONTINUE_STR))); TERN_(HAS_RESUME_CONTINUE, wait_for_user_response()); ui.reset_status(); @@ -801,7 +808,11 @@ float Probe::probe_at_point(const_float_t rx, const_float_t ry, const ProbePtRai do_blocking_move_to(npos, feedRate_t(XY_PROBE_FEEDRATE_MM_S)); float measured_z = NAN; - if (!deploy()) measured_z = run_z_probe(sanity_check) + offset.z; + if (!deploy()) { + measured_z = run_z_probe(sanity_check) + offset.z; + TERN_(HAS_PTC, ptc.apply_compensation(measured_z)); + TERN_(X_AXIS_TWIST_COMPENSATION, measured_z += xatc.compensation(npos + offset_xy)); + } if (!isnan(measured_z)) { const bool big_raise = raise_after == PROBE_PT_BIG_RAISE; if (big_raise || raise_after == PROBE_PT_RAISE) diff --git a/Marlin/src/module/servo.cpp b/Marlin/src/module/servo.cpp index 231efe84e1f2c..96d5ba9da837e 100644 --- a/Marlin/src/module/servo.cpp +++ b/Marlin/src/module/servo.cpp @@ -30,7 +30,7 @@ #include "servo.h" -HAL_SERVO_LIB servo[NUM_SERVOS]; +hal_servo_t servo[NUM_SERVOS]; #if ENABLED(EDITABLE_SERVO_ANGLES) uint16_t servo_angles[NUM_SERVOS][2]; diff --git a/Marlin/src/module/servo.h b/Marlin/src/module/servo.h index 73dbbdddb7297..cd55a317a2751 100644 --- a/Marlin/src/module/servo.h +++ b/Marlin/src/module/servo.h @@ -112,5 +112,5 @@ #define MOVE_SERVO(I, P) servo[I].move(P) #define DETACH_SERVO(I) servo[I].detach() -extern HAL_SERVO_LIB servo[NUM_SERVOS]; +extern hal_servo_t servo[NUM_SERVOS]; void servo_init(); diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index 8c2cd8813d6c7..6eb17d5d2e84d 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -64,7 +64,7 @@ #if HAS_LEVELING #include "../feature/bedlevel/bedlevel.h" #if ENABLED(X_AXIS_TWIST_COMPENSATION) - #include "../feature/bedlevel/abl/x_twist.h" + #include "../feature/x_twist.h" #endif #endif @@ -74,7 +74,7 @@ #if ENABLED(EXTENSIBLE_UI) #include "../lcd/extui/ui_api.h" -#elif ENABLED(DWIN_CREALITY_LCD_ENHANCED) +#elif ENABLED(DWIN_LCD_PROUI) #include "../lcd/e3v2/proui/dwin.h" #elif ENABLED(DWIN_CREALITY_LCD_JYERSUI) #include "../lcd/e3v2/jyersui/dwin.h" @@ -269,13 +269,17 @@ typedef struct SettingsDataStruct { xy_pos_t bilinear_grid_spacing, bilinear_start; // G29 L F #if ENABLED(AUTO_BED_LEVELING_BILINEAR) bed_mesh_t z_values; // G29 - #if ENABLED(X_AXIS_TWIST_COMPENSATION) - XATC xatc; // TBD - #endif #else float z_values[3][3]; #endif + // + // X_AXIS_TWIST_COMPENSATION + // + #if ENABLED(X_AXIS_TWIST_COMPENSATION) + XATC xatc; // M423 X Z + #endif + // // AUTO_BED_LEVELING_UBL // @@ -298,7 +302,7 @@ typedef struct SettingsDataStruct { int16_t z_offsets_bed[COUNT(ptc.z_offsets_bed)]; // M871 B I V #endif #if ENABLED(PTC_HOTEND) - int16_t z_offsets_hotend[COUNT(ptc.z_offsets_hotend)]; // M871 E I V + int16_t z_offsets_hotend[COUNT(ptc.z_offsets_hotend)]; // M871 E I V #endif #endif @@ -337,11 +341,11 @@ typedef struct SettingsDataStruct { #endif // - // Z_STEPPER_AUTO_ALIGN, Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS + // Z_STEPPER_AUTO_ALIGN, HAS_Z_STEPPER_ALIGN_STEPPER_XY // #if ENABLED(Z_STEPPER_AUTO_ALIGN) xy_pos_t z_stepper_align_xy[NUM_Z_STEPPER_DRIVERS]; // M422 S X Y - #if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) + #if HAS_Z_STEPPER_ALIGN_STEPPER_XY xy_pos_t z_stepper_align_stepper_xy[NUM_Z_STEPPER_DRIVERS]; // M422 W X Y #endif #endif @@ -391,6 +395,13 @@ typedef struct SettingsDataStruct { // uint8_t lcd_brightness; // M256 B + // + // LCD_BACKLIGHT_TIMEOUT + // + #if LCD_BACKLIGHT_TIMEOUT + uint16_t lcd_backlight_timeout; // (G-code needed) + #endif + // // Controller fan settings // @@ -476,7 +487,7 @@ typedef struct SettingsDataStruct { // // Ender-3 V2 DWIN // - #if ENABLED(DWIN_CREALITY_LCD_ENHANCED) + #if ENABLED(DWIN_LCD_PROUI) uint8_t dwin_data[eeprom_data_size]; #elif ENABLED(DWIN_CREALITY_LCD_JYERSUI) uint8_t dwin_settings[CrealityDWIN.eeprom_data_size]; @@ -607,6 +618,10 @@ void MarlinSettings::postprocess() { // Moved as last update due to interference with Neopixel init TERN_(HAS_LCD_CONTRAST, ui.refresh_contrast()); TERN_(HAS_LCD_BRIGHTNESS, ui.refresh_brightness()); + + #if LCD_BACKLIGHT_TIMEOUT + ui.refresh_backlight_timeout(); + #endif } #if BOTH(PRINTCOUNTER, EEPROM_SETTINGS) @@ -862,12 +877,6 @@ void MarlinSettings::postprocess() { sizeof(z_values) == (GRID_MAX_POINTS) * sizeof(z_values[0][0]), "Bilinear Z array is the wrong size." ); - #if ENABLED(X_AXIS_TWIST_COMPENSATION) - static_assert( - sizeof(xatc.z_values) == (XATC_MAX_POINTS) * sizeof(xatc.z_values[0]), - "Z-offset mesh is the wrong size." - ); - #endif #else const xy_pos_t bilinear_start{0}, bilinear_grid_spacing{0}; #endif @@ -881,15 +890,22 @@ void MarlinSettings::postprocess() { #if ENABLED(AUTO_BED_LEVELING_BILINEAR) EEPROM_WRITE(z_values); // 9-256 floats - #if ENABLED(X_AXIS_TWIST_COMPENSATION) - EEPROM_WRITE(xatc); - #endif #else dummyf = 0; for (uint16_t q = grid_max_x * grid_max_y; q--;) EEPROM_WRITE(dummyf); #endif } + // + // X Axis Twist Compensation + // + #if ENABLED(X_AXIS_TWIST_COMPENSATION) + _FIELD_TEST(xatc); + EEPROM_WRITE(xatc.spacing); + EEPROM_WRITE(xatc.start); + EEPROM_WRITE(xatc.z_offset); + #endif + // // Unified Bed Leveling // @@ -991,7 +1007,7 @@ void MarlinSettings::postprocess() { #if ENABLED(Z_STEPPER_AUTO_ALIGN) EEPROM_WRITE(z_stepper_align.xy); - #if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) + #if HAS_Z_STEPPER_ALIGN_STEPPER_XY EEPROM_WRITE(z_stepper_align.stepper_xy); #endif #endif @@ -1111,6 +1127,13 @@ void MarlinSettings::postprocess() { EEPROM_WRITE(lcd_brightness); } + // + // LCD Backlight Timeout + // + #if LCD_BACKLIGHT_TIMEOUT + EEPROM_WRITE(ui.lcd_backlight_timeout); + #endif + // // Controller Fan // @@ -1411,14 +1434,15 @@ void MarlinSettings::postprocess() { // { #if ENABLED(BACKLASH_GCODE) - const xyz_float_t &backlash_distance_mm = backlash.distance_mm; - const uint8_t &backlash_correction = backlash.correction; + xyz_float_t backlash_distance_mm; + LOOP_LINEAR_AXES(axis) backlash_distance_mm[axis] = backlash.get_distance_mm((AxisEnum)axis); + const uint8_t backlash_correction = backlash.get_correction_uint8(); #else const xyz_float_t backlash_distance_mm{0}; const uint8_t backlash_correction = 0; #endif #if ENABLED(BACKLASH_GCODE) && defined(BACKLASH_SMOOTHING_MM) - const float &backlash_smoothing_mm = backlash.smoothing_mm; + const float backlash_smoothing_mm = backlash.get_smoothing_mm(); #else const float backlash_smoothing_mm = 3; #endif @@ -1443,18 +1467,20 @@ void MarlinSettings::postprocess() { // // Creality DWIN User Data // - #if ENABLED(DWIN_CREALITY_LCD_ENHANCED) + #if ENABLED(DWIN_LCD_PROUI) { + _FIELD_TEST(dwin_data); char dwin_data[eeprom_data_size] = { 0 }; DWIN_StoreSettings(dwin_data); - _FIELD_TEST(dwin_data); EEPROM_WRITE(dwin_data); } - #elif ENABLED(DWIN_CREALITY_LCD_JYERSUI) + #endif + + #if ENABLED(DWIN_CREALITY_LCD_JYERSUI) { + _FIELD_TEST(dwin_settings); char dwin_settings[CrealityDWIN.eeprom_data_size] = { 0 }; CrealityDWIN.Save_Settings(dwin_settings); - _FIELD_TEST(dwin_settings); EEPROM_WRITE(dwin_settings); } #endif @@ -1588,7 +1614,7 @@ void MarlinSettings::postprocess() { stored_ver[1] = '\0'; } DEBUG_ECHO_MSG("EEPROM version mismatch (EEPROM=", stored_ver, " Marlin=" EEPROM_VERSION ")"); - TERN_(DWIN_CREALITY_LCD_ENHANCED, LCD_MESSAGE(MSG_ERR_EEPROM_VERSION)); + TERN_(DWIN_LCD_PROUI, LCD_MESSAGE(MSG_ERR_EEPROM_VERSION)); TERN_(HOST_PROMPT_SUPPORT, hostui.notify(GET_TEXT_F(MSG_ERR_EEPROM_VERSION))); IF_DISABLED(EEPROM_AUTO_INIT, ui.eeprom_alert_version()); @@ -1769,9 +1795,6 @@ void MarlinSettings::postprocess() { EEPROM_READ(bilinear_grid_spacing); // 2 ints EEPROM_READ(bilinear_start); // 2 ints EEPROM_READ(z_values); // 9 to 256 floats - #if ENABLED(X_AXIS_TWIST_COMPENSATION) - EEPROM_READ(xatc); - #endif } else // EEPROM data is stale #endif // AUTO_BED_LEVELING_BILINEAR @@ -1784,6 +1807,16 @@ void MarlinSettings::postprocess() { } } + // + // X Axis Twist Compensation + // + #if ENABLED(X_AXIS_TWIST_COMPENSATION) + _FIELD_TEST(xatc); + EEPROM_READ(xatc.spacing); + EEPROM_READ(xatc.start); + EEPROM_READ(xatc.z_offset); + #endif + // // Unified Bed Leveling active state // @@ -1898,7 +1931,7 @@ void MarlinSettings::postprocess() { #if ENABLED(Z_STEPPER_AUTO_ALIGN) EEPROM_READ(z_stepper_align.xy); - #if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) + #if HAS_Z_STEPPER_ALIGN_STEPPER_XY EEPROM_READ(z_stepper_align.stepper_xy); #endif #endif @@ -2018,6 +2051,13 @@ void MarlinSettings::postprocess() { TERN_(HAS_LCD_BRIGHTNESS, if (!validating) ui.brightness = lcd_brightness); } + // + // LCD Backlight Timeout + // + #if LCD_BACKLIGHT_TIMEOUT + EEPROM_READ(ui.lcd_backlight_timeout); + #endif + // // Controller Fan // @@ -2342,22 +2382,22 @@ void MarlinSettings::postprocess() { // Backlash Compensation // { - #if ENABLED(BACKLASH_GCODE) - const xyz_float_t &backlash_distance_mm = backlash.distance_mm; - const uint8_t &backlash_correction = backlash.correction; - #else - xyz_float_t backlash_distance_mm; - uint8_t backlash_correction; - #endif - #if ENABLED(BACKLASH_GCODE) && defined(BACKLASH_SMOOTHING_MM) - const float &backlash_smoothing_mm = backlash.smoothing_mm; - #else - float backlash_smoothing_mm; - #endif + xyz_float_t backlash_distance_mm; + uint8_t backlash_correction; + float backlash_smoothing_mm; + _FIELD_TEST(backlash_distance_mm); EEPROM_READ(backlash_distance_mm); EEPROM_READ(backlash_correction); EEPROM_READ(backlash_smoothing_mm); + + #if ENABLED(BACKLASH_GCODE) + LOOP_LINEAR_AXES(axis) backlash.set_distance_mm((AxisEnum)axis, backlash_distance_mm[axis]); + backlash.set_correction_uint8(backlash_correction); + #ifdef BACKLASH_SMOOTHING_MM + backlash.set_smoothing_mm(backlash_smoothing_mm); + #endif + #endif } // @@ -2375,7 +2415,7 @@ void MarlinSettings::postprocess() { // // Creality DWIN User Data // - #if ENABLED(DWIN_CREALITY_LCD_ENHANCED) + #if ENABLED(DWIN_LCD_PROUI) { const char dwin_data[eeprom_data_size] = { 0 }; _FIELD_TEST(dwin_data); @@ -2479,7 +2519,7 @@ void MarlinSettings::postprocess() { else if (working_crc != stored_crc) { eeprom_error = true; DEBUG_ERROR_MSG("EEPROM CRC mismatch - (stored) ", stored_crc, " != ", working_crc, " (calculated)!"); - TERN_(DWIN_CREALITY_LCD_ENHANCED, LCD_MESSAGE(MSG_ERR_EEPROM_CRC)); + TERN_(DWIN_LCD_PROUI, LCD_MESSAGE(MSG_ERR_EEPROM_CRC)); TERN_(HOST_EEPROM_CHITCHAT, hostui.notify(GET_TEXT_F(MSG_ERR_EEPROM_CRC))); IF_DISABLED(EEPROM_AUTO_INIT, ui.eeprom_alert_crc()); } @@ -2789,15 +2829,15 @@ void MarlinSettings::reset() { #endif #if ENABLED(BACKLASH_GCODE) - backlash.correction = (BACKLASH_CORRECTION) * 255; + backlash.set_correction(BACKLASH_CORRECTION); constexpr xyz_float_t tmp = BACKLASH_DISTANCE_MM; - backlash.distance_mm = tmp; + LOOP_LINEAR_AXES(axis) backlash.set_distance_mm((AxisEnum)axis, tmp[axis]); #ifdef BACKLASH_SMOOTHING_MM - backlash.smoothing_mm = BACKLASH_SMOOTHING_MM; + backlash.set_smoothing_mm(BACKLASH_SMOOTHING_MM); #endif #endif - TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_SetDataDefaults()); + TERN_(DWIN_LCD_PROUI, DWIN_SetDataDefaults()); TERN_(DWIN_CREALITY_LCD_JYERSUI, CrealityDWIN.Reset_Settings()); // @@ -2826,6 +2866,14 @@ void MarlinSettings::reset() { TERN_(ENABLE_LEVELING_FADE_HEIGHT, new_z_fade_height = (DEFAULT_LEVELING_FADE_HEIGHT)); TERN_(HAS_LEVELING, reset_bed_level()); + // + // X Axis Twist Compensation + // + TERN_(X_AXIS_TWIST_COMPENSATION, xatc.reset()); + + // + // Nozzle-to-probe Offset + // #if HAS_BED_PROBE constexpr float dpo[] = NOZZLE_TO_PROBE_OFFSET; static_assert(COUNT(dpo) == LINEAR_AXES, "NOZZLE_TO_PROBE_OFFSET must contain offsets for each linear axis X, Y, Z...."); @@ -3043,6 +3091,13 @@ void MarlinSettings::reset() { // TERN_(HAS_LCD_BRIGHTNESS, ui.brightness = LCD_BRIGHTNESS_DEFAULT); + // + // LCD Backlight Timeout + // + #if LCD_BACKLIGHT_TIMEOUT + ui.lcd_backlight_timeout = LCD_BACKLIGHT_TIMEOUT; + #endif + // // Controller Fan // @@ -3155,9 +3210,11 @@ void MarlinSettings::reset() { postprocess(); - FSTR_P const hdsl = F("Hardcoded Default Settings Loaded"); - TERN_(HOST_EEPROM_CHITCHAT, hostui.notify(hdsl)); - DEBUG_ECHO_START(); DEBUG_ECHOLNF(hdsl); + #if EITHER(EEPROM_CHITCHAT, DEBUG_LEVELING_FEATURE) + FSTR_P const hdsl = F("Hardcoded Default Settings Loaded"); + TERN_(HOST_EEPROM_CHITCHAT, hostui.notify(hdsl)); + DEBUG_ECHO_START(); DEBUG_ECHOLNF(hdsl); + #endif TERN_(EXTENSIBLE_UI, ExtUI::onFactoryReset()); } @@ -3283,16 +3340,15 @@ void MarlinSettings::reset() { } } - // TODO: Create G-code for settings - //#if ENABLED(X_AXIS_TWIST_COMPENSATION) - // CONFIG_ECHO_START(); - // xatc.print_points(); - //#endif - #endif #endif // HAS_LEVELING + // + // X Axis Twist Compensation + // + TERN_(X_AXIS_TWIST_COMPENSATION, gcode.M423_report(forReplay)); + // // Editable Servo Angles // diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index ae8a1ef0784cf..f83104fe9c477 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -497,6 +497,9 @@ void Stepper::enable_axis(const AxisEnum axis) { bool Stepper::disable_axis(const AxisEnum axis) { mark_axis_disabled(axis); + + TERN_(DWIN_LCD_PROUI, set_axis_untrusted(axis)); // MRISCOC workaround: https://github.com/MarlinFirmware/Marlin/issues/23095 + // If all the axes that share the enabled bit are disabled const bool can_disable = can_axis_disable(axis); if (can_disable) { @@ -1474,7 +1477,7 @@ void Stepper::isr() { #ifndef __AVR__ // Disable interrupts, to avoid ISR preemption while we reprogram the period // (AVR enters the ISR with global interrupts disabled, so no need to do it here) - DISABLE_ISRS(); + hal.isr_off(); #endif // Program timer compare for the maximum period, so it does NOT @@ -1492,7 +1495,7 @@ void Stepper::isr() { hal_timer_t min_ticks; do { // Enable ISRs to reduce USART processing latency - ENABLE_ISRS(); + hal.isr_on(); if (!nextMainISR) pulse_phase_isr(); // 0 = Do coordinated axes Stepper pulses @@ -1576,7 +1579,7 @@ void Stepper::isr() { * is less than the current count due to something preempting between the * read and the write of the new period value). */ - DISABLE_ISRS(); + hal.isr_off(); /** * Get the current tick value + margin @@ -1611,7 +1614,7 @@ void Stepper::isr() { HAL_timer_set_compare(MF_TIMER_STEP, hal_timer_t(next_isr_ticks)); // Don't forget to finally reenable interrupts - ENABLE_ISRS(); + hal.isr_on(); } #if MINIMUM_STEPPER_PULSE || MAXIMUM_STEPPER_RATE @@ -2151,7 +2154,10 @@ uint32_t Stepper::block_phase_isr() { cutter.apply_power(current_block->cutter_power); #endif - TERN_(POWER_LOSS_RECOVERY, recovery.info.sdpos = current_block->sdpos); + #if ENABLED(POWER_LOSS_RECOVERY) + recovery.info.sdpos = current_block->sdpos; + recovery.info.current_position = current_block->start_position; + #endif #if ENABLED(DIRECT_STEPPING) if (IS_PAGE(current_block)) { @@ -3257,33 +3263,33 @@ void Stepper::report_positions() { #elif HAS_MOTOR_CURRENT_PWM - #define _WRITE_CURRENT_PWM_DUTY(P) set_pwm_duty(pin_t(MOTOR_CURRENT_PWM_## P ##_PIN), 255L * current / (MOTOR_CURRENT_PWM_RANGE)) + #define _WRITE_CURRENT_PWM(P) hal.set_pwm_duty(pin_t(MOTOR_CURRENT_PWM_## P ##_PIN), 255L * current / (MOTOR_CURRENT_PWM_RANGE)) switch (driver) { case 0: #if PIN_EXISTS(MOTOR_CURRENT_PWM_X) - _WRITE_CURRENT_PWM_DUTY(X); + _WRITE_CURRENT_PWM(X); #endif #if PIN_EXISTS(MOTOR_CURRENT_PWM_Y) - _WRITE_CURRENT_PWM_DUTY(Y); + _WRITE_CURRENT_PWM(Y); #endif #if PIN_EXISTS(MOTOR_CURRENT_PWM_XY) - _WRITE_CURRENT_PWM_DUTY(XY); + _WRITE_CURRENT_PWM(XY); #endif break; case 1: #if PIN_EXISTS(MOTOR_CURRENT_PWM_Z) - _WRITE_CURRENT_PWM_DUTY(Z); + _WRITE_CURRENT_PWM(Z); #endif break; case 2: #if PIN_EXISTS(MOTOR_CURRENT_PWM_E) - _WRITE_CURRENT_PWM_DUTY(E); + _WRITE_CURRENT_PWM(E); #endif #if PIN_EXISTS(MOTOR_CURRENT_PWM_E0) - _WRITE_CURRENT_PWM_DUTY(E0); + _WRITE_CURRENT_PWM(E0); #endif #if PIN_EXISTS(MOTOR_CURRENT_PWM_E1) - _WRITE_CURRENT_PWM_DUTY(E1); + _WRITE_CURRENT_PWM(E1); #endif break; } @@ -3305,7 +3311,7 @@ void Stepper::report_positions() { #ifdef __SAM3X8E__ #define _RESET_CURRENT_PWM_FREQ(P) NOOP #else - #define _RESET_CURRENT_PWM_FREQ(P) set_pwm_frequency(pin_t(P), MOTOR_CURRENT_PWM_FREQUENCY) + #define _RESET_CURRENT_PWM_FREQ(P) hal.set_pwm_frequency(pin_t(P), MOTOR_CURRENT_PWM_FREQUENCY) #endif #define INIT_CURRENT_PWM(P) do{ SET_PWM(MOTOR_CURRENT_PWM_## P ##_PIN); _RESET_CURRENT_PWM_FREQ(MOTOR_CURRENT_PWM_## P ##_PIN); }while(0) diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 4ccd984b0d362..653b3179b0c04 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -51,7 +51,7 @@ #if ENABLED(DWIN_CREALITY_LCD) #include "../lcd/e3v2/creality/dwin.h" -#elif ENABLED(DWIN_CREALITY_LCD_ENHANCED) +#elif ENABLED(DWIN_LCD_PROUI) #include "../lcd/e3v2/proui/dwin.h" #endif @@ -327,7 +327,7 @@ PGMSTR(str_t_heating_failed, STR_T_HEATING_FAILED); #define _INIT_FAN_PIN(P) do{ if (PWM_PIN(P)) SET_PWM(P); else _INIT_SOFT_FAN(P); }while(0) #endif #if ENABLED(FAST_PWM_FAN) - #define SET_FAST_PWM_FREQ(P) set_pwm_frequency(P, FAST_PWM_FAN_FREQUENCY) + #define SET_FAST_PWM_FREQ(P) hal.set_pwm_frequency(pin_t(P), FAST_PWM_FAN_FREQUENCY) #else #define SET_FAST_PWM_FREQ(P) NOOP #endif @@ -623,12 +623,12 @@ volatile bool Temperature::raw_temps_ready = false; TERN_(HAS_FAN_LOGIC, fan_update_ms = next_temp_ms + fan_update_interval_ms); TERN_(EXTENSIBLE_UI, ExtUI::onPidTuning(ExtUI::result_t::PID_STARTED)); - TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_PidTuning(isbed ? PID_BED_START : PID_EXTR_START)); + TERN_(DWIN_LCD_PROUI, DWIN_PidTuning(isbed ? PID_BED_START : PID_EXTR_START)); if (target > GHV(CHAMBER_MAX_TARGET, BED_MAX_TARGET, temp_range[heater_id].maxtemp - (HOTEND_OVERSHOOT))) { SERIAL_ECHOLNPGM(STR_PID_TEMP_TOO_HIGH); TERN_(EXTENSIBLE_UI, ExtUI::onPidTuning(ExtUI::result_t::PID_TEMP_TOO_HIGH)); - TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_PidTuning(PID_TEMP_TOO_HIGH)); + TERN_(DWIN_LCD_PROUI, DWIN_PidTuning(PID_TEMP_TOO_HIGH)); TERN_(HOST_PROMPT_SUPPORT, hostui.notify(GET_TEXT_F(MSG_PID_TEMP_TOO_HIGH))); return; } @@ -719,7 +719,7 @@ volatile bool Temperature::raw_temps_ready = false; if (current_temp > target + MAX_OVERSHOOT_PID_AUTOTUNE) { SERIAL_ECHOLNPGM(STR_PID_TEMP_TOO_HIGH); TERN_(EXTENSIBLE_UI, ExtUI::onPidTuning(ExtUI::result_t::PID_TEMP_TOO_HIGH)); - TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_PidTuning(PID_TEMP_TOO_HIGH)); + TERN_(DWIN_LCD_PROUI, DWIN_PidTuning(PID_TEMP_TOO_HIGH)); TERN_(HOST_PROMPT_SUPPORT, hostui.notify(GET_TEXT_F(MSG_PID_TEMP_TOO_HIGH))); break; } @@ -756,7 +756,7 @@ volatile bool Temperature::raw_temps_ready = false; #endif if ((ms - _MIN(t1, t2)) > (MAX_CYCLE_TIME_PID_AUTOTUNE * 60L * 1000L)) { TERN_(DWIN_CREALITY_LCD, DWIN_Popup_Temperature(0)); - TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_PidTuning(PID_TUNING_TIMEOUT)); + TERN_(DWIN_LCD_PROUI, DWIN_PidTuning(PID_TUNING_TIMEOUT)); TERN_(EXTENSIBLE_UI, ExtUI::onPidTuning(ExtUI::result_t::PID_TUNING_TIMEOUT)); TERN_(HOST_PROMPT_SUPPORT, hostui.notify(GET_TEXT_F(MSG_PID_TIMEOUT))); SERIAL_ECHOLNPGM(STR_PID_TIMEOUT); @@ -812,16 +812,16 @@ volatile bool Temperature::raw_temps_ready = false; TERN_(PRINTER_EVENT_LEDS, printerEventLEDs.onPidTuningDone(color)); TERN_(EXTENSIBLE_UI, ExtUI::onPidTuning(ExtUI::result_t::PID_DONE)); - TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_PidTuning(PID_DONE)); + TERN_(DWIN_LCD_PROUI, DWIN_PidTuning(PID_DONE)); goto EXIT_M303; } // Run HAL idle tasks - TERN_(HAL_IDLETASK, HAL_idletask()); + hal.idletask(); // Run UI update - TERN(HAS_DWIN_E3V2_BASIC, DWIN_Update(), ui.update()); + TERN(DWIN_CREALITY_LCD, DWIN_Update(), ui.update()); } wait_for_heatup = false; @@ -830,7 +830,7 @@ volatile bool Temperature::raw_temps_ready = false; TERN_(PRINTER_EVENT_LEDS, printerEventLEDs.onPidTuningDone(color)); TERN_(EXTENSIBLE_UI, ExtUI::onPidTuning(ExtUI::result_t::PID_DONE)); - TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_PidTuning(PID_DONE)); + TERN_(DWIN_LCD_PROUI, DWIN_PidTuning(PID_DONE)); EXIT_M303: TERN_(NO_FAN_SLOWING_IN_PID_TUNING, adaptive_fan_slowing = true); @@ -907,7 +907,7 @@ int16_t Temperature::getHeaterPower(const heater_id_t heater_id) { #define _UPDATE_AUTO_FAN(P,D,A) do{ \ if (PWM_PIN(P##_AUTO_FAN_PIN) && A < 255) \ - set_pwm_duty(pin_t(P##_AUTO_FAN_PIN), D ? A : 0); \ + hal.set_pwm_duty(pin_t(P##_AUTO_FAN_PIN), D ? A : 0); \ else \ WRITE(P##_AUTO_FAN_PIN, D); \ }while(0) @@ -2321,74 +2321,33 @@ void Temperature::init() { TERN_(HAS_MAXTC_SW_SPI, max_tc_spi.init()); - HAL_adc_init(); + hal.adc_init(); + + TERN_(HAS_TEMP_ADC_0, hal.adc_enable(TEMP_0_PIN)); + TERN_(HAS_TEMP_ADC_1, hal.adc_enable(TEMP_1_PIN)); + TERN_(HAS_TEMP_ADC_2, hal.adc_enable(TEMP_2_PIN)); + TERN_(HAS_TEMP_ADC_3, hal.adc_enable(TEMP_3_PIN)); + TERN_(HAS_TEMP_ADC_4, hal.adc_enable(TEMP_4_PIN)); + TERN_(HAS_TEMP_ADC_5, hal.adc_enable(TEMP_5_PIN)); + TERN_(HAS_TEMP_ADC_6, hal.adc_enable(TEMP_6_PIN)); + TERN_(HAS_TEMP_ADC_7, hal.adc_enable(TEMP_7_PIN)); + TERN_(HAS_JOY_ADC_X, hal.adc_enable(JOY_X_PIN)); + TERN_(HAS_JOY_ADC_Y, hal.adc_enable(JOY_Y_PIN)); + TERN_(HAS_JOY_ADC_Z, hal.adc_enable(JOY_Z_PIN)); + TERN_(HAS_TEMP_ADC_BED, hal.adc_enable(TEMP_BED_PIN)); + TERN_(HAS_TEMP_ADC_CHAMBER, hal.adc_enable(TEMP_CHAMBER_PIN)); + TERN_(HAS_TEMP_ADC_PROBE, hal.adc_enable(TEMP_PROBE_PIN)); + TERN_(HAS_TEMP_ADC_COOLER, hal.adc_enable(TEMP_COOLER_PIN)); + TERN_(HAS_TEMP_ADC_BOARD, hal.adc_enable(TEMP_BOARD_PIN)); + TERN_(HAS_TEMP_ADC_REDUNDANT, hal.adc_enable(TEMP_REDUNDANT_PIN)); + TERN_(FILAMENT_WIDTH_SENSOR, hal.adc_enable(FILWIDTH_PIN)); + TERN_(HAS_ADC_BUTTONS, hal.adc_enable(ADC_KEYPAD_PIN)); + TERN_(POWER_MONITOR_CURRENT, hal.adc_enable(POWER_MONITOR_CURRENT_PIN)); + TERN_(POWER_MONITOR_VOLTAGE, hal.adc_enable(POWER_MONITOR_VOLTAGE_PIN)); - #if HAS_TEMP_ADC_0 - HAL_ANALOG_SELECT(TEMP_0_PIN); - #endif - #if HAS_TEMP_ADC_1 - HAL_ANALOG_SELECT(TEMP_1_PIN); - #endif - #if HAS_TEMP_ADC_2 - HAL_ANALOG_SELECT(TEMP_2_PIN); - #endif - #if HAS_TEMP_ADC_3 - HAL_ANALOG_SELECT(TEMP_3_PIN); - #endif - #if HAS_TEMP_ADC_4 - HAL_ANALOG_SELECT(TEMP_4_PIN); - #endif - #if HAS_TEMP_ADC_5 - HAL_ANALOG_SELECT(TEMP_5_PIN); - #endif - #if HAS_TEMP_ADC_6 - HAL_ANALOG_SELECT(TEMP_6_PIN); - #endif - #if HAS_TEMP_ADC_7 - HAL_ANALOG_SELECT(TEMP_7_PIN); - #endif - #if HAS_JOY_ADC_X - HAL_ANALOG_SELECT(JOY_X_PIN); - #endif - #if HAS_JOY_ADC_Y - HAL_ANALOG_SELECT(JOY_Y_PIN); - #endif - #if HAS_JOY_ADC_Z - HAL_ANALOG_SELECT(JOY_Z_PIN); - #endif #if HAS_JOY_ADC_EN SET_INPUT_PULLUP(JOY_EN_PIN); #endif - #if HAS_TEMP_ADC_BED - HAL_ANALOG_SELECT(TEMP_BED_PIN); - #endif - #if HAS_TEMP_ADC_CHAMBER - HAL_ANALOG_SELECT(TEMP_CHAMBER_PIN); - #endif - #if HAS_TEMP_ADC_PROBE - HAL_ANALOG_SELECT(TEMP_PROBE_PIN); - #endif - #if HAS_TEMP_ADC_COOLER - HAL_ANALOG_SELECT(TEMP_COOLER_PIN); - #endif - #if HAS_TEMP_ADC_BOARD - HAL_ANALOG_SELECT(TEMP_BOARD_PIN); - #endif - #if HAS_TEMP_ADC_REDUNDANT - HAL_ANALOG_SELECT(TEMP_REDUNDANT_PIN); - #endif - #if ENABLED(FILAMENT_WIDTH_SENSOR) - HAL_ANALOG_SELECT(FILWIDTH_PIN); - #endif - #if HAS_ADC_BUTTONS - HAL_ANALOG_SELECT(ADC_KEYPAD_PIN); - #endif - #if ENABLED(POWER_MONITOR_CURRENT) - HAL_ANALOG_SELECT(POWER_MONITOR_CURRENT_PIN); - #endif - #if ENABLED(POWER_MONITOR_VOLTAGE) - HAL_ANALOG_SELECT(POWER_MONITOR_VOLTAGE_PIN); - #endif HAL_timer_start(MF_TIMER_TEMP, TEMP_TIMER_FREQUENCY); ENABLE_TEMPERATURE_INTERRUPT(); @@ -3364,8 +3323,8 @@ void Temperature::isr() { * This gives each ADC 0.9765ms to charge up. */ #define ACCUMULATE_ADC(obj) do{ \ - if (!HAL_ADC_READY()) next_sensor_state = adc_sensor_state; \ - else obj.sample(HAL_READ_ADC()); \ + if (!hal.adc_ready()) next_sensor_state = adc_sensor_state; \ + else obj.sample(hal.adc_value()); \ }while(0) ADCSensorState next_sensor_state = adc_sensor_state < SensorsReady ? (ADCSensorState)(int(adc_sensor_state) + 1) : StartSampling; @@ -3397,115 +3356,115 @@ void Temperature::isr() { break; #if HAS_TEMP_ADC_0 - case PrepareTemp_0: HAL_START_ADC(TEMP_0_PIN); break; + case PrepareTemp_0: hal.adc_start(TEMP_0_PIN); break; case MeasureTemp_0: ACCUMULATE_ADC(temp_hotend[0]); break; #endif #if HAS_TEMP_ADC_BED - case PrepareTemp_BED: HAL_START_ADC(TEMP_BED_PIN); break; + case PrepareTemp_BED: hal.adc_start(TEMP_BED_PIN); break; case MeasureTemp_BED: ACCUMULATE_ADC(temp_bed); break; #endif #if HAS_TEMP_ADC_CHAMBER - case PrepareTemp_CHAMBER: HAL_START_ADC(TEMP_CHAMBER_PIN); break; + case PrepareTemp_CHAMBER: hal.adc_start(TEMP_CHAMBER_PIN); break; case MeasureTemp_CHAMBER: ACCUMULATE_ADC(temp_chamber); break; #endif #if HAS_TEMP_ADC_COOLER - case PrepareTemp_COOLER: HAL_START_ADC(TEMP_COOLER_PIN); break; + case PrepareTemp_COOLER: hal.adc_start(TEMP_COOLER_PIN); break; case MeasureTemp_COOLER: ACCUMULATE_ADC(temp_cooler); break; #endif #if HAS_TEMP_ADC_PROBE - case PrepareTemp_PROBE: HAL_START_ADC(TEMP_PROBE_PIN); break; + case PrepareTemp_PROBE: hal.adc_start(TEMP_PROBE_PIN); break; case MeasureTemp_PROBE: ACCUMULATE_ADC(temp_probe); break; #endif #if HAS_TEMP_ADC_BOARD - case PrepareTemp_BOARD: HAL_START_ADC(TEMP_BOARD_PIN); break; + case PrepareTemp_BOARD: hal.adc_start(TEMP_BOARD_PIN); break; case MeasureTemp_BOARD: ACCUMULATE_ADC(temp_board); break; #endif #if HAS_TEMP_ADC_REDUNDANT - case PrepareTemp_REDUNDANT: HAL_START_ADC(TEMP_REDUNDANT_PIN); break; + case PrepareTemp_REDUNDANT: hal.adc_start(TEMP_REDUNDANT_PIN); break; case MeasureTemp_REDUNDANT: ACCUMULATE_ADC(temp_redundant); break; #endif #if HAS_TEMP_ADC_1 - case PrepareTemp_1: HAL_START_ADC(TEMP_1_PIN); break; + case PrepareTemp_1: hal.adc_start(TEMP_1_PIN); break; case MeasureTemp_1: ACCUMULATE_ADC(temp_hotend[1]); break; #endif #if HAS_TEMP_ADC_2 - case PrepareTemp_2: HAL_START_ADC(TEMP_2_PIN); break; + case PrepareTemp_2: hal.adc_start(TEMP_2_PIN); break; case MeasureTemp_2: ACCUMULATE_ADC(temp_hotend[2]); break; #endif #if HAS_TEMP_ADC_3 - case PrepareTemp_3: HAL_START_ADC(TEMP_3_PIN); break; + case PrepareTemp_3: hal.adc_start(TEMP_3_PIN); break; case MeasureTemp_3: ACCUMULATE_ADC(temp_hotend[3]); break; #endif #if HAS_TEMP_ADC_4 - case PrepareTemp_4: HAL_START_ADC(TEMP_4_PIN); break; + case PrepareTemp_4: hal.adc_start(TEMP_4_PIN); break; case MeasureTemp_4: ACCUMULATE_ADC(temp_hotend[4]); break; #endif #if HAS_TEMP_ADC_5 - case PrepareTemp_5: HAL_START_ADC(TEMP_5_PIN); break; + case PrepareTemp_5: hal.adc_start(TEMP_5_PIN); break; case MeasureTemp_5: ACCUMULATE_ADC(temp_hotend[5]); break; #endif #if HAS_TEMP_ADC_6 - case PrepareTemp_6: HAL_START_ADC(TEMP_6_PIN); break; + case PrepareTemp_6: hal.adc_start(TEMP_6_PIN); break; case MeasureTemp_6: ACCUMULATE_ADC(temp_hotend[6]); break; #endif #if HAS_TEMP_ADC_7 - case PrepareTemp_7: HAL_START_ADC(TEMP_7_PIN); break; + case PrepareTemp_7: hal.adc_start(TEMP_7_PIN); break; case MeasureTemp_7: ACCUMULATE_ADC(temp_hotend[7]); break; #endif #if ENABLED(FILAMENT_WIDTH_SENSOR) - case Prepare_FILWIDTH: HAL_START_ADC(FILWIDTH_PIN); break; + case Prepare_FILWIDTH: hal.adc_start(FILWIDTH_PIN); break; case Measure_FILWIDTH: - if (!HAL_ADC_READY()) next_sensor_state = adc_sensor_state; // Redo this state - else filwidth.accumulate(HAL_READ_ADC()); + if (!hal.adc_ready()) next_sensor_state = adc_sensor_state; // Redo this state + else filwidth.accumulate(hal.adc_value()); break; #endif #if ENABLED(POWER_MONITOR_CURRENT) case Prepare_POWER_MONITOR_CURRENT: - HAL_START_ADC(POWER_MONITOR_CURRENT_PIN); + hal.adc_start(POWER_MONITOR_CURRENT_PIN); break; case Measure_POWER_MONITOR_CURRENT: - if (!HAL_ADC_READY()) next_sensor_state = adc_sensor_state; // Redo this state - else power_monitor.add_current_sample(HAL_READ_ADC()); + if (!hal.adc_ready()) next_sensor_state = adc_sensor_state; // Redo this state + else power_monitor.add_current_sample(hal.adc_value()); break; #endif #if ENABLED(POWER_MONITOR_VOLTAGE) case Prepare_POWER_MONITOR_VOLTAGE: - HAL_START_ADC(POWER_MONITOR_VOLTAGE_PIN); + hal.adc_start(POWER_MONITOR_VOLTAGE_PIN); break; case Measure_POWER_MONITOR_VOLTAGE: - if (!HAL_ADC_READY()) next_sensor_state = adc_sensor_state; // Redo this state - else power_monitor.add_voltage_sample(HAL_READ_ADC()); + if (!hal.adc_ready()) next_sensor_state = adc_sensor_state; // Redo this state + else power_monitor.add_voltage_sample(hal.adc_value()); break; #endif #if HAS_JOY_ADC_X - case PrepareJoy_X: HAL_START_ADC(JOY_X_PIN); break; + case PrepareJoy_X: hal.adc_start(JOY_X_PIN); break; case MeasureJoy_X: ACCUMULATE_ADC(joystick.x); break; #endif #if HAS_JOY_ADC_Y - case PrepareJoy_Y: HAL_START_ADC(JOY_Y_PIN); break; + case PrepareJoy_Y: hal.adc_start(JOY_Y_PIN); break; case MeasureJoy_Y: ACCUMULATE_ADC(joystick.y); break; #endif #if HAS_JOY_ADC_Z - case PrepareJoy_Z: HAL_START_ADC(JOY_Z_PIN); break; + case PrepareJoy_Z: hal.adc_start(JOY_Z_PIN); break; case MeasureJoy_Z: ACCUMULATE_ADC(joystick.z); break; #endif @@ -3513,12 +3472,12 @@ void Temperature::isr() { #ifndef ADC_BUTTON_DEBOUNCE_DELAY #define ADC_BUTTON_DEBOUNCE_DELAY 16 #endif - case Prepare_ADC_KEY: HAL_START_ADC(ADC_KEYPAD_PIN); break; + case Prepare_ADC_KEY: hal.adc_start(ADC_KEYPAD_PIN); break; case Measure_ADC_KEY: - if (!HAL_ADC_READY()) + if (!hal.adc_ready()) next_sensor_state = adc_sensor_state; // redo this state else if (ADCKey_count < ADC_BUTTON_DEBOUNCE_DELAY) { - raw_ADCKey_value = HAL_READ_ADC(); + raw_ADCKey_value = hal.adc_value(); if (raw_ADCKey_value <= 900UL * HAL_ADC_RANGE / 1024UL) { NOMORE(current_ADCKey_raw, raw_ADCKey_value); ADCKey_count++; diff --git a/Marlin/src/module/thermistor/thermistor_68.h b/Marlin/src/module/thermistor/thermistor_68.h new file mode 100644 index 0000000000000..270456dcb59c7 --- /dev/null +++ b/Marlin/src/module/thermistor/thermistor_68.h @@ -0,0 +1,54 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2022 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 REVERSE_TEMP_SENSOR_RANGE_68 1 + +// PT100 amplifier board from Dyze Design +const temp_entry_t temptable_68[] PROGMEM = { + { OV(273), 0 }, + { OV(294), 20 }, + { OV(315), 40 }, + { OV(336), 60 }, + { OV(356), 80 }, + { OV(376), 100 }, + { OV(396), 120 }, + { OV(416), 140 }, + { OV(436), 160 }, + { OV(455), 180 }, + { OV(474), 200 }, + { OV(494), 220 }, + { OV(513), 240 }, + { OV(531), 260 }, + { OV(550), 280 }, + { OV(568), 300 }, + { OV(587), 320 }, + { OV(605), 340 }, + { OV(623), 360 }, + { OV(641), 380 }, + { OV(658), 400 }, + { OV(676), 420 }, + { OV(693), 440 }, + { OV(710), 460 }, + { OV(727), 480 }, + { OV(744), 500 } +}; diff --git a/Marlin/src/module/thermistor/thermistors.h b/Marlin/src/module/thermistor/thermistors.h index 3d9ef5062d507..9f2ebce49a323 100644 --- a/Marlin/src/module/thermistor/thermistors.h +++ b/Marlin/src/module/thermistor/thermistors.h @@ -156,6 +156,9 @@ typedef struct { int16_t value; celsius_t celsius; } temp_entry_t; #if ANY_THERMISTOR_IS(67) // R25 = 500 KOhm, beta25 = 3800 K, 4.7 kOhm pull-up, SliceEngineering 450 °C Thermistor #include "thermistor_67.h" #endif +#if ANY_THERMISTOR_IS(68) // PT-100 with Dyze amplifier board + #include "thermistor_68.h" +#endif #if ANY_THERMISTOR_IS(12) // beta25 = 4700 K, R25 = 100 kOhm, Pull-up = 4.7 kOhm, "Personal calibration for Makibox hot bed" #include "thermistor_12.h" #endif diff --git a/Marlin/src/pins/linux/pins_RAMPS_LINUX.h b/Marlin/src/pins/linux/pins_RAMPS_LINUX.h index 372f96765239a..e2efdfa4929b8 100644 --- a/Marlin/src/pins/linux/pins_RAMPS_LINUX.h +++ b/Marlin/src/pins/linux/pins_RAMPS_LINUX.h @@ -234,14 +234,16 @@ // // Průša i3 MK2 Multiplexer Support // -#ifndef E_MUX0_PIN - #define E_MUX0_PIN 40 // Z_CS_PIN -#endif -#ifndef E_MUX1_PIN - #define E_MUX1_PIN 42 // E0_CS_PIN -#endif -#ifndef E_MUX2_PIN - #define E_MUX2_PIN 44 // E1_CS_PIN +#if HAS_PRUSA_MMU1 + #ifndef E_MUX0_PIN + #define E_MUX0_PIN 40 // Z_CS_PIN + #endif + #ifndef E_MUX1_PIN + #define E_MUX1_PIN 42 // E0_CS_PIN + #endif + #ifndef E_MUX2_PIN + #define E_MUX2_PIN 44 // E1_CS_PIN + #endif #endif /** diff --git a/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h b/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h index ee9d0e8c7a1d4..b08ac536b3d08 100644 --- a/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h +++ b/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h @@ -258,11 +258,13 @@ // // Průša i3 MK2 Multiplexer Support // -#if SERIAL_PORT != 0 && SERIAL_PORT_2 != 0 - #define E_MUX0_PIN P0_03 // ( 0) Z_CS_PIN - #define E_MUX1_PIN P0_02 // ( 1) E0_CS_PIN +#if HAS_PRUSA_MMU1 + #if SERIAL_PORT != 0 && SERIAL_PORT_2 != 0 + #define E_MUX0_PIN P0_03 // ( 0) Z_CS_PIN + #define E_MUX1_PIN P0_02 // ( 1) E0_CS_PIN + #endif + #define E_MUX2_PIN P0_26 // (63) E1_CS_PIN #endif -#define E_MUX2_PIN P0_26 // (63) E1_CS_PIN /** * LCD / Controller diff --git a/Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h b/Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h index eb92ab5cd010f..f2a95baf011b4 100644 --- a/Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h +++ b/Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h @@ -144,56 +144,41 @@ //#define TEMP_1_MOSI_PIN TEMP_0_MOSI_PIN // -// Augmentation for auto-assigning plugs -// -// Two thermocouple connectors allows for either -// 2 extruders or 1 extruder and a heated bed. -// With no heated bed, an additional 24V fan is possible. +// FET Pin Mapping - FET 1 is closest to the input power connector // -#define MOSFET_A_PIN 6 // H3 EX1_HEAT_PIN -#define MOSFET_B_PIN 11 // B5 EX2_HEAT_PIN -#define MOSFET_C_PIN 45 // L4 HBP_PIN -#define MOSFET_D_PIN 44 // L5 EXTRA_FET_PIN +#define MOSFET_1_PIN 6 // Plug EX1 Pin 1-2 -> PH3 #15 -> Logical 06 +#define MOSFET_2_PIN 7 // Plug EX1 Pin 3-4 -> PH4 #16 -> Logical 07 +#define MOSFET_3_PIN 12 // Plug EX2 1-2 -> PB5 #25 -> Logical 12 +#define MOSFET_4_PIN 11 // Plug EX2 3-4 -> PB6 #24 -> Logical 11 +#define MOSFET_5_PIN 45 // Plug HBD 1-2 -> PL4 #39 -> Logical 45 +#define MOSFET_6_PIN 13 // Plug Extra 1-2 -> PL5 #40 -> Logical 44 (FET not soldered in all boards) // // Heaters / Fans (24V) // -#define HEATER_0_PIN MOSFET_A_PIN - -#if FET_ORDER_EFB // Hotend, Fan, Bed - #define HEATER_BED_PIN MOSFET_C_PIN -#elif FET_ORDER_EEF // Hotend, Hotend, Fan - #define HEATER_1_PIN MOSFET_B_PIN -#elif FET_ORDER_EEB // Hotend, Hotend, Bed - #define HEATER_1_PIN MOSFET_B_PIN - #define HEATER_BED_PIN MOSFET_C_PIN -#elif FET_ORDER_EFF // Hotend, Fan, Fan - #define FAN1_PIN MOSFET_C_PIN -#endif -#ifndef FAN_PIN - #if EITHER(FET_ORDER_EFB, FET_ORDER_EFF) // Hotend, Fan, Bed or Hotend, Fan, Fan - #define FAN_PIN MOSFET_B_PIN - #elif EITHER(FET_ORDER_EEF, FET_ORDER_SF) // Hotend, Hotend, Fan or Spindle, Fan - #define FAN_PIN MOSFET_C_PIN - #else - #define FAN_PIN MOSFET_D_PIN - #endif -#endif +#define HEATER_0_PIN MOSFET_1_PIN // EX1 +#define HEATER_1_PIN MOSFET_3_PIN // EX2 +#define HEATER_BED_PIN MOSFET_5_PIN // HBP -#ifndef FAN1_PIN - #define FAN1_PIN 7 // H4 EX1_FAN_PIN +// EX1 FAN (Automatic Fans are disabled by default in Configuration_adv.h - comment that out for auto fans) +#ifndef E0_AUTO_FAN_PIN + #define E0_AUTO_FAN_PIN MOSFET_2_PIN +#else + #define FAN_PIN MOSFET_2_PIN #endif - -#ifndef CONTROLLER_FAN_PIN - #define CONTROLLER_FAN_PIN 12 // B6 EX2_FAN_PIN +// EX2 FAN (Automatic Fans are disabled by default in Configuration_adv.h - comment that out for auto fans) +#ifndef E1_AUTO_FAN_PIN + #define E1_AUTO_FAN_PIN MOSFET_4_PIN +#else + #define FAN1_PIN MOSFET_4_PIN #endif // // Misc. Functions // -#define LED_PIN 13 // B7 +#define LED_PIN MOSFET_6_PIN // B7 #define CUTOFF_RESET_PIN 16 // H1 #define CUTOFF_TEST_PIN 17 // H0 #define CUTOFF_SR_CHECK_PIN 70 // G4 (TOSC1) diff --git a/Marlin/src/pins/mega/pins_PICA.h b/Marlin/src/pins/mega/pins_PICA.h index 47c101711c4f8..0e29d8dffe75b 100644 --- a/Marlin/src/pins/mega/pins_PICA.h +++ b/Marlin/src/pins/mega/pins_PICA.h @@ -51,6 +51,7 @@ #define SERVO0_PIN 3 #define SERVO1_PIN 4 #define SERVO2_PIN 5 + // // Limit Switches // diff --git a/Marlin/src/pins/mega/pins_WEEDO_62A.h b/Marlin/src/pins/mega/pins_WEEDO_62A.h new file mode 100644 index 0000000000000..4b3bf6a43bee5 --- /dev/null +++ b/Marlin/src/pins/mega/pins_WEEDO_62A.h @@ -0,0 +1,106 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2022 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * Based on WEEDO 62A pin configuration + * Copyright (c) 2019 WEEDO3D Perron + */ + +#pragma once + +#include "env_validate.h" + +#ifndef BOARD_INFO_NAME + #define BOARD_INFO_NAME "WEEDO 62A" +#endif + +// +// Limit Switches +// +#define X_MIN_PIN 3 +#define X_MAX_PIN 2 +#define Y_MIN_PIN 40 +#define Y_MAX_PIN 41 +#define Z_MIN_PIN 18 +#define Z_MAX_PIN 19 + +// +// Steppers +// +#define X_STEP_PIN 26 +#define X_DIR_PIN 28 +#define X_ENABLE_PIN 24 + +#define Y_STEP_PIN 60 +#define Y_DIR_PIN 61 +#define Y_ENABLE_PIN 56 + +#define Z_STEP_PIN 46 +#define Z_DIR_PIN 48 +#define Z_ENABLE_PIN 62 + +#define E0_STEP_PIN 54 +#define E0_DIR_PIN 55 +#define E0_ENABLE_PIN 38 + +// +// Temperature Sensors +// +#define TEMP_0_PIN 13 // ANALOG NUMBERING +#define TEMP_BED_PIN 14 // ANALOG NUMBERING + +// +// Heaters / Fans +// +#define HEATER_0_PIN 10 // EXTRUDER 1 +#define HEATER_BED_PIN 8 // BED +#define FAN_PIN 4 // IO pin. Buffer needed + +// +// Misc. Functions +// +#define PS_ON_PIN 12 +#define LED_PIN 13 + +// +// SD Support +// +#if ENABLED(SDSUPPORT) + #define SDSS 53 + #define SD_DETECT_PIN 49 +#endif + +// +// LCD / Controller +// +#if HAS_WIRED_LCD + #define BEEPER_PIN 37 + + #define DOGLCD_A0 27 + #define DOGLCD_CS 29 + #define LCD_RESET_PIN 25 + #define LCD_CONTRAST_INIT 255 + + #define BTN_EN1 33 + #define BTN_EN2 31 + #define BTN_ENC 35 +#endif diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 4ba97a77a736c..7f0eac8c88fbf 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -201,6 +201,8 @@ #include "ramps/pins_RAMPS_S_12.h" // ATmega2560 env:mega2560 #elif MB(LONGER3D_LK1_PRO, LONGER3D_LKx_PRO) #include "ramps/pins_LONGER3D_LKx_PRO.h" // ATmega2560 env:mega2560 +#elif MB(PXMALION_CORE_I3) + #include "ramps/pins_PXMALION_CORE_I3.h" // ATmega2560 env:mega2560 // // RAMBo and derivatives @@ -285,6 +287,8 @@ #include "mega/pins_MALYAN_M180.h" // ATmega2560 env:mega2560 #elif MB(PROTONEER_CNC_SHIELD_V3) #include "mega/pins_PROTONEER_CNC_SHIELD_V3.h"// ATmega2560 env:mega2560 +#elif MB(WEEDO_62A) + #include "mega/pins_WEEDO_62A.h" // ATmega2560 env:mega2560 // // ATmega1281, ATmega2561 @@ -667,6 +671,8 @@ #include "stm32f4/pins_MKS_ROBIN_PRO_V2.h" // STM32F4 env:mks_robin_pro2 #elif MB(MKS_ROBIN_NANO_V3) #include "stm32f4/pins_MKS_ROBIN_NANO_V3.h" // STM32F4 env:mks_robin_nano_v3 env:mks_robin_nano_v3_usb_flash_drive env:mks_robin_nano_v3_usb_flash_drive_msc +#elif MB(MKS_ROBIN_NANO_V3_1) + #include "stm32f4/pins_MKS_ROBIN_NANO_V3.h" // STM32F4 env:mks_robin_nano_v3_1 env:mks_robin_nano_v3_1_usb_flash_drive env:mks_robin_nano_v3_1_usb_flash_drive_msc #elif MB(ANET_ET4) #include "stm32f4/pins_ANET_ET4.h" // STM32F4 env:Anet_ET4_OpenBLT #elif MB(ANET_ET4P) diff --git a/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h b/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h index a7d1a6282048f..9150bf13655d4 100644 --- a/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h +++ b/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h @@ -163,9 +163,11 @@ // // Průša i3 MK2 Multiplexer Support // -#define E_MUX0_PIN 17 -#define E_MUX1_PIN 16 -#define E_MUX2_PIN 78 // 84 in MK2 Firmware, with BEEPER as 78 +#if HAS_PRUSA_MMU1 + #define E_MUX0_PIN 17 + #define E_MUX1_PIN 16 + #define E_MUX2_PIN 78 // 84 in MK2 Firmware, with BEEPER as 78 +#endif // // LCD / Controller diff --git a/Marlin/src/pins/rambo/pins_EINSY_RETRO.h b/Marlin/src/pins/rambo/pins_EINSY_RETRO.h index 165475dae8fdf..8bc0a90c0586a 100644 --- a/Marlin/src/pins/rambo/pins_EINSY_RETRO.h +++ b/Marlin/src/pins/rambo/pins_EINSY_RETRO.h @@ -157,9 +157,11 @@ // // Průša i3 MK2 Multiplexer Support // -#define E_MUX0_PIN 17 -#define E_MUX1_PIN 16 -#define E_MUX2_PIN 78 // 84 in MK2 Firmware, with BEEPER as 78 +#if HAS_PRUSA_MMU1 + #define E_MUX0_PIN 17 + #define E_MUX1_PIN 16 + #define E_MUX2_PIN 78 // 84 in MK2 Firmware, with BEEPER as 78 +#endif // // LCD / Controller diff --git a/Marlin/src/pins/rambo/pins_MINIRAMBO.h b/Marlin/src/pins/rambo/pins_MINIRAMBO.h index ab25e2e692afe..31d44f2b34ba7 100644 --- a/Marlin/src/pins/rambo/pins_MINIRAMBO.h +++ b/Marlin/src/pins/rambo/pins_MINIRAMBO.h @@ -130,10 +130,12 @@ // // Průša i3 MK2 Multiplexer Support // -#define E_MUX0_PIN 17 -#define E_MUX1_PIN 16 -#if !MB(MINIRAMBO_10A) - #define E_MUX2_PIN 78 // 84 in MK2 Firmware, with BEEPER as 78 +#if HAS_PRUSA_MMU1 + #define E_MUX0_PIN 17 + #define E_MUX1_PIN 16 + #if !MB(MINIRAMBO_10A) + #define E_MUX2_PIN 78 // 84 in MK2 Firmware, with BEEPER as 78 + #endif #endif // diff --git a/Marlin/src/pins/rambo/pins_RAMBO.h b/Marlin/src/pins/rambo/pins_RAMBO.h index f27bced6238bc..5484b193b93bb 100644 --- a/Marlin/src/pins/rambo/pins_RAMBO.h +++ b/Marlin/src/pins/rambo/pins_RAMBO.h @@ -186,9 +186,11 @@ // // Průša i3 MK2 Multiplexer Support // -#define E_MUX0_PIN 17 -#define E_MUX1_PIN 16 -#define E_MUX2_PIN 84 // 84 in MK2 Firmware +#if HAS_PRUSA_MMU1 + #define E_MUX0_PIN 17 + #define E_MUX1_PIN 16 + #define E_MUX2_PIN 84 // 84 in MK2 Firmware +#endif // // LCD / Controller diff --git a/Marlin/src/pins/ramps/pins_LONGER3D_LKx_PRO.h b/Marlin/src/pins/ramps/pins_LONGER3D_LKx_PRO.h index 729a82b9c6339..a7817c6f3a7be 100644 --- a/Marlin/src/pins/ramps/pins_LONGER3D_LKx_PRO.h +++ b/Marlin/src/pins/ramps/pins_LONGER3D_LKx_PRO.h @@ -105,7 +105,9 @@ // // Průša i3 MK2 Multiplexer Support // -#define E_MUX2_PIN -1 +#if HAS_PRUSA_MMU1 + #define E_MUX2_PIN -1 +#endif // // Misc. Functions diff --git a/Marlin/src/pins/ramps/pins_PXMALION_CORE_I3.h b/Marlin/src/pins/ramps/pins_PXMALION_CORE_I3.h new file mode 100644 index 0000000000000..12c40c7dca03b --- /dev/null +++ b/Marlin/src/pins/ramps/pins_PXMALION_CORE_I3.h @@ -0,0 +1,86 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2022 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 . + * + */ + +/** + * Pxmalion Core i3 - https://github.com/Pxmalion + */ + +#include "env_validate.h" + +#ifndef BOARD_INFO_NAME + #define BOARD_INFO_NAME "Core i3" +#endif + +// +// Servos +// +#define SERVO0_PIN 51 +#define SERVO1_PIN -1 +#define SERVO2_PIN -1 +#define SERVO3_PIN -1 + +// +// Limit Switches +// +#define X_STOP_PIN 3 +#define Y_STOP_PIN 2 +#define Z_MIN_PIN 19 +#define Z_MAX_PIN 18 + +// TODO: Filament Runout Sensor +#ifndef FIL_RUNOUT_PIN + #define FIL_RUNOUT_PIN -1 +#endif + +// +// Steppers +// +#define X_CS_PIN -1 +#define Y_CS_PIN -1 +#define Z_CS_PIN -1 +#define E0_CS_PIN -1 +#define E1_CS_PIN -1 + +// +// Heaters / Fans +// +#define FET_ORDER_EFB +#ifndef MOSFET_A_PIN + #define MOSFET_A_PIN 8 +#endif +#ifndef MOSFET_B_PIN + #define MOSFET_B_PIN 7 +#endif +#ifndef MOSFET_C_PIN + #define MOSFET_C_PIN 9 +#endif + +// +// Misc. Functions +// +#ifndef FILWIDTH_PIN + #define FILWIDTH_PIN -1 // Analog Input +#endif + +#define PS_ON_PIN 11 + +#include "pins_RAMPS.h" diff --git a/Marlin/src/pins/ramps/pins_RAMPS.h b/Marlin/src/pins/ramps/pins_RAMPS.h index 70da23af73e52..29caaf0533b93 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS.h +++ b/Marlin/src/pins/ramps/pins_RAMPS.h @@ -412,14 +412,16 @@ // // Průša i3 MK2 Multiplexer Support // -#ifndef E_MUX0_PIN - #define E_MUX0_PIN 40 // Z_CS_PIN -#endif -#ifndef E_MUX1_PIN - #define E_MUX1_PIN 42 // E0_CS_PIN -#endif -#ifndef E_MUX2_PIN - #define E_MUX2_PIN 44 // E1_CS_PIN +#if HAS_PRUSA_MMU1 + #ifndef E_MUX0_PIN + #define E_MUX0_PIN 40 // Z_CS_PIN + #endif + #ifndef E_MUX1_PIN + #define E_MUX1_PIN 42 // E0_CS_PIN + #endif + #ifndef E_MUX2_PIN + #define E_MUX2_PIN 44 // E1_CS_PIN + #endif #endif // diff --git a/Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h b/Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h index def71fefc13e1..679503e982680 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h +++ b/Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h @@ -30,9 +30,8 @@ // // Heaters / Fans // - -// Power outputs EFBF or EFBE -#define MOSFET_D_PIN 7 +#define MOSFET_B_PIN 7 // For HEATER_1_PIN ("EEF" or "EEB") +#define FAN_PIN 9 #define FIL_RUNOUT_PIN 2 #if NUM_RUNOUT_SENSORS >= 2 @@ -40,7 +39,12 @@ #endif #ifndef SD_DETECT_PIN - #define SD_DETECT_PIN 49 // Always define onboard SD detect + #if SD_CONNECTION_IS(ONBOARD) + //#define HAS_ONBOARD_SD_DETECT // If the SD_DETECT_PIN is wired up + #endif + #if ENABLED(HAS_ONBOARD_SD_DETECT) || !SD_CONNECTION_IS(ONBOARD) + #define SD_DETECT_PIN 49 + #endif #endif #ifndef PS_ON_PIN diff --git a/Marlin/src/pins/ramps/pins_RAMPS_S_12.h b/Marlin/src/pins/ramps/pins_RAMPS_S_12.h index e1ba91cde8f0e..f41573b527cda 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS_S_12.h +++ b/Marlin/src/pins/ramps/pins_RAMPS_S_12.h @@ -233,14 +233,16 @@ // // Průša i3 MK2 Multiplexer Support // -#ifndef E_MUX0_PIN - #define E_MUX0_PIN 29 // E2_STEP_PIN -#endif -#ifndef E_MUX1_PIN - #define E_MUX1_PIN 28 // E2_DIR_PIN -#endif -#ifndef E_MUX2_PIN - #define E_MUX2_PIN 39 // E2_ENABLE_PIN +#if HAS_PRUSA_MMU1 + #ifndef E_MUX0_PIN + #define E_MUX0_PIN 29 // E2_STEP_PIN + #endif + #ifndef E_MUX1_PIN + #define E_MUX1_PIN 28 // E2_DIR_PIN + #endif + #ifndef E_MUX2_PIN + #define E_MUX2_PIN 39 // E2_ENABLE_PIN + #endif #endif ////////////////////////// diff --git a/Marlin/src/pins/ramps/pins_TT_OSCAR.h b/Marlin/src/pins/ramps/pins_TT_OSCAR.h index 277b1af2de86a..9d844ebcdcba8 100644 --- a/Marlin/src/pins/ramps/pins_TT_OSCAR.h +++ b/Marlin/src/pins/ramps/pins_TT_OSCAR.h @@ -252,15 +252,17 @@ // // Průša i3 MK2 Multiplexer Support // -//#ifndef E_MUX0_PIN -// #define E_MUX0_PIN 58 // Y_CS_PIN -//#endif -//#ifndef E_MUX1_PIN -// #define E_MUX1_PIN 53 // Z_CS_PIN -//#endif -//#ifndef E_MUX2_PIN -// #define E_MUX2_PIN 49 // En_CS_PIN -//#endif +#if 0 && HAS_PRUSA_MMU1 + #ifndef E_MUX0_PIN + #define E_MUX0_PIN 58 // Y_CS_PIN + #endif + #ifndef E_MUX1_PIN + #define E_MUX1_PIN 53 // Z_CS_PIN + #endif + #ifndef E_MUX2_PIN + #define E_MUX2_PIN 49 // En_CS_PIN + #endif +#endif ////////////////////////// // LCDs and Controllers // 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 a8ba9049efee8..5b48d7cadbcfd 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 @@ -236,8 +236,72 @@ #endif + #elif ENABLED(FYSETC_MINI_12864_2_1) + + #error "CAUTION! FYSETC_MINI_12864_2_1 / MKS_MINI_12864_V3 / BTT_MINI_12864_V1 requires wiring modifications. See 'pins_BTT_SKR_MINI_E3_common.h' for details. Comment out this line to continue." + + /** + * FYSETC_MINI_12864_2_1 / MKS_MINI_12864_V3 / BTT_MINI_12864_V1 display pinout + * + * Board Display + * ------ ------ + * PB5 |10 9 | PA15 (BEEP) |10 9 | BTN_ENC + * PA9 | 8 7 | RESET LCD_CS | 8 7 | LCD A0 + * PA10 | 6 5 | PB9 LCD_RST | 6 5 | RED + * PB8 | 4 3 | PB15 (GREEN) | 4 3 | (BLUE) + * GND | 2 1 | 5V GND | 2 1 | 5V + * ------ ------ + * EXP1 EXP1 + * + * --- ------ + * RST | 1 | (MISO) |10 9 | SCK + * (RX2) PA2 | 2 | BTN_EN1 | 8 7 | (SS) + * (TX2) PA3 | 3 | BTN_EN2 | 6 5 | MOSI + * GND | 4 | (CD) | 4 3 | (RST) + * 5V | 5 | (GND) | 2 1 | (KILL) + * --- ------ + * TFT EXP2 + * + * Needs custom cable: + * + * Board Display + * + * EXP1-1 ----------- EXP1-1 + * EXP1-2 ----------- EXP1-2 + * EXP1-3 ----------- EXP2-6 + * EXP1-4 ----------- EXP1-5 + * EXP1-5 ----------- EXP2-8 + * EXP1-6 ----------- EXP1-6 + * EXP1-8 ----------- EXP1-8 + * EXP1-9 ----------- EXP1-9 + * EXP1-10 ----------- EXP1-7 + * + * TFT-2 ----------- EXP2-9 + * TFT-3 ----------- EXP2-5 + * + * for backlight configuration see steps 2 (V2.1) and 3 in https://wiki.fysetc.com/Mini12864_Panel/ + */ + + #define LCD_PINS_RS PA9 // CS + #define LCD_PINS_ENABLE PA3 // MOSI + #define LCD_BACKLIGHT_PIN -1 + #define NEOPIXEL_PIN PB8 + #define LCD_CONTRAST 255 + #define LCD_RESET_PIN PA10 + + #define DOGLCD_CS PA9 + #define DOGLCD_A0 PB5 + #define DOGLCD_SCK PA2 + #define DOGLCD_MOSI PA3 + + #define BTN_ENC PA15 + #define BTN_EN1 PB9 + #define BTN_EN2 PB15 + + #define FORCE_SOFT_SPI + #else - #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." + #error "Only CR10_STOCKDISPLAY, ZONESTAR_LCD, ENDER2_STOCKDISPLAY, MKS_MINI_12864, TFTGLCD_PANEL_(SPI|I2C), FYSETC_MINI_12864_2_1, MKS_MINI_12864_V3, and BTT_MINI_12864_V1 are currently supported on the BIGTREE_SKR_MINI_E3." #endif #endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V24S1_301.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V24S1_301.h index 8616a8fb34061..fb7198e57c21a 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V24S1_301.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V24S1_301.h @@ -28,7 +28,11 @@ #include "env_validate.h" #if HAS_MULTI_HOTEND || E_STEPPERS > 1 - #error "Creality V4 only supports one hotend / E-stepper. Comment out this line to continue." + #error "Creality V24S1 only supports one hotend / E-stepper. Comment out this line to continue." +#endif + +#if BOTH(BLTOUCH, Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) + #error "Disable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN when using BLTOUCH with Creality V24S1-301." #endif #define BOARD_INFO_NAME "Creality V24S1-301" @@ -44,7 +48,7 @@ // // Limit Switches // -#define Z_STOP_PIN PC14 +#define Z_STOP_PIN PA15 #ifndef Z_MIN_PROBE_PIN #define Z_MIN_PROBE_PIN PC14 // BLTouch IN @@ -63,4 +67,22 @@ #define HEATER_BED_PIN PA7 // HOT BED #define FAN1_PIN PC0 // extruder fan +// +// SD Card +// +#define ONBOARD_SPI_DEVICE 1 +#define ONBOARD_SD_CS_PIN PA4 // SDSS + +// +// M3/M4/M5 - Spindle/Laser Control +// +#if HAS_CUTTER + //#define HEATER_0_PIN -1 + //#define HEATER_BED_PIN -1 + #define FAN_PIN -1 + #define SPINDLE_LASER_ENA_PIN PA0 // FET 1 + #define SPINDLE_LASER_PWM_PIN PA0 // Bed FET + #define SPINDLE_DIR_PIN PA0 // FET 4 +#endif + #include "pins_CREALITY_V4.h" diff --git a/Marlin/src/pins/stm32f4/pins_INDEX_REV03.h b/Marlin/src/pins/stm32f4/pins_INDEX_REV03.h index a9828c5bdaef6..977f4763437ce 100644 --- a/Marlin/src/pins/stm32f4/pins_INDEX_REV03.h +++ b/Marlin/src/pins/stm32f4/pins_INDEX_REV03.h @@ -60,12 +60,12 @@ // None of these require limit switches by default, so we leave these commented // here for your reference. -// #define I_MIN_PIN PA8 -// #define I_MAX_PIN PA8 -// #define J_MIN_PIN PD13 -// #define J_MAX_PIN PD13 -// #define K_MIN_PIN PC9 -// #define K_MAX_PIN PC9 +//#define I_MIN_PIN PA8 +//#define I_MAX_PIN PA8 +//#define J_MIN_PIN PD13 +//#define J_MAX_PIN PD13 +//#define K_MIN_PIN PC9 +//#define K_MAX_PIN PC9 // // Steppers @@ -73,47 +73,81 @@ #define X_STEP_PIN PB15 #define X_DIR_PIN PB14 #define X_ENABLE_PIN PD9 -#define X_SERIAL_TX_PIN PD8 -#define X_SERIAL_RX_PIN PD8 #define Y_STEP_PIN PE15 #define Y_DIR_PIN PE14 #define Y_ENABLE_PIN PB13 -#define Y_SERIAL_TX_PIN PB12 -#define Y_SERIAL_RX_PIN PB12 #define Z_STEP_PIN PE7 #define Z_DIR_PIN PB1 #define Z_ENABLE_PIN PE9 -#define Z_SERIAL_TX_PIN PE8 -#define Z_SERIAL_RX_PIN PE8 #define I_STEP_PIN PC4 #define I_DIR_PIN PA4 #define I_ENABLE_PIN PB0 -#define I_SERIAL_TX_PIN PC5 -#define I_SERIAL_RX_PIN PC5 #define J_STEP_PIN PE11 #define J_DIR_PIN PE10 #define J_ENABLE_PIN PE13 -#define J_SERIAL_TX_PIN PE12 -#define J_SERIAL_RX_PIN PE12 -#define K_SERIAL_TX_PIN PA2 -#define K_SERIAL_RX_PIN PA2 #define K_STEP_PIN PD6 #define K_DIR_PIN PD7 #define K_ENABLE_PIN PA3 -// Reduce baud rate to improve software serial reliability -#define TMC_BAUD_RATE 19200 +#if HAS_TMC_SPI + /** + * Make sure to configure the jumpers on the back side of the Mobo according to + * this diagram: https://github.com/MarlinFirmware/Marlin/pull/23851 + */ + #error "SPI drivers require a custom jumper configuration, see comment above! Comment out this line to continue." + + #if AXIS_HAS_SPI(X) + #define X_CS_PIN PD8 + #endif + #if AXIS_HAS_SPI(Y) + #define Y_CS_PIN PB12 + #endif + #if AXIS_HAS_SPI(Z) + #define Z_CS_PIN PE8 + #endif + #if AXIS_HAS_SPI(I) + #define I_CS_PIN PC5 + #endif + #if AXIS_HAS_SPI(J) + #define J_CS_PIN PE12 + #endif + #if AXIS_HAS_SPI(K) + #define K_CS_PIN PA2 + #endif + +#elif HAS_TMC_UART + + #define X_SERIAL_TX_PIN PD8 + #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN + + #define Y_SERIAL_TX_PIN PB12 + #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN + + #define Z_SERIAL_TX_PIN PE8 + #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN + + #define I_SERIAL_TX_PIN PC5 + #define I_SERIAL_RX_PIN I_SERIAL_TX_PIN + + #define J_SERIAL_TX_PIN PE12 + #define J_SERIAL_RX_PIN J_SERIAL_TX_PIN + + #define K_SERIAL_TX_PIN PA2 + #define K_SERIAL_RX_PIN K_SERIAL_TX_PIN + + // Reduce baud rate to improve software serial reliability + #define TMC_BAUD_RATE 19200 + +#endif -// Not required for this board. Fails to compile otherwise. -// PD0 is not connected on this board. -#define TEMP_0_PIN PD0 - -// General use mosfets, useful for things like pumps and solenoids +// +// Heaters / Fans +// #define FAN_PIN PE2 #define FAN1_PIN PE3 #define FAN2_PIN PE4 @@ -121,16 +155,26 @@ #define FAN_SOFT_PWM_REQUIRED -// Neopixel Rings +// +// Neopixel +// #define NEOPIXEL_PIN PC7 #define NEOPIXEL2_PIN PC8 +// // SPI +// #define MISO_PIN PB4 #define MOSI_PIN PB5 #define SCK_PIN PB3 +#define TMC_SW_MISO MISO_PIN +#define TMC_SW_MOSI MOSI_PIN +#define TMC_SW_SCK SCK_PIN + +// // I2C +// #define I2C_SDA_PIN PB7 #define I2C_SCL_PIN PB6 diff --git a/Marlin/src/pins/stm32f4/pins_LERDGE_S.h b/Marlin/src/pins/stm32f4/pins_LERDGE_S.h index c904d57a1f0aa..e4fc97170c442 100644 --- a/Marlin/src/pins/stm32f4/pins_LERDGE_S.h +++ b/Marlin/src/pins/stm32f4/pins_LERDGE_S.h @@ -133,8 +133,10 @@ // // Průša i3 MK2 Multi Material Multiplexer Support // -//#define E_MUX0_PIN -1 -//#define E_MUX1_PIN -1 +#if HAS_PRUSA_MMU1 + //#define E_MUX0_PIN -1 + //#define E_MUX1_PIN -1 +#endif // // LED / Lighting diff --git a/Marlin/src/pins/stm32f4/pins_TH3D_EZBOARD_V2.h b/Marlin/src/pins/stm32f4/pins_TH3D_EZBOARD_V2.h index bd4798209e6ab..fd6b960542141 100644 --- a/Marlin/src/pins/stm32f4/pins_TH3D_EZBOARD_V2.h +++ b/Marlin/src/pins/stm32f4/pins_TH3D_EZBOARD_V2.h @@ -130,6 +130,20 @@ // Reduce baud rate to improve software serial reliability #define TMC_BAUD_RATE 19200 + + // Default TMC slave addresses + #ifndef X_SLAVE_ADDRESS + #define X_SLAVE_ADDRESS 0 + #endif + #ifndef Y_SLAVE_ADDRESS + #define Y_SLAVE_ADDRESS 1 + #endif + #ifndef Z_SLAVE_ADDRESS + #define Z_SLAVE_ADDRESS 2 + #endif + #ifndef E0_SLAVE_ADDRESS + #define E0_SLAVE_ADDRESS 3 + #endif #endif // diff --git a/Marlin/src/pins/stm32f4/pins_VAKE403D.h b/Marlin/src/pins/stm32f4/pins_VAKE403D.h index bb5507b29a06b..c6b24f9eca615 100644 --- a/Marlin/src/pins/stm32f4/pins_VAKE403D.h +++ b/Marlin/src/pins/stm32f4/pins_VAKE403D.h @@ -150,8 +150,10 @@ // // Průša i3 MK2 Multi Material Multiplexer Support // -//#define E_MUX0_PIN PG3 -//#define E_MUX1_PIN PG4 +#if HAS_PRUSA_MMU1 + //#define E_MUX0_PIN PG3 + //#define E_MUX1_PIN PG4 +#endif #define LED_PIN PB14 // Alive #define PS_ON_PIN PE0 diff --git a/Marlin/src/pins/stm32g0/pins_BTT_SKR_MINI_E3_V3_0.h b/Marlin/src/pins/stm32g0/pins_BTT_SKR_MINI_E3_V3_0.h index 7cbf9f9d58d19..2589a316b6b11 100644 --- a/Marlin/src/pins/stm32g0/pins_BTT_SKR_MINI_E3_V3_0.h +++ b/Marlin/src/pins/stm32g0/pins_BTT_SKR_MINI_E3_V3_0.h @@ -156,7 +156,7 @@ #define EXP1_09_PIN PA15 #define EXP1_03_PIN PD6 -#if EITHER(DWIN_CREALITY_LCD, IS_DWIN_MARLINUI) +#if HAS_DWIN_E3V2 || IS_DWIN_MARLINUI /** * ------ ------ ------ * (ENT) |10 9 | (BEEP) |10 9 | |10 9 | diff --git a/Marlin/src/sd/SdBaseFile.cpp b/Marlin/src/sd/SdBaseFile.cpp index 64d0ad68bd809..1c1e0c7d145a6 100644 --- a/Marlin/src/sd/SdBaseFile.cpp +++ b/Marlin/src/sd/SdBaseFile.cpp @@ -1140,8 +1140,8 @@ bool SdBaseFile::openNext(SdBaseFile *dirFile, uint8_t oflag) { // We can't reconvert to UTF-8 here as UTF-8 is variable-size encoding, but joining LFN blocks // needs static bytes addressing. So here just store full UTF-16LE words to re-convert later. uint16_t idx = (startOffset + i) * 2; // This is fixed as FAT LFN always contain UTF-16LE encoding - longFilename[idx] = utf16_ch & 0xFF; - longFilename[idx + 1] = (utf16_ch >> 8) & 0xFF; + lname[idx] = utf16_ch & 0xFF; + lname[idx + 1] = (utf16_ch >> 8) & 0xFF; #else // Replace all multibyte characters to '_' lname[startOffset + i] = (utf16_ch > 0xFF) ? '_' : (utf16_ch & 0xFF); diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index 9966773418945..724de8f82a2f0 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -33,7 +33,7 @@ #if ENABLED(DWIN_CREALITY_LCD) #include "../lcd/e3v2/creality/dwin.h" -#elif ENABLED(DWIN_CREALITY_LCD_ENHANCED) +#elif ENABLED(DWIN_LCD_PROUI) #include "../lcd/e3v2/proui/dwin.h" #endif @@ -195,7 +195,7 @@ char *createFilename(char * const buffer, const dir_t &p) { } // -// Return 'true' if the item is something Marlin can read +// Return 'true' if the item is a folder, G-code file or Binary file // bool CardReader::is_visible_entity(const dir_t &p OPTARG(CUSTOM_FIRMWARE_UPLOAD, bool onlyBin/*=false*/)) { //uint8_t pn0 = p.name[0]; @@ -212,14 +212,15 @@ bool CardReader::is_visible_entity(const dir_t &p OPTARG(CUSTOM_FIRMWARE_UPLOAD, ) return false; flag.filenameIsDir = DIR_IS_SUBDIR(&p); // We know it's a File or Folder + setBinFlag(p.name[8] == 'B' && // List .bin files (a firmware file for flashing) + p.name[9] == 'I' && + p.name[10]== 'N'); return ( flag.filenameIsDir // All Directories are ok + || fileIsBinary() // BIN files are accepted || (!onlyBin && p.name[8] == 'G' && p.name[9] != '~') // Non-backup *.G* files are accepted - || ( onlyBin && p.name[8] == 'B' - && p.name[9] == 'I' - && p.name[10] == 'N') // BIN files are accepted ); } @@ -867,6 +868,7 @@ void CardReader::selectFileByIndex(const uint16_t nr) { strcpy(filename, sortshort[nr]); strcpy(longFilename, sortnames[nr]); flag.filenameIsDir = IS_DIR(nr); + setBinFlag(strcmp_P(strrchr(filename, '.'), PSTR(".BIN")) == 0); return; } #endif @@ -884,6 +886,7 @@ void CardReader::selectFileByName(const char * const match) { strcpy(filename, sortshort[nr]); strcpy(longFilename, sortnames[nr]); flag.filenameIsDir = IS_DIR(nr); + setBinFlag(strcmp_P(strrchr(filename, '.'), PSTR(".BIN")) == 0); return; } #endif diff --git a/Marlin/src/sd/cardreader.h b/Marlin/src/sd/cardreader.h index 2b3dcd00fbfbf..483ab81395848 100644 --- a/Marlin/src/sd/cardreader.h +++ b/Marlin/src/sd/cardreader.h @@ -80,6 +80,9 @@ typedef struct { filenameIsDir:1, workDirIsRoot:1, abort_sd_printing:1 + #if DO_LIST_BIN_FILES + , filenameIsBin:1 + #endif #if ENABLED(BINARY_FILE_TRANSFER) , binary_mode:1 #endif @@ -218,6 +221,10 @@ class CardReader { static void removeJobRecoveryFile(); #endif + // Binary flag for the current file + static bool fileIsBinary() { return TERN0(DO_LIST_BIN_FILES, flag.filenameIsBin); } + static void setBinFlag(const bool bin) { TERN(DO_LIST_BIN_FILES, flag.filenameIsBin = bin, UNUSED(bin)); } + // Current Working Dir - Set by cd, cdup, cdroot, and diveToFile(true, ...) static char* getWorkDirName() { workDir.getDosName(filename); return filename; } static SdFile& getWorkDir() { return workDir.isOpen() ? workDir : root; } diff --git a/buildroot/share/PlatformIO/boards/marlin_STM32F407VET6_CCM.json b/buildroot/share/PlatformIO/boards/marlin_STM32F407VET6_CCM.json new file mode 100644 index 0000000000000..faf32c200e474 --- /dev/null +++ b/buildroot/share/PlatformIO/boards/marlin_STM32F407VET6_CCM.json @@ -0,0 +1,56 @@ +{ + "build": { + "core": "stm32", + "cpu": "cortex-m4", + "extra_flags": "-DSTM32F407xx -DSTM32F4", + "f_cpu": "168000000L", + "hwids": [ + [ + "0x1EAF", + "0x0003" + ], + [ + "0x0483", + "0x3748" + ] + ], + "mcu": "stm32f407vet6", + "product_line": "STM32F407xx", + "variant": "Generic_F4x7Vx" + }, + "debug": { + "default_tools": [ + "stlink" + ], + "jlink_device": "STM32F407VE", + "openocd_extra_args": [ + "-c", + "reset_config none" + ], + "openocd_target": "stm32f4x", + "svd_path": "STM32F40x.svd" + }, + "frameworks": [ + "arduino", + "cmsis", + "stm32cube", + "libopencm3" + ], + "name": "STM32F407VE (128k RAM, 64k CCM RAM, 512k Flash", + "upload": { + "disable_flushing": false, + "maximum_ram_size": 131072, + "maximum_size": 524288, + "protocol": "stlink", + "protocols": [ + "stlink", + "dfu", + "jlink" + ], + "require_upload_port": true, + "use_1200bps_touch": false, + "wait_for_upload_port": false + }, + "url": "https://www.st.com/content/st_com/en/products/microcontrollers/stm32-32-bit-arm-cortex-mcus/stm32-high-performance-mcus/stm32f4-series/stm32f407-417/stm32f407vg.html", + "vendor": "Generic" +} diff --git a/buildroot/share/PlatformIO/variants/MARLIN_G0B1RE/variant_MARLIN_STM32G0B1RE.cpp b/buildroot/share/PlatformIO/variants/MARLIN_G0B1RE/variant_MARLIN_STM32G0B1RE.cpp index e53fb4182c2ed..8af7150dc7815 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_G0B1RE/variant_MARLIN_STM32G0B1RE.cpp +++ b/buildroot/share/PlatformIO/variants/MARLIN_G0B1RE/variant_MARLIN_STM32G0B1RE.cpp @@ -115,11 +115,11 @@ extern "C" { * AHB Prescaler = 1 * APB1 Prescaler = 1 * PLL_M = 1 - * PLL_N = 16 - * PLL_R = 2 + * PLL_N = 24 + * PLL_R = 3 * PLL_P = 2 - * PLL_Q = 2 - * USB(Hz) = 48000000 (HSI48M) + * PLL_Q = 4 + * USB(Hz) = 48000000 (PLLQ) * @param None * @retval None */ @@ -129,22 +129,31 @@ WEAK void SystemClock_Config(void) RCC_ClkInitTypeDef RCC_ClkInitStruct = {0}; RCC_PeriphCLKInitTypeDef PeriphClkInit = {0}; + // Reset clock registers (in case bootloader has changed them) + RCC->CR |= RCC_CR_HSION; + while (!(RCC->CR & RCC_CR_HSIRDY)) + ; + RCC->CFGR = 0x00000000; + RCC->CR = RCC_CR_HSION; + while (RCC->CR & RCC_CR_PLLRDY) + ; + RCC->PLLCFGR = 0x00001000; + /** Configure the main internal regulator output voltage */ HAL_PWREx_ControlVoltageScaling(PWR_REGULATOR_VOLTAGE_SCALE1); /** Initializes the RCC Oscillators according to the specified parameters * in the RCC_OscInitTypeDef structure. */ - RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE|RCC_OSCILLATORTYPE_HSI48; + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; RCC_OscInitStruct.HSEState = RCC_HSE_ON; - RCC_OscInitStruct.HSI48State = RCC_HSI48_ON; RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; RCC_OscInitStruct.PLL.PLLM = RCC_PLLM_DIV1; - RCC_OscInitStruct.PLL.PLLN = 16; + RCC_OscInitStruct.PLL.PLLN = 24; RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; - RCC_OscInitStruct.PLL.PLLQ = RCC_PLLQ_DIV2; - RCC_OscInitStruct.PLL.PLLR = RCC_PLLR_DIV2; + RCC_OscInitStruct.PLL.PLLQ = RCC_PLLQ_DIV4; + RCC_OscInitStruct.PLL.PLLR = RCC_PLLR_DIV3; if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) { Error_Handler(); @@ -164,7 +173,7 @@ WEAK void SystemClock_Config(void) /** Initializes the peripherals clocks */ PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_USB; - PeriphClkInit.UsbClockSelection = RCC_USBCLKSOURCE_HSI48; + PeriphClkInit.UsbClockSelection = RCC_USBCLKSOURCE_PLL; if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK) { Error_Handler(); diff --git a/buildroot/share/vscode/MarlinFirmware.code-workspace b/buildroot/share/vscode/MarlinFirmware.code-workspace new file mode 100644 index 0000000000000..bd433b07f0e25 --- /dev/null +++ b/buildroot/share/vscode/MarlinFirmware.code-workspace @@ -0,0 +1,4 @@ +{ + "folders": [ { "path": "../../.." } ], + "extensions": { "recommendations": [ "marlinfirmware.auto-build" ] } +} diff --git a/buildroot/tests/DUE b/buildroot/tests/DUE index 5810b73bdca8e..9b968cbd8d4df 100755 --- a/buildroot/tests/DUE +++ b/buildroot/tests/DUE @@ -37,7 +37,7 @@ exec_test $1 $2 "RAMPS4DUE_EFB with ABL (Bilinear), ExtUI, S-Curve, many options restore_configs opt_set MOTHERBOARD BOARD_RADDS NUM_Z_STEPPER_DRIVERS 3 opt_enable USE_XMAX_PLUG USE_YMAX_PLUG ENDSTOPPULLUPS BLTOUCH AUTO_BED_LEVELING_BILINEAR \ - Z_STEPPER_AUTO_ALIGN Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS Z_SAFE_HOMING + Z_STEPPER_AUTO_ALIGN Z_STEPPER_ALIGN_STEPPER_XY Z_SAFE_HOMING pins_set ramps/RAMPS X_MAX_PIN -1 pins_set ramps/RAMPS Y_MAX_PIN -1 exec_test $1 $2 "RADDS with ABL (Bilinear), Triple Z Axis, Z_STEPPER_AUTO_ALIGN, E_DUAL_STEPPER_DRIVERS" "$3" diff --git a/buildroot/tests/STM32F103RE_creality b/buildroot/tests/STM32F103RE_creality index 257616ddd172c..6440c56792242 100755 --- a/buildroot/tests/STM32F103RE_creality +++ b/buildroot/tests/STM32F103RE_creality @@ -15,8 +15,9 @@ exec_test $1 $2 "Ender 3 v2 with CrealityUI" "$3" use_example_configs "Creality/Ender-3 V2/CrealityV422/CrealityUI" opt_disable DWIN_CREALITY_LCD -opt_enable DWIN_CREALITY_LCD_ENHANCED BLTOUCH AUTO_BED_LEVELING_UBL Z_SAFE_HOMING INDIVIDUAL_AXIS_HOMING_SUBMENU LCD_SET_PROGRESS_MANUALLY STATUS_MESSAGE_SCROLLING BAUD_RATE_GCODE -exec_test $1 $2 "Ender 3 v2 with Enhanced UI" "$3" +opt_enable BLTOUCH AUTO_BED_LEVELING_UBL Z_SAFE_HOMING INDIVIDUAL_AXIS_HOMING_SUBMENU LCD_SET_PROGRESS_MANUALLY STATUS_MESSAGE_SCROLLING BAUD_RATE_GCODE \ + DWIN_LCD_PROUI SOUND_MENU_ITEM PRINTCOUNTER +exec_test $1 $2 "Ender 3 v2 with ProUI" "$3" use_example_configs "Creality/Ender-3 V2/CrealityV422/CrealityUI" opt_disable DWIN_CREALITY_LCD diff --git a/ini/features.ini b/ini/features.ini index 720748d7f05d8..9150ff54516b9 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -18,13 +18,14 @@ POSTMORTEM_DEBUGGING = src_filter=+ + + + + + + src_filter=+ + + + + +HAS_T(RINAMIC_CONFIG|MC_SPI) = src_filter=+ HAS_STEALTHCHOP = src_filter=+ SR_LCD_3W_NL = SailfishLCD=https://github.com/mikeshub/SailfishLCD/archive/master.zip HAS_MOTOR_CURRENT_I2C = SlowSoftI2CMaster src_filter=+ HAS_TMC26X = TMC26XStepper=https://github.com/trinamic/TMC26XStepper/archive/master.zip - src_filter=+ + src_filter=+ HAS_L64XX = Arduino-L6470@0.8.0 src_filter=+ + + + LIB_INTERNAL_MAX31865 = src_filter=+ @@ -34,7 +35,7 @@ I2C_AMMETER = peterus/INA226Lib@1.1.2 USES_LIQUIDCRYSTAL = LiquidCrystal=https://github.com/MarlinFirmware/New-LiquidCrystal/archive/1.5.1.zip USES_LIQUIDCRYSTAL_I2C = marcoschwartz/LiquidCrystal_I2C@1.1.4 USES_LIQUIDTWI2 = LiquidTWI2@1.2.7 -HAS_WIRED_LCD = src_filter=+ +HAS_LCDPRINT = src_filter=+ HAS_MARLINUI_HD44780 = src_filter=+ HAS_MARLINUI_U8GLIB = U8glib-HAL@~0.5.0 src_filter=+ @@ -46,7 +47,7 @@ SOFT_I2C_EEPROM = SlowSoftI2CMaster, SlowSoftWire=https:/ SPI_EEPROM = src_filter=+ HAS_DWIN_E3V2|IS_DWIN_MARLINUI = src_filter=+ DWIN_CREALITY_LCD = src_filter=+ -DWIN_CREALITY_LCD_ENHANCED = src_filter=+ +DWIN_LCD_PROUI = src_filter=+ DWIN_CREALITY_LCD_JYERSUI = src_filter=+ IS_DWIN_MARLINUI = src_filter=+ HAS_GRAPHICAL_TFT = src_filter=+ @@ -97,7 +98,7 @@ USB_FLASH_DRIVE_SUPPORT = src_filter=+ + AUTO_BED_LEVELING_BILINEAR = src_filter=+ AUTO_BED_LEVELING_(3POINT|(BI)?LINEAR) = src_filter=+ -X_AXIS_TWIST_COMPENSATION = src_filter=+ + +X_AXIS_TWIST_COMPENSATION = src_filter=+ + + MESH_BED_LEVELING = src_filter=+ + AUTO_BED_LEVELING_UBL = src_filter=+ + UBL_HILBERT_CURVE = src_filter=+ @@ -233,7 +234,7 @@ HAS_SERVOS = src_filter=+ + HAS_MICROSTEPS = src_filter=+ (ESP3D_)?WIFISUPPORT = AsyncTCP, ESP Async WebServer - ESP3DLib=https://github.com/luc-github/ESP3DLib/archive/master.zip + ESP3DLib=https://github.com/luc-github/ESP3DLib/archive/master-2.0.7.zip arduinoWebSockets=links2004/WebSockets@2.3.4 luc-github/ESP32SSDP@^1.1.1 lib_ignore=ESPAsyncTCP diff --git a/ini/native.ini b/ini/native.ini index 5355284992cb3..3d196f3436499 100644 --- a/ini/native.ini +++ b/ini/native.ini @@ -34,14 +34,14 @@ src_filter = ${common.default_src_filter} + [simulator_common] platform = native framework = -build_flags = ${common.build_flags} -std=gnu++17 -D__PLAT_NATIVE_SIM__ -DU8G_HAL_LINKS -I/usr/include/SDL2 -IMarlin -IMarlin/src/HAL/NATIVE_SIM/include -IMarlin/src/HAL/NATIVE_SIM/u8g +build_flags = ${common.build_flags} -std=gnu++17 -D__PLAT_NATIVE_SIM__ -DU8G_HAL_LINKS -I/usr/include/SDL2 -IMarlin -IMarlin/src/HAL/NATIVE_SIM/u8g src_build_flags = -Wall -Wno-expansion-to-defined -Wcast-align release_flags = -g0 -O3 -flto debug_build_flags = -fstack-protector-strong -g -g3 -ggdb lib_compat_mode = off src_filter = ${common.default_src_filter} + lib_deps = ${common.lib_deps} - MarlinSimUI=https://github.com/p3p/MarlinSimUI/archive/master.zip + MarlinSimUI=https://github.com/p3p/MarlinSimUI/archive/0.0.2.zip Adafruit NeoPixel=https://github.com/p3p/Adafruit_NeoPixel/archive/marlin_sim_native.zip LiquidCrystal=https://github.com/p3p/LiquidCrystal/archive/master.zip extra_scripts = ${common.extra_scripts} diff --git a/ini/renamed.ini b/ini/renamed.ini index bc1e438d60c1b..b325476d2f9e8 100644 --- a/ini/renamed.ini +++ b/ini/renamed.ini @@ -9,17 +9,42 @@ # # ################################# +# +# A platform that doesn't match anything in pins.h +# + +[renamed] +platform = ststm32 +board = genericSTM32F103RE + # # List of environment names that are no longer used # [env:STM32F103RET6_creality_maple] -extends = env:STM32F103RE_maple +# Renamed to STM32F103RE_creality_maple +extends = renamed [env:STM32F103RET6_creality] -extends = STM32F103Rx_creality -board = genericSTM32F103RE +# Renamed to STM32F103RE_creality +extends = renamed [env:STM32F103RET6_creality_xfer] -extends = STM32F103Rx_creality_xfer -board = genericSTM32F103RE +# Renamed to STM32F103RE_creality_xfer +extends = renamed + +[env:STM32F103RC_btt_512K] +# Renamed to STM32F103RE_btt +extends = renamed + +[env:STM32F103RC_btt_512K_USB] +# Renamed to STM32F103RE_btt_USB +extends = renamed + +[env:STM32F103RC_btt_512K_maple] +# Renamed to STM32F103RE_btt_maple +extends = renamed + +[env:STM32F103RC_btt_512K_USB_maple] +# Renamed to STM32F103RE_btt_USB_maple +extends = renamed diff --git a/ini/stm32-common.ini b/ini/stm32-common.ini index 54bc746ff4ffb..1d3f858bf8e9e 100644 --- a/ini/stm32-common.ini +++ b/ini/stm32-common.ini @@ -16,6 +16,7 @@ build_flags = ${common.build_flags} -std=gnu++14 -DHAL_STM32 -DUSBCON -DUSBD_USE_CDC -DTIM_IRQ_PRIO=13 + -DADC_RESOLUTION=12 build_unflags = -std=gnu++11 src_filter = ${common.default_src_filter} + + extra_scripts = ${common.extra_scripts} diff --git a/ini/stm32f4.ini b/ini/stm32f4.ini index c7d70dd01de27..d7c160d63942f 100644 --- a/ini/stm32f4.ini +++ b/ini/stm32f4.ini @@ -298,9 +298,8 @@ extends = env:BIGTREE_OCTOPUS_PRO_V1_F429 platform_packages = ${stm_flash_drive.platform_packages} build_unflags = -DUSBD_USE_CDC build_flags = ${stm_flash_drive.build_flags} - -DSTM32F446_5VX -DUSE_USB_HS_IN_FS - -DUSE_USBHOST_HS -DUSBD_IRQ_PRIO=5 - -DUSBD_IRQ_SUBPRIO=6 + -DUSE_USB_HS_IN_FS -DUSE_USBHOST_HS + -DUSBD_IRQ_PRIO=5 -DUSBD_IRQ_SUBPRIO=6 -DUSBD_USE_CDC_MSC # @@ -440,6 +439,29 @@ build_flags = ${env:mks_robin_nano_v3_usb_flash_drive.build_flags} -DUSBD_USE_CDC_MSC build_unflags = -DUSBD_USE_CDC +# +# MKS Robin Nano V3_1 +# +[env:mks_robin_nano_v3_1] +extends = env:mks_robin_nano_v3 +board = marlin_STM32F407VET6_CCM + +# +# MKS Robin Nano V3.1 with USB Flash Drive Support +# Currently, using a STM32duino fork, until USB Host get merged +# +[env:mks_robin_nano_v3_1_usb_flash_drive] +extends = env:mks_robin_nano_v3_usb_flash_drive +board = marlin_STM32F407VET6_CCM + +# +# MKS Robin Nano V3.1 with USB Flash Drive Support and Shared Media +# Currently, using a STM32duino fork, until USB Host and USB Device MSC get merged +# +[env:mks_robin_nano_v3_1_usb_flash_drive_msc] +extends = env:mks_robin_nano_v3_usb_flash_drive_msc +board = marlin_STM32F407VET6_CCM + # # MKS Eagle # 5 TMC2209 uart mode on board diff --git a/ini/stm32g0.ini b/ini/stm32g0.ini index 171945ffe2f0a..e6094c1e312db 100644 --- a/ini/stm32g0.ini +++ b/ini/stm32g0.ini @@ -30,7 +30,6 @@ board = marlin_STM32G0B1RE board_build.offset = 0x2000 board_upload.offset_address = 0x08002000 build_flags = ${stm32_variant.build_flags} - -DADC_RESOLUTION=12 -DPIN_SERIAL4_RX=PC_11 -DPIN_SERIAL4_TX=PC_10 -DSERIAL_RX_BUFFER_SIZE=1024 -DSERIAL_TX_BUFFER_SIZE=1024 -DTIMER_SERVO=TIM3 -DTIMER_TONE=TIM4 diff --git a/platformio.ini b/platformio.ini index 3a02b5ab185be..0e50da2b7392e 100644 --- a/platformio.ini +++ b/platformio.ini @@ -100,7 +100,6 @@ default_src_filter = + - - + - - - - - - - - - - - - @@ -151,6 +150,7 @@ default_src_filter = + - - + - - - - + - - - - -