From 8e0066eca538fe3027c8c9cdfbc3ef7124b4da37 Mon Sep 17 00:00:00 2001 From: Daniel Mejia <2473632+damvcoool@users.noreply.github.com> Date: Sat, 4 Apr 2020 16:40:38 -0400 Subject: [PATCH] Update to Marlin 2.0.5.3 --- Marlin/Configuration.h | 5 +- Marlin/Configuration_adv.h | 152 ++++++++---- Marlin/Version.h | 2 +- ...persistent_store_eeprom.cpp => eeprom.cpp} | 2 +- Marlin/src/HAL/AVR/fastio.h | 4 +- Marlin/src/HAL/DUE/EepromEmulation.cpp | 2 +- ...persistent_store_eeprom.cpp => eeprom.cpp} | 2 +- Marlin/src/HAL/DUE/fastio.h | 2 +- Marlin/src/HAL/DUE/fastio/G2_PWM.cpp | 155 ++++++++---- Marlin/src/HAL/DUE/inc/Conditionals_post.h | 2 +- ...sistent_store_impl.cpp => eeprom_impl.cpp} | 2 +- Marlin/src/HAL/ESP32/fastio.h | 2 +- Marlin/src/HAL/ESP32/inc/Conditionals_post.h | 2 +- ...sistent_store_impl.cpp => eeprom_impl.cpp} | 2 +- .../{persistent_store_api.h => eeprom_api.h} | 2 +- ...stent_store_flash.cpp => eeprom_flash.cpp} | 2 +- ...ent_store_sdcard.cpp => eeprom_sdcard.cpp} | 2 +- Marlin/src/HAL/LPC1768/fastio.h | 2 +- .../src/HAL/LPC1768/inc/Conditionals_post.h | 2 +- Marlin/src/HAL/LPC1768/main.cpp | 2 +- Marlin/src/HAL/SAMD51/QSPIFlash.cpp | 78 ++++++ Marlin/src/HAL/SAMD51/QSPIFlash.h | 51 ++++ Marlin/src/HAL/SAMD51/eeprom.cpp | 66 +++++ Marlin/src/HAL/SAMD51/eeprom_flash.cpp | 96 ++++++++ Marlin/src/HAL/SAMD51/eeprom_qspi.cpp | 71 ++++++ Marlin/src/HAL/SAMD51/fastio.h | 4 +- Marlin/src/HAL/SAMD51/inc/Conditionals_post.h | 4 +- .../HAL/SAMD51/persistent_store_eeprom.cpp | 129 ---------- Marlin/src/HAL/STM32/SoftwareSerial.h | 9 +- ...stent_store_flash.cpp => eeprom_flash.cpp} | 2 +- ...sistent_store_impl.cpp => eeprom_impl.cpp} | 12 +- ...ent_store_sdcard.cpp => eeprom_sdcard.cpp} | 2 +- Marlin/src/HAL/STM32/inc/Conditionals_post.h | 2 +- ...persistent_store_eeprom.cpp => eeprom.cpp} | 6 +- ...stent_store_flash.cpp => eeprom_flash.cpp} | 7 +- ...ent_store_sdcard.cpp => eeprom_sdcard.cpp} | 3 +- ...persistent_store_eeprom.cpp => eeprom.cpp} | 2 +- .../HAL/STM32_F4_F7/inc/Conditionals_post.h | 2 +- ...sistent_store_impl.cpp => eeprom_impl.cpp} | 2 +- Marlin/src/HAL/TEENSY31_32/fastio.h | 3 +- .../HAL/TEENSY31_32/inc/Conditionals_post.h | 2 +- ...persistent_store_eeprom.cpp => eeprom.cpp} | 2 +- Marlin/src/HAL/TEENSY35_36/fastio.h | 3 +- ...ersistent_store_api.cpp => eeprom_api.cpp} | 2 +- .../{persistent_store_api.h => eeprom_api.h} | 0 Marlin/src/MarlinCore.cpp | 68 ++---- Marlin/src/MarlinCore.h | 2 + Marlin/src/core/boards.h | 1 + Marlin/src/core/macros.h | 3 + Marlin/src/feature/backlash.cpp | 2 +- Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp | 2 +- Marlin/src/feature/max7219.cpp | 2 +- Marlin/src/feature/mmu2/mmu2.cpp | 3 +- Marlin/src/feature/pause.cpp | 39 ++- Marlin/src/feature/pause.h | 2 - Marlin/src/feature/twibus.cpp | 56 ++--- Marlin/src/feature/twibus.h | 7 +- Marlin/src/gcode/calibrate/G28.cpp | 20 +- Marlin/src/gcode/calibrate/G425.cpp | 144 ++++++----- Marlin/src/gcode/calibrate/M425.cpp | 6 +- Marlin/src/gcode/config/M43.cpp | 12 +- Marlin/src/gcode/feature/camera/M240.cpp | 10 +- Marlin/src/gcode/feature/powerloss/M1000.cpp | 2 +- Marlin/src/gcode/gcode.cpp | 6 +- Marlin/src/gcode/gcode.h | 4 + Marlin/src/gcode/lcd/M0_M1.cpp | 37 +-- Marlin/src/gcode/motion/G2_G3.cpp | 2 +- Marlin/src/gcode/sd/M1001.cpp | 109 +++++++++ Marlin/src/gcode/temp/M303.cpp | 29 ++- Marlin/src/inc/Conditionals_adv.h | 2 +- Marlin/src/inc/Conditionals_post.h | 24 +- Marlin/src/inc/MarlinConfig.h | 3 +- Marlin/src/inc/Version.h | 4 +- .../ftdi_eve_lib/basic/spi.cpp | 11 + .../ftdi_eve_touch_ui/ftdi_eve_lib/compat.h | 21 +- .../ftdi_eve_lib/extended/event_loop.cpp | 2 +- .../ftdi_eve_touch_ui/language/language_en.h | 14 +- .../lib/ftdi_eve_touch_ui/marlin_events.cpp | 8 +- .../lib/ftdi_eve_touch_ui/pin_mappings.h | 15 +- .../screens/about_screen.cpp | 78 +++--- .../screens/advanced_settings_menu.cpp | 154 ++++++------ .../base_numeric_adjustment_screen.cpp | 12 +- .../ftdi_eve_touch_ui/screens/base_screen.cpp | 8 +- .../screens/bio_advanced_settings.cpp | 2 +- .../screens/bio_confirm_home_e.cpp | 12 +- .../screens/bio_confirm_home_xyz.cpp | 10 +- .../screens/bio_main_menu.cpp | 4 +- .../ftdi_eve_touch_ui/screens/boot_screen.cpp | 14 +- .../screens/change_filament_screen.cpp | 3 +- .../screens/interface_settings_screen.cpp | 12 +- .../screens/interface_sounds_screen.cpp | 2 +- .../ftdi_eve_touch_ui/screens/main_menu.cpp | 165 +++++++------ .../screens/preheat_menu.cpp | 83 +++++++ .../screens/preheat_timer_screen.cpp | 3 - .../lib/ftdi_eve_touch_ui/screens/screens.cpp | 1 + .../lib/ftdi_eve_touch_ui/screens/screens.h | 9 +- .../screens/status_screen.cpp | 226 ++++++++--------- .../lib/ftdi_eve_touch_ui/theme/colors.h | 228 ++++++++++-------- .../theme/marlin_bootscreen_landscape.h | 4 +- .../theme/marlin_bootscreen_portrait.h | 4 +- Marlin/src/lcd/extui/ui_api.h | 4 +- Marlin/src/lcd/extui_dgus_lcd.cpp | 6 +- Marlin/src/lcd/extui_example.cpp | 4 +- Marlin/src/lcd/extui_malyan_lcd.cpp | 2 +- Marlin/src/lcd/language/language_en.h | 4 + Marlin/src/lcd/language/language_fr.h | 4 +- Marlin/src/lcd/language/language_it.h | 8 + Marlin/src/lcd/language/language_ru.h | 5 + Marlin/src/lcd/menu/menu_advanced.cpp | 2 +- Marlin/src/lcd/menu/menu_backlash.cpp | 6 +- Marlin/src/lcd/menu/menu_delta_calibrate.cpp | 4 +- Marlin/src/lcd/ultralcd.cpp | 34 +-- Marlin/src/libs/numtostr.cpp | 2 +- Marlin/src/module/configuration_store.cpp | 45 +++- Marlin/src/module/configuration_store.h | 2 +- Marlin/src/module/motion.cpp | 28 ++- Marlin/src/module/motion.h | 4 + Marlin/src/module/planner.cpp | 100 ++++---- Marlin/src/module/planner.h | 24 +- Marlin/src/module/printcounter.cpp | 2 +- Marlin/src/module/printcounter.h | 4 +- Marlin/src/module/probe.cpp | 10 +- Marlin/src/module/temperature.cpp | 28 +-- Marlin/src/module/tool_change.cpp | 6 +- Marlin/src/pins/mega/pins_INTAMSYS40.h | 152 ++++++++++++ Marlin/src/pins/pins.h | 2 + Marlin/src/pins/rambo/pins_RAMBO.h | 11 + .../src/pins/ramps/pins_FORMBOT_TREX2PLUS.h | 9 + Marlin/src/pins/ramps/pins_RAMPS.h | 8 +- Marlin/src/pins/ramps/pins_TRIGORILLA_14.h | 36 +-- Marlin/src/pins/samd/pins_RAMPS_144.h | 3 +- Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h | 16 +- Marlin/src/sd/cardreader.cpp | 3 +- Marlin/src/sd/cardreader.h | 1 - bin/SKR_Mini_E3_v1.2_256K_BLTouch_v3.1.bin | Bin 211660 -> 211740 bytes ...SKR_Mini_E3_v1.2_256K_Manual_Bed_Level.bin | Bin 204916 -> 204868 bytes .../PlatformIO/scripts/STM32F103RC_fysetc.py | 2 +- buildroot/share/tests/mega2560-tests | 37 --- buildroot/share/tests/rambo-tests | 35 +++ config/README.md | 2 +- .../SKR Mini E3 1.2 BLTouch/Configuration.h | 5 +- .../Configuration_adv.h | 152 ++++++++---- config/SKR Mini E3 1.2/Configuration.h | 5 +- config/SKR Mini E3 1.2/Configuration_adv.h | 154 ++++++++---- platformio.ini | 10 +- 145 files changed, 2290 insertions(+), 1305 deletions(-) rename Marlin/src/HAL/AVR/{persistent_store_eeprom.cpp => eeprom.cpp} (97%) rename Marlin/src/HAL/DUE/{persistent_store_eeprom.cpp => eeprom.cpp} (98%) rename Marlin/src/HAL/ESP32/{persistent_store_impl.cpp => eeprom_impl.cpp} (97%) rename Marlin/src/HAL/LINUX/{persistent_store_impl.cpp => eeprom_impl.cpp} (98%) rename Marlin/src/HAL/LPC1768/{persistent_store_api.h => eeprom_api.h} (95%) rename Marlin/src/HAL/LPC1768/{persistent_store_flash.cpp => eeprom_flash.cpp} (99%) rename Marlin/src/HAL/LPC1768/{persistent_store_sdcard.cpp => eeprom_sdcard.cpp} (99%) create mode 100644 Marlin/src/HAL/SAMD51/QSPIFlash.cpp create mode 100644 Marlin/src/HAL/SAMD51/QSPIFlash.h create mode 100644 Marlin/src/HAL/SAMD51/eeprom.cpp create mode 100644 Marlin/src/HAL/SAMD51/eeprom_flash.cpp create mode 100644 Marlin/src/HAL/SAMD51/eeprom_qspi.cpp delete mode 100644 Marlin/src/HAL/SAMD51/persistent_store_eeprom.cpp rename Marlin/src/HAL/STM32/{persistent_store_flash.cpp => eeprom_flash.cpp} (99%) rename Marlin/src/HAL/STM32/{persistent_store_impl.cpp => eeprom_impl.cpp} (91%) rename Marlin/src/HAL/STM32/{persistent_store_sdcard.cpp => eeprom_sdcard.cpp} (98%) rename Marlin/src/HAL/STM32F1/{persistent_store_eeprom.cpp => eeprom.cpp} (95%) rename Marlin/src/HAL/STM32F1/{persistent_store_flash.cpp => eeprom_flash.cpp} (95%) rename Marlin/src/HAL/STM32F1/{persistent_store_sdcard.cpp => eeprom_sdcard.cpp} (98%) rename Marlin/src/HAL/STM32_F4_F7/{persistent_store_eeprom.cpp => eeprom.cpp} (98%) rename Marlin/src/HAL/TEENSY31_32/{persistent_store_impl.cpp => eeprom_impl.cpp} (97%) rename Marlin/src/HAL/TEENSY35_36/{persistent_store_eeprom.cpp => eeprom.cpp} (98%) rename Marlin/src/HAL/shared/{persistent_store_api.cpp => eeprom_api.cpp} (96%) rename Marlin/src/HAL/shared/{persistent_store_api.h => eeprom_api.h} (100%) create mode 100644 Marlin/src/gcode/sd/M1001.cpp create mode 100644 Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/preheat_menu.cpp create mode 100644 Marlin/src/pins/mega/pins_INTAMSYS40.h diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 4a235983..150736f2 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -108,9 +108,6 @@ /** * Select a secondary serial port on the board to use for communication with the host. - - - * :[-1, 0, 1, 2, 3, 4, 5, 6, 7] */ #define SERIAL_PORT_2 -1 @@ -2250,4 +2247,4 @@ //#define DEACTIVATE_SERVOS_AFTER_MOVE // Allow servo angle to be edited and saved to EEPROM -//#define EDITABLE_SERVO_ANGLES +//#define EDITABLE_SERVO_ANGLES \ No newline at end of file diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 4fc5efe4..cc502ba4 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -720,7 +720,6 @@ #define Z_STEPPER_ALIGN_AMP 1.0 #endif - #define G34_MAX_GRADE 5 // (%) Maximum incline that G34 will handle #define Z_STEPPER_ALIGN_ITERATIONS 3 // Number of iterations to apply during alignment #define Z_STEPPER_ALIGN_ACC 0.02 // Stop iterating early if the accuracy is better than this @@ -1035,9 +1034,6 @@ // The standard SD detect circuit reads LOW when media is inserted and HIGH when empty. // Enable this option and set to HIGH if your SD cards are incorrectly detected. - - - #define SD_DETECT_STATE HIGH #define SD_FINISHED_STEPPERRELEASE true // Disable steppers when SD Print is finished @@ -1249,10 +1245,6 @@ // Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese. //#define USE_SMALL_INFOFONT - - - - // Swap the CW/CCW indicators in the graphics overlay //#define OVERLAY_GFX_REVERSE @@ -1318,7 +1310,6 @@ //#define DGUS_SERIAL_STATS_RX_BUFFER_OVERRUNS // Fix Rx overrun situation (Currently only for AVR) #define DGUS_UPDATE_INTERVAL_MS 500 // (ms) Interval between automatic screen updates - #if EITHER(DGUS_LCD_UI_FYSETC, DGUS_LCD_UI_HIPRECY) #define DGUS_PRINT_FILENAME // Display the filename during printing @@ -1608,18 +1599,11 @@ // Add additional compensation depending on hotend temperature // Note: this values cannot be calibrated and have to be set manually #if ENABLED(PROBE_TEMP_COMPENSATION) - // Max temperature that can be reached by heated bed. - // This is required only for the calibration process. - #define PTC_MAX_BED_TEMP BED_MAXTEMP - // Park position to wait for probe cooldown - #define PTC_PARK_POS_X 0.0F - #define PTC_PARK_POS_Y 0.0F - #define PTC_PARK_POS_Z 100.0F + #define PTC_PARK_POS { 0, 0, 100 } // Probe position to probe and wait for probe to reach target temperature - #define PTC_PROBE_POS_X 90.0F - #define PTC_PROBE_POS_Y 100.0F + #define PTC_PROBE_POS { 90, 100 } // Enable additional compensation using hotend temperature // Note: this values cannot be calibrated automatically but have to be set manually @@ -2334,14 +2318,6 @@ */ //#define SENSORLESS_HOMING // StallGuard capable drivers only - - - - - - - - #if EITHER(SENSORLESS_HOMING, SENSORLESS_PROBING) // TMC2209: 0...255. TMC2130: -64...63 #define X_STALL_SENSITIVITY 8 @@ -2678,31 +2654,123 @@ #define SPINDLE_LASER_ACTIVE_HIGH false // Set to "true" if the on/off function is active HIGH #define SPINDLE_LASER_PWM true // Set to "true" if your controller supports setting the speed/power #define SPINDLE_LASER_PWM_INVERT true // Set to "true" if the speed/power goes up when you want it to go slower - #define SPINDLE_LASER_POWERUP_DELAY 5000 // (ms) Delay to allow the spindle/laser to come up to speed/power - #define SPINDLE_LASER_POWERDOWN_DELAY 5000 // (ms) Delay to allow the spindle to stop + + #define SPINDLE_LASER_FREQUENCY 2500 // (Hz) Spindle/laser frequency (only on supported HALs: AVR and LPC) + + /** + * Speed / Power can be set ('M3 S') and displayed in terms of: + * - PWM (S0 - S255) + * - PERCENT (S0 - S100) + * - RPM (S0 - S50000) Best for use with a spindle + */ + #define CUTTER_POWER_DISPLAY PWM + + /** + * Relative mode uses relative range (SPEED_POWER_MIN to SPEED_POWER_MAX) instead of normal range (0 to SPEED_POWER_MAX) + * Best use with SuperPID router controller where for example S0 = 5,000 RPM and S255 = 30,000 RPM + */ + //#define CUTTER_POWER_RELATIVE // Set speed proportional to [SPEED_POWER_MIN...SPEED_POWER_MAX] instead of directly #if ENABLED(SPINDLE_FEATURE) //#define SPINDLE_CHANGE_DIR // Enable if your spindle controller can change spindle direction #define SPINDLE_CHANGE_DIR_STOP // Enable if the spindle should stop before changing spin direction #define SPINDLE_INVERT_DIR false // Set to "true" if the spin direction is reversed + #define SPINDLE_LASER_POWERUP_DELAY 5000 // (ms) Delay to allow the spindle/laser to come up to speed/power + #define SPINDLE_LASER_POWERDOWN_DELAY 5000 // (ms) Delay to allow the spindle to stop + /** - * The M3 & M4 commands use the following equation to convert PWM duty cycle to speed/power - * - * SPEED/POWER = PWM duty cycle * SPEED_POWER_SLOPE + SPEED_POWER_INTERCEPT - * where PWM duty cycle varies from 0 to 255 + * M3/M4 uses the following equation to convert speed/power to PWM duty cycle + * Power = ((DC / 255 * 100) - SPEED_POWER_INTERCEPT)) * (1 / SPEED_POWER_SLOPE) + * where PWM DC varies from 0 to 255 * - * set the following for your controller (ALL MUST BE SET) + * Set these required parameters for your controller */ - #define SPEED_POWER_SLOPE 118.4 - #define SPEED_POWER_INTERCEPT 0 - #define SPEED_POWER_MIN 5000 - #define SPEED_POWER_MAX 30000 // SuperPID router controller 0 - 30,000 RPM + #define SPEED_POWER_SLOPE 118.4 // SPEED_POWER_SLOPE = SPEED_POWER_MAX / 255 + #define SPEED_POWER_INTERCEPT 0 + #define SPEED_POWER_MIN 5000 + #define SPEED_POWER_MAX 30000 // SuperPID router controller 0 - 30,000 RPM + #define SPEED_POWER_STARTUP 25000 // The default value for speed power when M3 is called without arguments + #else - #define SPEED_POWER_SLOPE 0.3922 - #define SPEED_POWER_INTERCEPT 0 - #define SPEED_POWER_MIN 10 - #define SPEED_POWER_MAX 100 // 0-100% + + #define SPEED_POWER_SLOPE 0.3922 // SPEED_POWER_SLOPE = SPEED_POWER_MAX / 255 + #define SPEED_POWER_INTERCEPT 0 + #define SPEED_POWER_MIN 0 + #define SPEED_POWER_MAX 100 // 0-100% + #define SPEED_POWER_STARTUP 80 // The default value for speed power when M3 is called without arguments + + /** + * Enable inline laser power to be handled in the planner / stepper routines. + * Inline power is specified by the I (inline) flag in an M3 command (e.g., M3 S20 I) + * or by the 'S' parameter in G0/G1/G2/G3 moves (see LASER_MOVE_POWER). + * + * This allows the laser to keep in perfect sync with the planner and removes + * the powerup/down delay since lasers require negligible time. + */ + #define LASER_POWER_INLINE + + #if ENABLED(LASER_POWER_INLINE) + /** + * Scale the laser's power in proportion to the movement rate. + * + * - Sets the entry power proportional to the entry speed over the nominal speed. + * - Ramps the power up every N steps to approximate the speed trapezoid. + * - Due to the limited power resolution this is only approximate. + */ + #define LASER_POWER_INLINE_TRAPEZOID + + /** + * Continuously calculate the current power (nominal_power * current_rate / nominal_rate). + * Required for accurate power with non-trapezoidal acceleration (e.g., S_CURVE_ACCELERATION). + * This is a costly calculation so this option is discouraged on 8-bit AVR boards. + * + * LASER_POWER_INLINE_TRAPEZOID_CONT_PER defines how many step cycles there are between power updates. If your + * board isn't able to generate steps fast enough (and you are using LASER_POWER_INLINE_TRAPEZOID_CONT), increase this. + * Note that when this is zero it means it occurs every cycle; 1 means a delay wait one cycle then run, etc. + */ + //#define LASER_POWER_INLINE_TRAPEZOID_CONT + + /** + * Stepper iterations between power updates. Increase this value if the board + * can't keep up with the processing demands of LASER_POWER_INLINE_TRAPEZOID_CONT. + * Disable (or set to 0) to recalculate power on every stepper iteration. + */ + //#define LASER_POWER_INLINE_TRAPEZOID_CONT_PER 10 + + /** + * Include laser power in G0/G1/G2/G3/G5 commands with the 'S' parameter + */ + //#define LASER_MOVE_POWER + + #if ENABLED(LASER_MOVE_POWER) + // Turn off the laser on G0 moves with no power parameter. + // If a power parameter is provided, use that instead. + //#define LASER_MOVE_G0_OFF + #endif + + /** + * Inline flag inverted + * + * WARNING: M5 will NOT turn off the laser unless another move + * is done (so G-code files must end with 'M5 I'). + */ + //#define LASER_POWER_INLINE_INVERT + + /** + * Continuously apply inline power. ('M3 S3' == 'G1 S3' == 'M3 S3 I') + * + * The laser might do some weird things, so only enable this + * feature if you understand the implications. + */ + //#define LASER_POWER_INLINE_CONTINUOUS + + #else + + #define SPINDLE_LASER_POWERUP_DELAY 50 // (ms) Delay to allow the spindle/laser to come up to speed/power + #define SPINDLE_LASER_POWERDOWN_DELAY 50 // (ms) Delay to allow the spindle to stop + + #endif #endif #endif @@ -3158,4 +3226,4 @@ //#define PINS_DEBUGGING // Enable Marlin dev mode which adds some special commands -//#define MARLIN_DEV_MODE +//#define MARLIN_DEV_MODE \ No newline at end of file diff --git a/Marlin/Version.h b/Marlin/Version.h index 91cc6144..b4e51841 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -28,7 +28,7 @@ /** * Marlin release version identifier */ -//#define SHORT_BUILD_VERSION "2.0.5.2" +//#define SHORT_BUILD_VERSION "2.0.5.3" /** * Verbose version identifier which should contain a reference to the location diff --git a/Marlin/src/HAL/AVR/persistent_store_eeprom.cpp b/Marlin/src/HAL/AVR/eeprom.cpp similarity index 97% rename from Marlin/src/HAL/AVR/persistent_store_eeprom.cpp rename to Marlin/src/HAL/AVR/eeprom.cpp index 1ae37f89..ee416b7a 100644 --- a/Marlin/src/HAL/AVR/persistent_store_eeprom.cpp +++ b/Marlin/src/HAL/AVR/eeprom.cpp @@ -25,7 +25,7 @@ #if EITHER(EEPROM_SETTINGS, SD_FIRMWARE_UPDATE) -#include "../shared/persistent_store_api.h" +#include "../shared/eeprom_api.h" bool PersistentStore::access_start() { return true; } bool PersistentStore::access_finish() { return true; } diff --git a/Marlin/src/HAL/AVR/fastio.h b/Marlin/src/HAL/AVR/fastio.h index 2246a0f9..a45e0f2b 100644 --- a/Marlin/src/HAL/AVR/fastio.h +++ b/Marlin/src/HAL/AVR/fastio.h @@ -98,9 +98,9 @@ #define SET_INPUT(IO) _SET_INPUT(IO) #define SET_INPUT_PULLUP(IO) do{ _SET_INPUT(IO); _WRITE(IO, HIGH); }while(0) +#define SET_INPUT_PULLDOWN SET_INPUT #define SET_OUTPUT(IO) _SET_OUTPUT(IO) - -#define SET_PWM(IO) SET_OUTPUT(IO) +#define SET_PWM SET_OUTPUT #define IS_INPUT(IO) _IS_INPUT(IO) #define IS_OUTPUT(IO) _IS_OUTPUT(IO) diff --git a/Marlin/src/HAL/DUE/EepromEmulation.cpp b/Marlin/src/HAL/DUE/EepromEmulation.cpp index f1ae224b..66af50cf 100644 --- a/Marlin/src/HAL/DUE/EepromEmulation.cpp +++ b/Marlin/src/HAL/DUE/EepromEmulation.cpp @@ -57,7 +57,7 @@ #if ENABLED(FLASH_EEPROM_EMULATION) #include "../shared/Marduino.h" -#include "../shared/persistent_store_api.h" +#include "../shared/eeprom_api.h" #define EEPROMSize 4096 #define PagesPerGroup 128 diff --git a/Marlin/src/HAL/DUE/persistent_store_eeprom.cpp b/Marlin/src/HAL/DUE/eeprom.cpp similarity index 98% rename from Marlin/src/HAL/DUE/persistent_store_eeprom.cpp rename to Marlin/src/HAL/DUE/eeprom.cpp index fbdc760e..ec9ef51f 100644 --- a/Marlin/src/HAL/DUE/persistent_store_eeprom.cpp +++ b/Marlin/src/HAL/DUE/eeprom.cpp @@ -27,7 +27,7 @@ #if ENABLED(EEPROM_SETTINGS) #include "../../inc/MarlinConfig.h" -#include "../shared/persistent_store_api.h" +#include "../shared/eeprom_api.h" #if !defined(E2END) && ENABLED(FLASH_EEPROM_EMULATION) #define E2END 0xFFF // Default to Flash emulated EEPROM size (EepromEmulation_Due.cpp) diff --git a/Marlin/src/HAL/DUE/fastio.h b/Marlin/src/HAL/DUE/fastio.h index 6f1f8d8b..01abd820 100644 --- a/Marlin/src/HAL/DUE/fastio.h +++ b/Marlin/src/HAL/DUE/fastio.h @@ -166,7 +166,7 @@ // Set pin as output (wrapper) - reads the pin and sets the output to that value #define SET_OUTPUT(IO) _SET_OUTPUT(IO) // Set pin as PWM -#define SET_PWM(IO) SET_OUTPUT(IO) +#define SET_PWM SET_OUTPUT // Check if pin is an input #define IS_INPUT(IO) ((digitalPinToPort(IO)->PIO_OSR & digitalPinToBitMask(IO)) == 0) diff --git a/Marlin/src/HAL/DUE/fastio/G2_PWM.cpp b/Marlin/src/HAL/DUE/fastio/G2_PWM.cpp index fd2c6ccf..672932f5 100644 --- a/Marlin/src/HAL/DUE/fastio/G2_PWM.cpp +++ b/Marlin/src/HAL/DUE/fastio/G2_PWM.cpp @@ -46,6 +46,31 @@ #include "G2_PWM.h" +#if PIN_EXISTS(MOTOR_CURRENT_PWM_X) + #define G2_PWM_X 1 +#else + #define G2_PWM_X 0 +#endif +#if PIN_EXISTS(MOTOR_CURRENT_PWM_Y) + #define G2_PWM_Y 1 +#else + #define G2_PWM_Y 0 +#endif +#if PIN_EXISTS(MOTOR_CURRENT_PWM_Z) + #define G2_PWM_Z 1 +#else + #define G2_PWM_Z 0 +#endif +#if PIN_EXISTS(MOTOR_CURRENT_PWM_E) + #define G2_PWM_E 1 +#else + #define G2_PWM_E 0 +#endif +#define G2_MASK_X(V) (G2_PWM_X * (V)) +#define G2_MASK_Y(V) (G2_PWM_Y * (V)) +#define G2_MASK_Z(V) (G2_PWM_Z * (V)) +#define G2_MASK_E(V) (G2_PWM_E * (V)) + volatile uint32_t *SODR_A = &PIOA->PIO_SODR, *SODR_B = &PIOB->PIO_SODR, *CODR_A = &PIOA->PIO_CODR, @@ -55,10 +80,18 @@ PWM_map ISR_table[NUM_PWMS] = PWM_MAP_INIT; void Stepper::digipot_init() { - OUT_WRITE(MOTOR_CURRENT_PWM_X_PIN, 0); // init pins - OUT_WRITE(MOTOR_CURRENT_PWM_Y_PIN, 0); - OUT_WRITE(MOTOR_CURRENT_PWM_Z_PIN, 0); - OUT_WRITE(MOTOR_CURRENT_PWM_E_PIN, 0); + #if PIN_EXISTS(MOTOR_CURRENT_PWM_X) + OUT_WRITE(MOTOR_CURRENT_PWM_X_PIN, 0); // init pins + #endif + #if PIN_EXISTS(MOTOR_CURRENT_PWM_Y) + OUT_WRITE(MOTOR_CURRENT_PWM_Y_PIN, 0); + #endif + #if G2_PWM_Z + OUT_WRITE(MOTOR_CURRENT_PWM_Z_PIN, 0); + #endif + #if G2_PWM_E + OUT_WRITE(MOTOR_CURRENT_PWM_E_PIN, 0); + #endif #define WPKEY (0x50574D << 8) // “PWM” in ASCII #define WPCMD_DIS_SW 0 // command to disable Write Protect SW @@ -71,30 +104,51 @@ void Stepper::digipot_init() { PWM->PWM_WPCR = WPKEY | WPRG_ALL | WPCMD_DIS_SW; // enable setting of all PWM registers PWM->PWM_CLK = PWM_CLOCK_F; // enable CLK_A and set it to 1MHz, leave CLK_B disabled PWM->PWM_CH_NUM[0].PWM_CMR = 0b1011; // set channel 0 to Clock A input & to left aligned - PWM->PWM_CH_NUM[1].PWM_CMR = 0b1011; // set channel 1 to Clock A input & to left aligned - PWM->PWM_CH_NUM[2].PWM_CMR = 0b1011; // set channel 2 to Clock A input & to left aligned - PWM->PWM_CH_NUM[3].PWM_CMR = 0b1011; // set channel 3 to Clock A input & to left aligned - PWM->PWM_CH_NUM[4].PWM_CMR = 0b1011; // set channel 4 to Clock A input & to left aligned + if (G2_PWM_X) PWM->PWM_CH_NUM[1].PWM_CMR = 0b1011; // set channel 1 to Clock A input & to left aligned + if (G2_PWM_Y) PWM->PWM_CH_NUM[2].PWM_CMR = 0b1011; // set channel 2 to Clock A input & to left aligned + if (G2_PWM_Z) PWM->PWM_CH_NUM[3].PWM_CMR = 0b1011; // set channel 3 to Clock A input & to left aligned + if (G2_PWM_E) PWM->PWM_CH_NUM[4].PWM_CMR = 0b1011; // set channel 4 to Clock A input & to left aligned PWM->PWM_CH_NUM[0].PWM_CPRD = PWM_PERIOD_US; // set channel 0 Period PWM->PWM_IER2 = PWM_IER1_CHID0; // generate interrupt when counter0 overflows - PWM->PWM_IER2 = PWM_IER2_CMPM0 | PWM_IER2_CMPM1 | PWM_IER2_CMPM2 | PWM_IER2_CMPM3 | PWM_IER2_CMPM4; // generate interrupt on compare event - - PWM->PWM_CMP[1].PWM_CMPV = 0x010000000LL | G2_VREF_COUNT(G2_VREF(motor_current_setting[0])); // interrupt when counter0 == CMPV - used to set Motor 1 PWM inactive - PWM->PWM_CMP[2].PWM_CMPV = 0x010000000LL | G2_VREF_COUNT(G2_VREF(motor_current_setting[0])); // interrupt when counter0 == CMPV - used to set Motor 2 PWM inactive - PWM->PWM_CMP[3].PWM_CMPV = 0x010000000LL | G2_VREF_COUNT(G2_VREF(motor_current_setting[1])); // interrupt when counter0 == CMPV - used to set Motor 3 PWM inactive - PWM->PWM_CMP[4].PWM_CMPV = 0x010000000LL | G2_VREF_COUNT(G2_VREF(motor_current_setting[2])); // interrupt when counter0 == CMPV - used to set Motor 4 PWM inactive - - PWM->PWM_CMP[1].PWM_CMPM = 0x0001; // enable compare event - PWM->PWM_CMP[2].PWM_CMPM = 0x0001; // enable compare event - PWM->PWM_CMP[3].PWM_CMPM = 0x0001; // enable compare event - PWM->PWM_CMP[4].PWM_CMPM = 0x0001; // enable compare event - - PWM->PWM_SCM = PWM_SCM_UPDM_MODE0 | PWM_SCM_SYNC0 | PWM_SCM_SYNC1 | PWM_SCM_SYNC2 | PWM_SCM_SYNC3 | PWM_SCM_SYNC4; // sync 1-4 with 0, use mode 0 for updates - - PWM->PWM_ENA = PWM_ENA_CHID0 | PWM_ENA_CHID1 | PWM_ENA_CHID2 | PWM_ENA_CHID3 | PWM_ENA_CHID4; // enable the channels used by G2 - PWM->PWM_IER1 = PWM_IER1_CHID0 | PWM_IER1_CHID1 | PWM_IER1_CHID2 | PWM_IER1_CHID3 | PWM_IER1_CHID4; // enable interrupts for the channels used by G2 + PWM->PWM_IER2 = PWM_IER2_CMPM0 + | G2_MASK_X(PWM_IER2_CMPM1) + | G2_MASK_Y(PWM_IER2_CMPM2) + | G2_MASK_Z(PWM_IER2_CMPM3) + | G2_MASK_E(PWM_IER2_CMPM4) + ; // generate interrupt on compare event + + if (G2_PWM_X) PWM->PWM_CMP[1].PWM_CMPV = 0x010000000LL | G2_VREF_COUNT(G2_VREF(motor_current_setting[0])); // interrupt when counter0 == CMPV - used to set Motor 1 PWM inactive + if (G2_PWM_Y) PWM->PWM_CMP[2].PWM_CMPV = 0x010000000LL | G2_VREF_COUNT(G2_VREF(motor_current_setting[0])); // interrupt when counter0 == CMPV - used to set Motor 2 PWM inactive + if (G2_PWM_Z) PWM->PWM_CMP[3].PWM_CMPV = 0x010000000LL | G2_VREF_COUNT(G2_VREF(motor_current_setting[1])); // interrupt when counter0 == CMPV - used to set Motor 3 PWM inactive + if (G2_PWM_E) PWM->PWM_CMP[4].PWM_CMPV = 0x010000000LL | G2_VREF_COUNT(G2_VREF(motor_current_setting[2])); // interrupt when counter0 == CMPV - used to set Motor 4 PWM inactive + + if (G2_PWM_X) PWM->PWM_CMP[1].PWM_CMPM = 0x0001; // enable compare event + if (G2_PWM_Y) PWM->PWM_CMP[2].PWM_CMPM = 0x0001; // enable compare event + if (G2_PWM_Z) PWM->PWM_CMP[3].PWM_CMPM = 0x0001; // enable compare event + if (G2_PWM_E) PWM->PWM_CMP[4].PWM_CMPM = 0x0001; // enable compare event + + PWM->PWM_SCM = PWM_SCM_UPDM_MODE0 | PWM_SCM_SYNC0 + | G2_MASK_X(PWM_SCM_SYNC1) + | G2_MASK_Y(PWM_SCM_SYNC2) + | G2_MASK_Z(PWM_SCM_SYNC3) + | G2_MASK_E(PWM_SCM_SYNC4) + ; // sync 1-4 with 0, use mode 0 for updates + + PWM->PWM_ENA = PWM_ENA_CHID0 + | G2_MASK_X(PWM_ENA_CHID1) + | G2_MASK_Y(PWM_ENA_CHID2) + | G2_MASK_Z(PWM_ENA_CHID3) + | G2_MASK_E(PWM_ENA_CHID4) + ; // enable channels used by G2 + + PWM->PWM_IER1 = PWM_IER1_CHID0 + | G2_MASK_X(PWM_IER1_CHID1) + | G2_MASK_Y(PWM_IER1_CHID2) + | G2_MASK_Z(PWM_IER1_CHID3) + | G2_MASK_E(PWM_IER1_CHID4) + ; // enable interrupts for channels used by G2 NVIC_EnableIRQ(PWM_IRQn); // Enable interrupt handler NVIC_SetPriority(PWM_IRQn, NVIC_EncodePriority(0, 10, 0)); // normal priority for PWM module (can stand some jitter on the Vref signals) @@ -105,20 +159,27 @@ void Stepper::digipot_current(const uint8_t driver, const int16_t current) { if (!(PWM->PWM_CH_NUM[0].PWM_CPRD == PWM_PERIOD_US)) digipot_init(); // Init PWM system if needed switch (driver) { - case 0: PWM->PWM_CMP[1].PWM_CMPVUPD = 0x010000000LL | G2_VREF_COUNT(G2_VREF(current)); // update X & Y - PWM->PWM_CMP[2].PWM_CMPVUPD = 0x010000000LL | G2_VREF_COUNT(G2_VREF(current)); - PWM->PWM_CMP[1].PWM_CMPMUPD = 0x0001; // enable compare event - PWM->PWM_CMP[2].PWM_CMPMUPD = 0x0001; // enable compare event - PWM->PWM_SCUC = PWM_SCUC_UPDULOCK; // tell the PWM controller to update the values on the next cycle - break; - case 1: PWM->PWM_CMP[3].PWM_CMPVUPD = 0x010000000LL | G2_VREF_COUNT(G2_VREF(current)); // update Z - PWM->PWM_CMP[3].PWM_CMPMUPD = 0x0001; // enable compare event - PWM->PWM_SCUC = PWM_SCUC_UPDULOCK; // tell the PWM controller to update the values on the next cycle - break; - default:PWM->PWM_CMP[4].PWM_CMPVUPD = 0x010000000LL | G2_VREF_COUNT(G2_VREF(current)); // update E - PWM->PWM_CMP[4].PWM_CMPMUPD = 0x0001; // enable compare event - PWM->PWM_SCUC = PWM_SCUC_UPDULOCK; // tell the PWM controller to update the values on the next cycle - break; + case 0: + if (G2_PWM_X) PWM->PWM_CMP[1].PWM_CMPVUPD = 0x010000000LL | G2_VREF_COUNT(G2_VREF(current)); // update X & Y + if (G2_PWM_Y) PWM->PWM_CMP[2].PWM_CMPVUPD = 0x010000000LL | G2_VREF_COUNT(G2_VREF(current)); + if (G2_PWM_X) PWM->PWM_CMP[1].PWM_CMPMUPD = 0x0001; // enable compare event + if (G2_PWM_Y) PWM->PWM_CMP[2].PWM_CMPMUPD = 0x0001; // enable compare event + if (G2_PWM_X || G2_PWM_Y) PWM->PWM_SCUC = PWM_SCUC_UPDULOCK; // tell the PWM controller to update the values on the next cycle + break; + case 1: + if (G2_PWM_Z) { + PWM->PWM_CMP[3].PWM_CMPVUPD = 0x010000000LL | G2_VREF_COUNT(G2_VREF(current)); // update Z + PWM->PWM_CMP[3].PWM_CMPMUPD = 0x0001; // enable compare event + PWM->PWM_SCUC = PWM_SCUC_UPDULOCK; // tell the PWM controller to update the values on the next cycle + } + break; + default: + if (G2_PWM_E) { + PWM->PWM_CMP[4].PWM_CMPVUPD = 0x010000000LL | G2_VREF_COUNT(G2_VREF(current)); // update E + PWM->PWM_CMP[4].PWM_CMPMUPD = 0x0001; // enable compare event + PWM->PWM_SCUC = PWM_SCUC_UPDULOCK; // tell the PWM controller to update the values on the next cycle + } + break; } } @@ -127,17 +188,17 @@ volatile uint32_t PWM_ISR1_STATUS, PWM_ISR2_STATUS; void PWM_Handler() { PWM_ISR1_STATUS = PWM->PWM_ISR1; PWM_ISR2_STATUS = PWM->PWM_ISR2; - if (PWM_ISR1_STATUS & PWM_IER1_CHID0) { // CHAN_0 interrupt - *ISR_table[0].set_register = ISR_table[0].write_mask; // set X to active - *ISR_table[1].set_register = ISR_table[1].write_mask; // set Y to active - *ISR_table[2].set_register = ISR_table[2].write_mask; // set Z to active - *ISR_table[3].set_register = ISR_table[3].write_mask; // set E to active + if (PWM_ISR1_STATUS & PWM_IER1_CHID0) { // CHAN_0 interrupt + if (G2_PWM_X) *ISR_table[0].set_register = ISR_table[0].write_mask; // set X to active + if (G2_PWM_Y) *ISR_table[1].set_register = ISR_table[1].write_mask; // set Y to active + if (G2_PWM_Z) *ISR_table[2].set_register = ISR_table[2].write_mask; // set Z to active + if (G2_PWM_E) *ISR_table[3].set_register = ISR_table[3].write_mask; // set E to active } else { - if (PWM_ISR2_STATUS & PWM_IER2_CMPM1) *ISR_table[0].clr_register = ISR_table[0].write_mask; // set X to inactive - if (PWM_ISR2_STATUS & PWM_IER2_CMPM2) *ISR_table[1].clr_register = ISR_table[1].write_mask; // set Y to inactive - if (PWM_ISR2_STATUS & PWM_IER2_CMPM3) *ISR_table[2].clr_register = ISR_table[2].write_mask; // set Z to inactive - if (PWM_ISR2_STATUS & PWM_IER2_CMPM4) *ISR_table[3].clr_register = ISR_table[3].write_mask; // set E to inactive + if (G2_PWM_X && (PWM_ISR2_STATUS & PWM_IER2_CMPM1)) *ISR_table[0].clr_register = ISR_table[0].write_mask; // set X to inactive + if (G2_PWM_Y && (PWM_ISR2_STATUS & PWM_IER2_CMPM2)) *ISR_table[1].clr_register = ISR_table[1].write_mask; // set Y to inactive + if (G2_PWM_Z && (PWM_ISR2_STATUS & PWM_IER2_CMPM3)) *ISR_table[2].clr_register = ISR_table[2].write_mask; // set Z to inactive + if (G2_PWM_E && (PWM_ISR2_STATUS & PWM_IER2_CMPM4)) *ISR_table[3].clr_register = ISR_table[3].write_mask; // set E to inactive } return; } diff --git a/Marlin/src/HAL/DUE/inc/Conditionals_post.h b/Marlin/src/HAL/DUE/inc/Conditionals_post.h index b52462f6..8a305009 100644 --- a/Marlin/src/HAL/DUE/inc/Conditionals_post.h +++ b/Marlin/src/HAL/DUE/inc/Conditionals_post.h @@ -21,7 +21,7 @@ */ #pragma once -#if USE_EMULATED_EEPROM +#if USE_FALLBACK_EEPROM #undef SRAM_EEPROM_EMULATION #undef SDCARD_EEPROM_EMULATION #define FLASH_EEPROM_EMULATION diff --git a/Marlin/src/HAL/ESP32/persistent_store_impl.cpp b/Marlin/src/HAL/ESP32/eeprom_impl.cpp similarity index 97% rename from Marlin/src/HAL/ESP32/persistent_store_impl.cpp rename to Marlin/src/HAL/ESP32/eeprom_impl.cpp index 7113b684..dbfee140 100644 --- a/Marlin/src/HAL/ESP32/persistent_store_impl.cpp +++ b/Marlin/src/HAL/ESP32/eeprom_impl.cpp @@ -26,7 +26,7 @@ #if ENABLED(EEPROM_SETTINGS) && DISABLED(FLASH_EEPROM_EMULATION) -#include "../shared/persistent_store_api.h" +#include "../shared/eeprom_api.h" #include "EEPROM.h" #define EEPROM_SIZE 4096 diff --git a/Marlin/src/HAL/ESP32/fastio.h b/Marlin/src/HAL/ESP32/fastio.h index 9c4efaee..09930194 100644 --- a/Marlin/src/HAL/ESP32/fastio.h +++ b/Marlin/src/HAL/ESP32/fastio.h @@ -56,7 +56,7 @@ #define SET_OUTPUT(IO) do{ _SET_OUTPUT(IO); }while(0) // Set pin as PWM -#define SET_PWM(IO) SET_OUTPUT(IO) +#define SET_PWM SET_OUTPUT // Set pin as output and init #define OUT_WRITE(IO,V) do{ _SET_OUTPUT(IO); WRITE(IO,V); }while(0) diff --git a/Marlin/src/HAL/ESP32/inc/Conditionals_post.h b/Marlin/src/HAL/ESP32/inc/Conditionals_post.h index e51b5569..11603c9e 100644 --- a/Marlin/src/HAL/ESP32/inc/Conditionals_post.h +++ b/Marlin/src/HAL/ESP32/inc/Conditionals_post.h @@ -22,6 +22,6 @@ #pragma once // If no real EEPROM, Flash emulation, or SRAM emulation is available fall back to SD emulation -#if ENABLED(EEPROM_SETTINGS) && NONE(USE_REAL_EEPROM, FLASH_EEPROM_EMULATION, SRAM_EEPROM_EMULATION) +#if ENABLED(EEPROM_SETTINGS) && NONE(USE_WIRED_EEPROM, FLASH_EEPROM_EMULATION, SRAM_EEPROM_EMULATION) #define SDCARD_EEPROM_EMULATION #endif diff --git a/Marlin/src/HAL/LINUX/persistent_store_impl.cpp b/Marlin/src/HAL/LINUX/eeprom_impl.cpp similarity index 98% rename from Marlin/src/HAL/LINUX/persistent_store_impl.cpp rename to Marlin/src/HAL/LINUX/eeprom_impl.cpp index 660ecd56..4745f056 100644 --- a/Marlin/src/HAL/LINUX/persistent_store_impl.cpp +++ b/Marlin/src/HAL/LINUX/eeprom_impl.cpp @@ -26,7 +26,7 @@ #if ENABLED(EEPROM_SETTINGS) -#include "../shared/persistent_store_api.h" +#include "../shared/eeprom_api.h" #include #define LINUX_EEPROM_SIZE (E2END + 1) diff --git a/Marlin/src/HAL/LPC1768/persistent_store_api.h b/Marlin/src/HAL/LPC1768/eeprom_api.h similarity index 95% rename from Marlin/src/HAL/LPC1768/persistent_store_api.h rename to Marlin/src/HAL/LPC1768/eeprom_api.h index 55a58fde..f874eac5 100644 --- a/Marlin/src/HAL/LPC1768/persistent_store_api.h +++ b/Marlin/src/HAL/LPC1768/eeprom_api.h @@ -21,6 +21,6 @@ */ #pragma once -#include "../shared/persistent_store_api.h" +#include "../shared/eeprom_api.h" #define FLASH_EEPROM_EMULATION diff --git a/Marlin/src/HAL/LPC1768/persistent_store_flash.cpp b/Marlin/src/HAL/LPC1768/eeprom_flash.cpp similarity index 99% rename from Marlin/src/HAL/LPC1768/persistent_store_flash.cpp rename to Marlin/src/HAL/LPC1768/eeprom_flash.cpp index e166858d..92258074 100644 --- a/Marlin/src/HAL/LPC1768/persistent_store_flash.cpp +++ b/Marlin/src/HAL/LPC1768/eeprom_flash.cpp @@ -40,7 +40,7 @@ #if ENABLED(FLASH_EEPROM_EMULATION) -#include "persistent_store_api.h" +#include "eeprom_api.h" extern "C" { #include diff --git a/Marlin/src/HAL/LPC1768/persistent_store_sdcard.cpp b/Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp similarity index 99% rename from Marlin/src/HAL/LPC1768/persistent_store_sdcard.cpp rename to Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp index aa61938b..d982bd62 100644 --- a/Marlin/src/HAL/LPC1768/persistent_store_sdcard.cpp +++ b/Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp @@ -26,7 +26,7 @@ #if ENABLED(SDCARD_EEPROM_EMULATION) -#include "persistent_store_api.h" +#include "eeprom_api.h" #include #include diff --git a/Marlin/src/HAL/LPC1768/fastio.h b/Marlin/src/HAL/LPC1768/fastio.h index 48de5b8f..8e8e66db 100644 --- a/Marlin/src/HAL/LPC1768/fastio.h +++ b/Marlin/src/HAL/LPC1768/fastio.h @@ -104,7 +104,7 @@ /// set pin as output wrapper - reads the pin and sets the output to that value #define SET_OUTPUT(IO) do{ _WRITE(IO, _READ(IO)); _SET_OUTPUT(IO); }while(0) // set pin as PWM -#define SET_PWM(IO) SET_OUTPUT(IO) +#define SET_PWM SET_OUTPUT /// check if pin is an input wrapper #define IS_INPUT(IO) _IS_INPUT(IO) diff --git a/Marlin/src/HAL/LPC1768/inc/Conditionals_post.h b/Marlin/src/HAL/LPC1768/inc/Conditionals_post.h index a8d102e8..490cfd50 100644 --- a/Marlin/src/HAL/LPC1768/inc/Conditionals_post.h +++ b/Marlin/src/HAL/LPC1768/inc/Conditionals_post.h @@ -21,6 +21,6 @@ */ #pragma once -#if USE_EMULATED_EEPROM && NONE(SDCARD_EEPROM_EMULATION, SRAM_EEPROM_EMULATION) +#if USE_FALLBACK_EEPROM && NONE(SDCARD_EEPROM_EMULATION, SRAM_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION #endif diff --git a/Marlin/src/HAL/LPC1768/main.cpp b/Marlin/src/HAL/LPC1768/main.cpp index fb739434..d7b05dce 100644 --- a/Marlin/src/HAL/LPC1768/main.cpp +++ b/Marlin/src/HAL/LPC1768/main.cpp @@ -90,7 +90,7 @@ void HAL_init() { //debug_frmwrk_init(); //_DBG("\n\nDebug running\n"); - // Initialise the SD card chip select pins as soon as possible + // Initialize the SD card chip select pins as soon as possible #if PIN_EXISTS(SS) OUT_WRITE(SS_PIN, HIGH); #endif diff --git a/Marlin/src/HAL/SAMD51/QSPIFlash.cpp b/Marlin/src/HAL/SAMD51/QSPIFlash.cpp new file mode 100644 index 00000000..76a33297 --- /dev/null +++ b/Marlin/src/HAL/SAMD51/QSPIFlash.cpp @@ -0,0 +1,78 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "../../inc/MarlinConfig.h" + +#if ENABLED(QSPI_EEPROM) + +#include "QSPIFlash.h" + +#define INVALID_ADDR 0xffffffff +#define SECTOR_OF(a) (a & ~(SFLASH_SECTOR_SIZE - 1)) +#define OFFSET_OF(a) (a & (SFLASH_SECTOR_SIZE - 1)) + +Adafruit_SPIFlashBase * QSPIFlash::_flashBase = nullptr; +uint8_t QSPIFlash::_buf[SFLASH_SECTOR_SIZE]; +uint32_t QSPIFlash::_addr = INVALID_ADDR; + +void QSPIFlash::begin() { + if (_flashBase != nullptr) return; + + _flashBase = new Adafruit_SPIFlashBase(new Adafruit_FlashTransport_QSPI()); + _flashBase->begin(NULL); +} + +size_t QSPIFlash::size() { + return _flashBase->size(); +} + +uint8_t QSPIFlash::readByte(const uint32_t address) { + if (SECTOR_OF(address) == _addr) return _buf[OFFSET_OF(address)]; + + return _flashBase->read8(address); +} + +void QSPIFlash::writeByte(const uint32_t address, const uint8_t value) { + uint32_t const sector_addr = SECTOR_OF(address); + + // Page changes, flush old and update new cache + if (sector_addr != _addr) { + flush(); + _addr = sector_addr; + + // read a whole page from flash + _flashBase->readBuffer(sector_addr, _buf, SFLASH_SECTOR_SIZE); + } + + _buf[OFFSET_OF(address)] = value; +} + +void QSPIFlash::flush() { + if (_addr == INVALID_ADDR) return; + + _flashBase->eraseSector(_addr / SFLASH_SECTOR_SIZE); + _flashBase->writeBuffer(_addr, _buf, SFLASH_SECTOR_SIZE); + + _addr = INVALID_ADDR; +} + +#endif // QSPI_EEPROM diff --git a/Marlin/src/HAL/SAMD51/QSPIFlash.h b/Marlin/src/HAL/SAMD51/QSPIFlash.h new file mode 100644 index 00000000..7f75286e --- /dev/null +++ b/Marlin/src/HAL/SAMD51/QSPIFlash.h @@ -0,0 +1,51 @@ +/** + * @file QSPIFlash.h + * + * The MIT License (MIT) + * + * Copyright (c) 2019 Ha Thach and Dean Miller for Adafruit Industries LLC + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + * + * Derived from Adafruit_SPIFlash class with no SdFat references + * + */ + +#pragma once + +#include "Adafruit_SPIFlashBase.h" + +// This class extends Adafruit_SPIFlashBase by adding caching support. +// +// This class will use 4096 Bytes of RAM as a block cache. +class QSPIFlash { + public: + static void begin(); + static size_t size(); + static uint8_t readByte(const uint32_t address); + static void writeByte(const uint32_t address, const uint8_t v); + static void flush(); + + private: + static Adafruit_SPIFlashBase * _flashBase; + static uint8_t _buf[SFLASH_SECTOR_SIZE]; + static uint32_t _addr; +}; + +extern QSPIFlash qspi; diff --git a/Marlin/src/HAL/SAMD51/eeprom.cpp b/Marlin/src/HAL/SAMD51/eeprom.cpp new file mode 100644 index 00000000..e167515b --- /dev/null +++ b/Marlin/src/HAL/SAMD51/eeprom.cpp @@ -0,0 +1,66 @@ +/** + * Marlin 3D Printer Firmware + * + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * SAMD51 HAL developed by Giuliano Zaro (AKA GMagician) + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#ifdef __SAMD51__ + +#include "../../inc/MarlinConfig.h" + +#if ENABLED(EEPROM_SETTINGS) && NONE(QSPI_EEPROM, FLASH_EEPROM_EMULATION) + +#include "../shared/eeprom_api.h" + +size_t PersistentStore::capacity() { return E2END + 1; } + +bool PersistentStore::access_start() { return true; } +bool PersistentStore::access_finish() { return true; } + +bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { + while (size--) { + const uint8_t v = *value; + uint8_t * const p = (uint8_t * const)pos; + if (v != eeprom_read_byte(p)) { + eeprom_write_byte(p, v); + delay(2); + if (eeprom_read_byte(p) != v) { + SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE); + return true; + } + } + crc16(crc, &v, 1); + pos++; + value++; + } + return false; +} + +bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) { + while (size--) { + uint8_t c = eeprom_read_byte((uint8_t*)pos); + if (writing) *value = c; + crc16(crc, &c, 1); + pos++; + value++; + } + return false; +} + +#endif // EEPROM_SETTINGS && !(QSPI_EEPROM || FLASH_EEPROM_EMULATION) +#endif // __SAMD51__ diff --git a/Marlin/src/HAL/SAMD51/eeprom_flash.cpp b/Marlin/src/HAL/SAMD51/eeprom_flash.cpp new file mode 100644 index 00000000..fd897336 --- /dev/null +++ b/Marlin/src/HAL/SAMD51/eeprom_flash.cpp @@ -0,0 +1,96 @@ +/** + * Marlin 3D Printer Firmware + * + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * SAMD51 HAL developed by Giuliano Zaro (AKA GMagician) + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#ifdef __SAMD51__ + +#include "../../inc/MarlinConfig.h" + +#if ENABLED(FLASH_EEPROM_EMULATION) + +#include "../shared/eeprom_api.h" + +#define NVMCTRL_CMD(c) do{ \ + SYNC(!NVMCTRL->STATUS.bit.READY); \ + NVMCTRL->INTFLAG.bit.DONE = true; \ + NVMCTRL->CTRLB.reg = c | NVMCTRL_CTRLB_CMDEX_KEY; \ + SYNC(NVMCTRL->INTFLAG.bit.DONE); \ + }while(0) +#define NVMCTRL_FLUSH() do{ \ + if (NVMCTRL->SEESTAT.bit.LOAD) \ + NVMCTRL_CMD(NVMCTRL_CTRLB_CMD_SEEFLUSH); \ + }while(0) + +size_t PersistentStore::capacity() { + const uint8_t psz = NVMCTRL->SEESTAT.bit.PSZ, + sblk = NVMCTRL->SEESTAT.bit.SBLK; + + return (!psz && !sblk) ? 0 + : (psz <= 2) ? (0x200 << psz) + : (sblk == 1 || psz == 3) ? 4096 + : (sblk == 2 || psz == 4) ? 8192 + : (sblk <= 4 || psz == 5) ? 16384 + : (sblk >= 9 && psz == 7) ? 65536 + : 32768; +} + +bool PersistentStore::access_start() { + NVMCTRL->SEECFG.reg = NVMCTRL_SEECFG_WMODE_BUFFERED; // Buffered mode and segment reallocation active + if (NVMCTRL->SEESTAT.bit.RLOCK) + NVMCTRL_CMD(NVMCTRL_CTRLB_CMD_USEE); // Unlock E2P data write access + return true; +} + +bool PersistentStore::access_finish() { + NVMCTRL_FLUSH(); + if (!NVMCTRL->SEESTAT.bit.LOCK) + NVMCTRL_CMD(NVMCTRL_CTRLB_CMD_LSEE); // Lock E2P data write access + return true; +} + +bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { + while (size--) { + const uint8_t v = *value; + SYNC(NVMCTRL->SEESTAT.bit.BUSY); + if (NVMCTRL->INTFLAG.bit.SEESFULL) + NVMCTRL_FLUSH(); // Next write will trigger a sector reallocation. I need to flush 'pagebuffer' + ((volatile uint8_t *)SEEPROM_ADDR)[pos] = v; + SYNC(!NVMCTRL->INTFLAG.bit.SEEWRC); + crc16(crc, &v, 1); + pos++; + value++; + } + return false; +} + +bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) { + while (size--) { + SYNC(NVMCTRL->SEESTAT.bit.BUSY); + uint8_t c = ((volatile uint8_t *)SEEPROM_ADDR)[pos]; + if (writing) *value = c; + crc16(crc, &c, 1); + pos++; + value++; + } + return false; +} + +#endif // FLASH_EEPROM_EMULATION +#endif // __SAMD51__ diff --git a/Marlin/src/HAL/SAMD51/eeprom_qspi.cpp b/Marlin/src/HAL/SAMD51/eeprom_qspi.cpp new file mode 100644 index 00000000..c6aa383f --- /dev/null +++ b/Marlin/src/HAL/SAMD51/eeprom_qspi.cpp @@ -0,0 +1,71 @@ +/** + * Marlin 3D Printer Firmware + * + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * SAMD51 HAL developed by Giuliano Zaro (AKA GMagician) + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#ifdef __SAMD51__ + +#include "../../inc/MarlinConfig.h" + +#if ENABLED(QSPI_EEPROM) + +#include "../shared/eeprom_api.h" + +#include "QSPIFlash.h" + +static bool initialized; + +size_t PersistentStore::capacity() { return qspi.size(); } + +bool PersistentStore::access_start() { + if (!initialized) { + qspi.begin(); + initialized = true; + } + return true; +} + +bool PersistentStore::access_finish() { + qspi.flush(); + return true; +} + +bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { + while (size--) { + const uint8_t v = *value; + qspi.writeByte(pos, v); + crc16(crc, &v, 1); + pos++; + value++; + } + return false; +} + +bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) { + while (size--) { + uint8_t c = qspi.readByte(pos); + if (writing) *value = c; + crc16(crc, &c, 1); + pos++; + value++; + } + return false; +} + +#endif // QSPI_EEPROM +#endif // __SAMD51__ diff --git a/Marlin/src/HAL/SAMD51/fastio.h b/Marlin/src/HAL/SAMD51/fastio.h index f6a2675d..d3b3dc1f 100644 --- a/Marlin/src/HAL/SAMD51/fastio.h +++ b/Marlin/src/HAL/SAMD51/fastio.h @@ -100,9 +100,9 @@ PORT->Group[port].DIRCLR.reg = MASK(pin); \ }while(0) // Set pin as PWM (push pull) -#define SET_PWM(IO) SET_OUTPUT(IO) +#define SET_PWM SET_OUTPUT // Set pin as PWM (open drain) -#define SET_PWM_OD(IO) SET_OUTPUT_OD(IO) +#define SET_PWM_OD SET_OUTPUT_OD // check if pin is an output #define IS_OUTPUT(IO) ((PORT->Group[(EPortType)GET_SAMD_PORT(IO)].DIR.reg & MASK(GET_SAMD_PIN(IO))) \ diff --git a/Marlin/src/HAL/SAMD51/inc/Conditionals_post.h b/Marlin/src/HAL/SAMD51/inc/Conditionals_post.h index b52462f6..490cfd50 100644 --- a/Marlin/src/HAL/SAMD51/inc/Conditionals_post.h +++ b/Marlin/src/HAL/SAMD51/inc/Conditionals_post.h @@ -21,8 +21,6 @@ */ #pragma once -#if USE_EMULATED_EEPROM - #undef SRAM_EEPROM_EMULATION - #undef SDCARD_EEPROM_EMULATION +#if USE_FALLBACK_EEPROM && NONE(SDCARD_EEPROM_EMULATION, SRAM_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION #endif diff --git a/Marlin/src/HAL/SAMD51/persistent_store_eeprom.cpp b/Marlin/src/HAL/SAMD51/persistent_store_eeprom.cpp deleted file mode 100644 index 6b7326bb..00000000 --- a/Marlin/src/HAL/SAMD51/persistent_store_eeprom.cpp +++ /dev/null @@ -1,129 +0,0 @@ -/** - * Marlin 3D Printer Firmware - * - * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * SAMD51 HAL developed by Giuliano Zaro (AKA GMagician) - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - * - */ - -#ifdef __SAMD51__ - -#include "../../inc/MarlinConfig.h" - -#if ENABLED(EEPROM_SETTINGS) - -#include "../shared/persistent_store_api.h" - -#if ENABLED(FLASH_EEPROM_EMULATION) - #define NVMCTRL_CMD(c) do{ \ - SYNC(!NVMCTRL->STATUS.bit.READY); \ - NVMCTRL->INTFLAG.bit.DONE = true; \ - NVMCTRL->CTRLB.reg = c | NVMCTRL_CTRLB_CMDEX_KEY; \ - SYNC(NVMCTRL->INTFLAG.bit.DONE); \ - }while(0) - #define NVMCTRL_FLUSH() do{ \ - if (NVMCTRL->SEESTAT.bit.LOAD) \ - NVMCTRL_CMD(NVMCTRL_CTRLB_CMD_SEEFLUSH); \ - }while(0) -#endif - -bool PersistentStore::access_start() { - #if ENABLED(FLASH_EEPROM_EMULATION) - NVMCTRL->SEECFG.reg = NVMCTRL_SEECFG_WMODE_BUFFERED; // Buffered mode and segment reallocation active - #endif - - return true; -} - -bool PersistentStore::access_finish() { - #if ENABLED(FLASH_EEPROM_EMULATION) - NVMCTRL_FLUSH(); - if (!NVMCTRL->SEESTAT.bit.LOCK) - NVMCTRL_CMD(NVMCTRL_CTRLB_CMD_LSEE); // Lock E2P data write access - #endif - - return true; -} - -bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { - #if ENABLED(FLASH_EEPROM_EMULATION) - if (NVMCTRL->SEESTAT.bit.RLOCK) - NVMCTRL_CMD(NVMCTRL_CTRLB_CMD_USEE); // Unlock E2P data write access - #endif - - while (size--) { - const uint8_t v = *value; - #if ENABLED(FLASH_EEPROM_EMULATION) - SYNC(NVMCTRL->SEESTAT.bit.BUSY); - if (NVMCTRL->INTFLAG.bit.SEESFULL) - NVMCTRL_FLUSH(); // Next write will trigger a sector reallocation. I need to flush 'pagebuffer' - ((volatile uint8_t *)SEEPROM_ADDR)[pos] = v; - SYNC(!NVMCTRL->INTFLAG.bit.SEEWRC); - #else - uint8_t * const p = (uint8_t * const)pos; - if (v != eeprom_read_byte(p)) { - eeprom_write_byte(p, v); - delay(2); - if (eeprom_read_byte(p) != v) { - SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE); - return true; - } - } - #endif - crc16(crc, &v, 1); - pos++; - value++; - } - return false; -} - -bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) { - while (size--) { - uint8_t c; - #if ENABLED(FLASH_EEPROM_EMULATION) - SYNC(NVMCTRL->SEESTAT.bit.BUSY); - c = ((volatile uint8_t *)SEEPROM_ADDR)[pos]; - #else - c = eeprom_read_byte((uint8_t*)pos); - #endif - if (writing) *value = c; - crc16(crc, &c, 1); - pos++; - value++; - } - return false; -} - -size_t PersistentStore::capacity() { - #if ENABLED(FLASH_EEPROM_EMULATION) - const uint8_t psz = NVMCTRL->SEESTAT.bit.PSZ, - sblk = NVMCTRL->SEESTAT.bit.SBLK; - - if (!psz && !sblk) return 0; - else if (psz <= 2) return (0x200 << psz); - else if (sblk == 1 || psz == 3) return 4096; - else if (sblk == 2 || psz == 4) return 8192; - else if (sblk <= 4 || psz == 5) return 16384; - else if (sblk >= 9 && psz == 7) return 65536; - else return 32768; - #else - return E2END + 1; - #endif -} - -#endif // EEPROM_SETTINGS - -#endif // __SAMD51__ diff --git a/Marlin/src/HAL/STM32/SoftwareSerial.h b/Marlin/src/HAL/STM32/SoftwareSerial.h index 3799701c..504bd697 100644 --- a/Marlin/src/HAL/STM32/SoftwareSerial.h +++ b/Marlin/src/HAL/STM32/SoftwareSerial.h @@ -29,9 +29,7 @@ * The latest version of this library can always be found at * http://arduiniana.org. */ - -#ifndef SOFTWARESERIAL_H -#define SOFTWARESERIAL_H +#pragma once #include @@ -64,7 +62,6 @@ class SoftwareSerial : public Stream { uint32_t delta_start = 0; // static data - static bool initialised; static HardwareTimer timer; static const IRQn_Type timer_interrupt_number; static uint32_t timer_interrupt_priority; @@ -91,7 +88,7 @@ class SoftwareSerial : public Stream { public: // public methods - SoftwareSerial(uint16_t receivePin, uint16_t transmitPin, bool inverse_logic = false); + SoftwareSerial(uint16_t receivePin, uint16_t transmitPin, bool inverse_logic=false); virtual ~SoftwareSerial(); void begin(long speed); bool listen(); @@ -115,5 +112,3 @@ class SoftwareSerial : public Stream { using Print::write; }; - -#endif // SOFTWARESERIAL_H diff --git a/Marlin/src/HAL/STM32/persistent_store_flash.cpp b/Marlin/src/HAL/STM32/eeprom_flash.cpp similarity index 99% rename from Marlin/src/HAL/STM32/persistent_store_flash.cpp rename to Marlin/src/HAL/STM32/eeprom_flash.cpp index 80ef901c..39012f82 100644 --- a/Marlin/src/HAL/STM32/persistent_store_flash.cpp +++ b/Marlin/src/HAL/STM32/eeprom_flash.cpp @@ -27,7 +27,7 @@ #if BOTH(EEPROM_SETTINGS, FLASH_EEPROM_EMULATION) -#include "../shared/persistent_store_api.h" +#include "../shared/eeprom_api.h" // Only STM32F4 can support wear leveling at this time diff --git a/Marlin/src/HAL/STM32/persistent_store_impl.cpp b/Marlin/src/HAL/STM32/eeprom_impl.cpp similarity index 91% rename from Marlin/src/HAL/STM32/persistent_store_impl.cpp rename to Marlin/src/HAL/STM32/eeprom_impl.cpp index d9538741..cd0f93e8 100644 --- a/Marlin/src/HAL/STM32/persistent_store_impl.cpp +++ b/Marlin/src/HAL/STM32/eeprom_impl.cpp @@ -24,9 +24,9 @@ #include "../../inc/MarlinConfig.h" -#if EITHER(USE_REAL_EEPROM, SRAM_EEPROM_EMULATION) +#if EITHER(USE_WIRED_EEPROM, SRAM_EEPROM_EMULATION) -#include "../shared/persistent_store_api.h" +#include "../shared/eeprom_api.h" bool PersistentStore::access_start() { return true; @@ -41,7 +41,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui uint8_t v = *value; // Save to either external EEPROM, program flash or Backup SRAM - #if USE_REAL_EEPROM + #if USE_WIRED_EEPROM // EEPROM has only ~100,000 write cycles, // so only write bytes that have changed! uint8_t * const p = (uint8_t * const)pos; @@ -68,7 +68,7 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t do { // Read from either external EEPROM, program flash or Backup SRAM const uint8_t c = ( - #if USE_REAL_EEPROM + #if USE_WIRED_EEPROM eeprom_read_byte((uint8_t*)pos) #else (*(__IO uint8_t *)(BKPSRAM_BASE + ((uint8_t*)pos))) @@ -85,7 +85,7 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t size_t PersistentStore::capacity() { return ( - #if USE_REAL_EEPROM + #if USE_WIRED_EEPROM E2END + 1 #else 4096 // 4kB @@ -93,5 +93,5 @@ size_t PersistentStore::capacity() { ); } -#endif // USE_REAL_EEPROM || SRAM_EEPROM_EMULATION +#endif // USE_WIRED_EEPROM || SRAM_EEPROM_EMULATION #endif // ARDUINO_ARCH_STM32 && !STM32GENERIC diff --git a/Marlin/src/HAL/STM32/persistent_store_sdcard.cpp b/Marlin/src/HAL/STM32/eeprom_sdcard.cpp similarity index 98% rename from Marlin/src/HAL/STM32/persistent_store_sdcard.cpp rename to Marlin/src/HAL/STM32/eeprom_sdcard.cpp index c5afc557..2b89c21b 100644 --- a/Marlin/src/HAL/STM32/persistent_store_sdcard.cpp +++ b/Marlin/src/HAL/STM32/eeprom_sdcard.cpp @@ -30,7 +30,7 @@ #if ENABLED(SDCARD_EEPROM_EMULATION) -#include "../shared/persistent_store_api.h" +#include "../shared/eeprom_api.h" #ifndef E2END #define E2END 0xFFF // 4KB diff --git a/Marlin/src/HAL/STM32/inc/Conditionals_post.h b/Marlin/src/HAL/STM32/inc/Conditionals_post.h index e51b5569..11603c9e 100644 --- a/Marlin/src/HAL/STM32/inc/Conditionals_post.h +++ b/Marlin/src/HAL/STM32/inc/Conditionals_post.h @@ -22,6 +22,6 @@ #pragma once // If no real EEPROM, Flash emulation, or SRAM emulation is available fall back to SD emulation -#if ENABLED(EEPROM_SETTINGS) && NONE(USE_REAL_EEPROM, FLASH_EEPROM_EMULATION, SRAM_EEPROM_EMULATION) +#if ENABLED(EEPROM_SETTINGS) && NONE(USE_WIRED_EEPROM, FLASH_EEPROM_EMULATION, SRAM_EEPROM_EMULATION) #define SDCARD_EEPROM_EMULATION #endif diff --git a/Marlin/src/HAL/STM32F1/persistent_store_eeprom.cpp b/Marlin/src/HAL/STM32F1/eeprom.cpp similarity index 95% rename from Marlin/src/HAL/STM32F1/persistent_store_eeprom.cpp rename to Marlin/src/HAL/STM32F1/eeprom.cpp index 1b3714c5..ed5d50cb 100644 --- a/Marlin/src/HAL/STM32F1/persistent_store_eeprom.cpp +++ b/Marlin/src/HAL/STM32F1/eeprom.cpp @@ -22,9 +22,9 @@ #include "../../inc/MarlinConfig.h" -#if USE_REAL_EEPROM +#if USE_WIRED_EEPROM -#include "../shared/persistent_store_api.h" +#include "../shared/eeprom_api.h" bool PersistentStore::access_start() { #if ENABLED(SPI_EEPROM) @@ -73,5 +73,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t size_t PersistentStore::capacity() { return E2END + 1; } -#endif // USE_REAL_EEPROM +#endif // USE_WIRED_EEPROM #endif // __STM32F1__ diff --git a/Marlin/src/HAL/STM32F1/persistent_store_flash.cpp b/Marlin/src/HAL/STM32F1/eeprom_flash.cpp similarity index 95% rename from Marlin/src/HAL/STM32F1/persistent_store_flash.cpp rename to Marlin/src/HAL/STM32F1/eeprom_flash.cpp index 3d6a3b45..9c817304 100644 --- a/Marlin/src/HAL/STM32F1/persistent_store_flash.cpp +++ b/Marlin/src/HAL/STM32F1/eeprom_flash.cpp @@ -31,10 +31,9 @@ #include "../../inc/MarlinConfig.h" -// This is for EEPROM emulation in flash -#if BOTH(EEPROM_SETTINGS, FLASH_EEPROM_EMULATION) +#if ENABLED(FLASH_EEPROM_EMULATION) -#include "../shared/persistent_store_api.h" +#include "../shared/eeprom_api.h" #include #include @@ -108,5 +107,5 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, const size_t size, uin size_t PersistentStore::capacity() { return EEPROM_SIZE; } -#endif // EEPROM_SETTINGS && EEPROM FLASH +#endif // FLASH_EEPROM_EMULATION #endif // __STM32F1__ diff --git a/Marlin/src/HAL/STM32F1/persistent_store_sdcard.cpp b/Marlin/src/HAL/STM32F1/eeprom_sdcard.cpp similarity index 98% rename from Marlin/src/HAL/STM32F1/persistent_store_sdcard.cpp rename to Marlin/src/HAL/STM32F1/eeprom_sdcard.cpp index 8b5d89ad..7894e697 100644 --- a/Marlin/src/HAL/STM32F1/persistent_store_sdcard.cpp +++ b/Marlin/src/HAL/STM32F1/eeprom_sdcard.cpp @@ -31,7 +31,7 @@ #if ENABLED(SDCARD_EEPROM_EMULATION) -#include "../shared/persistent_store_api.h" +#include "../shared/eeprom_api.h" #ifndef E2END #define E2END 0xFFF // 4KB @@ -101,5 +101,4 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, const size_t size, uin size_t PersistentStore::capacity() { return HAL_EEPROM_SIZE; } #endif // SDCARD_EEPROM_EMULATION - #endif // __STM32F1__ diff --git a/Marlin/src/HAL/STM32_F4_F7/persistent_store_eeprom.cpp b/Marlin/src/HAL/STM32_F4_F7/eeprom.cpp similarity index 98% rename from Marlin/src/HAL/STM32_F4_F7/persistent_store_eeprom.cpp rename to Marlin/src/HAL/STM32_F4_F7/eeprom.cpp index 2ffbc609..b957aae6 100644 --- a/Marlin/src/HAL/STM32_F4_F7/persistent_store_eeprom.cpp +++ b/Marlin/src/HAL/STM32_F4_F7/eeprom.cpp @@ -27,7 +27,7 @@ #if ENABLED(EEPROM_SETTINGS) -#include "../shared/persistent_store_api.h" +#include "../shared/eeprom_api.h" bool PersistentStore::access_start() { return true; } bool PersistentStore::access_finish() { return true; } diff --git a/Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_post.h b/Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_post.h index 5a190342..d2162495 100644 --- a/Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_post.h +++ b/Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_post.h @@ -22,7 +22,7 @@ #pragma once #if ENABLED(EEPROM_SETTINGS) && defined(STM32F7) - #undef USE_REAL_EEPROM + #undef USE_WIRED_EEPROM #undef SRAM_EEPROM_EMULATION #undef SDCARD_EEPROM_EMULATION #define FLASH_EEPROM_EMULATION diff --git a/Marlin/src/HAL/TEENSY31_32/persistent_store_impl.cpp b/Marlin/src/HAL/TEENSY31_32/eeprom_impl.cpp similarity index 97% rename from Marlin/src/HAL/TEENSY31_32/persistent_store_impl.cpp rename to Marlin/src/HAL/TEENSY31_32/eeprom_impl.cpp index 6a179cd9..96499d4f 100644 --- a/Marlin/src/HAL/TEENSY31_32/persistent_store_impl.cpp +++ b/Marlin/src/HAL/TEENSY31_32/eeprom_impl.cpp @@ -22,7 +22,7 @@ #if ENABLED(EEPROM_SETTINGS) -#include "../shared/persistent_store_api.h" +#include "../shared/eeprom_api.h" bool PersistentStore::access_start() { return true; } bool PersistentStore::access_finish() { return true; } diff --git a/Marlin/src/HAL/TEENSY31_32/fastio.h b/Marlin/src/HAL/TEENSY31_32/fastio.h index 8547fe2b..e74920d4 100644 --- a/Marlin/src/HAL/TEENSY31_32/fastio.h +++ b/Marlin/src/HAL/TEENSY31_32/fastio.h @@ -76,8 +76,9 @@ #define SET_INPUT(IO) _SET_INPUT(IO) #define SET_INPUT_PULLUP(IO) _SET_INPUT_PULLUP(IO) +#define SET_INPUT_PULLDOWN SET_INPUT #define SET_OUTPUT(IO) _SET_OUTPUT(IO) -#define SET_PWM(IO) SET_OUTPUT(IO) +#define SET_PWM SET_OUTPUT #define IS_INPUT(IO) _IS_INPUT(IO) #define IS_OUTPUT(IO) _IS_OUTPUT(IO) diff --git a/Marlin/src/HAL/TEENSY31_32/inc/Conditionals_post.h b/Marlin/src/HAL/TEENSY31_32/inc/Conditionals_post.h index e51b5569..11603c9e 100644 --- a/Marlin/src/HAL/TEENSY31_32/inc/Conditionals_post.h +++ b/Marlin/src/HAL/TEENSY31_32/inc/Conditionals_post.h @@ -22,6 +22,6 @@ #pragma once // If no real EEPROM, Flash emulation, or SRAM emulation is available fall back to SD emulation -#if ENABLED(EEPROM_SETTINGS) && NONE(USE_REAL_EEPROM, FLASH_EEPROM_EMULATION, SRAM_EEPROM_EMULATION) +#if ENABLED(EEPROM_SETTINGS) && NONE(USE_WIRED_EEPROM, FLASH_EEPROM_EMULATION, SRAM_EEPROM_EMULATION) #define SDCARD_EEPROM_EMULATION #endif diff --git a/Marlin/src/HAL/TEENSY35_36/persistent_store_eeprom.cpp b/Marlin/src/HAL/TEENSY35_36/eeprom.cpp similarity index 98% rename from Marlin/src/HAL/TEENSY35_36/persistent_store_eeprom.cpp rename to Marlin/src/HAL/TEENSY35_36/eeprom.cpp index 32b215ee..c66a45e2 100644 --- a/Marlin/src/HAL/TEENSY35_36/persistent_store_eeprom.cpp +++ b/Marlin/src/HAL/TEENSY35_36/eeprom.cpp @@ -27,7 +27,7 @@ #if ENABLED(EEPROM_SETTINGS) -#include "../shared/persistent_store_api.h" +#include "../shared/eeprom_api.h" #include bool PersistentStore::access_start() { return true; } diff --git a/Marlin/src/HAL/TEENSY35_36/fastio.h b/Marlin/src/HAL/TEENSY35_36/fastio.h index 8547fe2b..e74920d4 100644 --- a/Marlin/src/HAL/TEENSY35_36/fastio.h +++ b/Marlin/src/HAL/TEENSY35_36/fastio.h @@ -76,8 +76,9 @@ #define SET_INPUT(IO) _SET_INPUT(IO) #define SET_INPUT_PULLUP(IO) _SET_INPUT_PULLUP(IO) +#define SET_INPUT_PULLDOWN SET_INPUT #define SET_OUTPUT(IO) _SET_OUTPUT(IO) -#define SET_PWM(IO) SET_OUTPUT(IO) +#define SET_PWM SET_OUTPUT #define IS_INPUT(IO) _IS_INPUT(IO) #define IS_OUTPUT(IO) _IS_OUTPUT(IO) diff --git a/Marlin/src/HAL/shared/persistent_store_api.cpp b/Marlin/src/HAL/shared/eeprom_api.cpp similarity index 96% rename from Marlin/src/HAL/shared/persistent_store_api.cpp rename to Marlin/src/HAL/shared/eeprom_api.cpp index 735fa427..d8839e3d 100644 --- a/Marlin/src/HAL/shared/persistent_store_api.cpp +++ b/Marlin/src/HAL/shared/eeprom_api.cpp @@ -24,7 +24,7 @@ #if EITHER(EEPROM_SETTINGS, SD_FIRMWARE_UPDATE) - #include "persistent_store_api.h" + #include "eeprom_api.h" PersistentStore persistentStore; #endif diff --git a/Marlin/src/HAL/shared/persistent_store_api.h b/Marlin/src/HAL/shared/eeprom_api.h similarity index 100% rename from Marlin/src/HAL/shared/persistent_store_api.h rename to Marlin/src/HAL/shared/eeprom_api.h diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 0ea1a22f..8130affe 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -210,6 +210,24 @@ bool wait_for_heatup = true; // For M0/M1, this flag may be cleared (by M108) to exit the wait-for-user loop #if HAS_RESUME_CONTINUE bool wait_for_user; // = false; + + void wait_for_user_response(millis_t ms/*=0*/, const bool no_sleep/*=false*/) { + #if DISABLED(ADVANCED_PAUSE_FEATURE) + UNUSED(no_sleep); + #endif + KEEPALIVE_STATE(PAUSED_FOR_USER); + wait_for_user = true; + if (ms) ms += millis(); // expire time + while (wait_for_user && !(ms && ELAPSED(millis(), ms))) { + idle( + #if ENABLED(ADVANCED_PAUSE_FEATURE) + no_sleep + #endif + ); + } + wait_for_user = false; + } + #endif // Inactivity shutdown @@ -418,52 +436,8 @@ void startOrResumeJob() { } inline void finishSDPrinting() { - - bool did_state = true; - switch (card.sdprinting_done_state) { - - case 1: - did_state = print_job_timer.duration() < 60 || queue.enqueue_one_P(PSTR("M31")); - break; - - case 2: - did_state = queue.enqueue_one_P(PSTR("M77")); - break; - - case 3: - #if ENABLED(LCD_SET_PROGRESS_MANUALLY) - ui.set_progress_done(); - #endif - break; - - case 4: // Display "Click to Continue..." - #if HAS_RESUME_CONTINUE // 30 min timeout with LCD, 1 min without - did_state = queue.enqueue_one_P( - print_job_timer.duration() < 60 ? PSTR("M0Q1P1") : PSTR("M0Q1S" TERN(HAS_LCD_MENU, "1800", "60")) - ); - #endif - break; - - case 5: - #if ENABLED(POWER_LOSS_RECOVERY) - recovery.purge(); - #endif - - #if ENABLED(SD_FINISHED_STEPPERRELEASE) && defined(SD_FINISHED_RELEASECOMMAND) - planner.finish_and_disable(); - #endif - - #if ENABLED(SD_REPRINT_LAST_SELECTED_FILE) - ui.reselect_last_file(); - #endif - - SERIAL_ECHOLNPGM(STR_FILE_PRINTED); - - default: - did_state = false; - card.sdprinting_done_state = 0; - } - if (did_state) ++card.sdprinting_done_state; + if (queue.enqueue_one_P(PSTR("M1001"))) + marlin_state = MF_RUNNING; } #endif // SDSUPPORT @@ -1208,7 +1182,7 @@ void loop() { #if ENABLED(SDSUPPORT) card.checkautostart(); if (card.flag.abort_sd_printing) abortSDPrinting(); - if (card.sdprinting_done_state) finishSDPrinting(); + if (marlin_state == MF_SD_COMPLETE) finishSDPrinting(); #endif queue.advance(); diff --git a/Marlin/src/MarlinCore.h b/Marlin/src/MarlinCore.h index 3bce72ab..e6678c5b 100644 --- a/Marlin/src/MarlinCore.h +++ b/Marlin/src/MarlinCore.h @@ -83,6 +83,7 @@ enum MarlinState : uint8_t { MF_PAUSED = _BV(1), MF_WAITING = _BV(2), MF_STOPPED = _BV(3), + MF_SD_COMPLETE = _BV(4), MF_KILLED = _BV(7) }; @@ -98,6 +99,7 @@ extern bool wait_for_heatup; #if HAS_RESUME_CONTINUE extern bool wait_for_user; + void wait_for_user_response(millis_t ms=0, const bool no_sleep=false); #endif // Inactivity shutdown timer diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index 86107f7d..30c2d3eb 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -144,6 +144,7 @@ #define BOARD_LEAPFROG_XEED2015 1321 // Leapfrog Xeed 2015 #define BOARD_PICA_REVB 1322 // PICA Shield (original version) #define BOARD_PICA 1323 // PICA Shield (rev C or later) +#define BOARD_INTAMSYS40 1324 // Intamsys 4.0 (Funmat HT) // // ATmega1281, ATmega2561 diff --git a/Marlin/src/core/macros.h b/Marlin/src/core/macros.h index bcee6423..899baf73 100644 --- a/Marlin/src/core/macros.h +++ b/Marlin/src/core/macros.h @@ -194,6 +194,9 @@ #define DISABLED(V...) DO(DIS,&&,V) #define TERN(O,A,B) _TERN(_ENA_1(O),B,A) // OPTION converted to '0' or '1' +#define TERN0(O,A) _TERN(_ENA_1(O),0,A) // OPTION converted to A or '0' +#define TERN1(O,A) _TERN(_ENA_1(O),1,A) // OPTION converted to A or '1' +#define TERN_(O,A) _TERN(_ENA_1(O),,A) // OPTION converted to A or '' #define _TERN(E,V...) __TERN(_CAT(T_,E),V) // Prepend 'T_' to get 'T_0' or 'T_1' #define __TERN(T,V...) ___TERN(_CAT(_NO,T),V) // Prepend '_NO' to get '_NOT_0' or '_NOT_1' #define ___TERN(P,V...) THIRD(P,V) // If first argument has a comma, A. Else B. diff --git a/Marlin/src/feature/backlash.cpp b/Marlin/src/feature/backlash.cpp index 84cd0a85..bc33ae31 100644 --- a/Marlin/src/feature/backlash.cpp +++ b/Marlin/src/feature/backlash.cpp @@ -113,7 +113,7 @@ void Backlash::add_correction_steps(const int32_t &da, const int32_t &db, const error_correction = 0; // Don't take up any backlash in this segment, as it would subtract steps } #endif - // Making a correction reduces the residual error and modifies delta_mm + // Making a correction reduces the residual error and adds block steps if (error_correction) { block->steps[axis] += ABS(error_correction); residual_error[axis] -= error_correction; diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index 1ac036e5..217d8945 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -27,7 +27,7 @@ #include "../bedlevel.h" #include "../../../MarlinCore.h" - #include "../../../HAL/shared/persistent_store_api.h" + #include "../../../HAL/shared/eeprom_api.h" #include "../../../libs/hex_print_routines.h" #include "../../../module/configuration_store.h" #include "../../../lcd/ultralcd.h" diff --git a/Marlin/src/feature/max7219.cpp b/Marlin/src/feature/max7219.cpp index 2ec23f01..a012aeb5 100644 --- a/Marlin/src/feature/max7219.cpp +++ b/Marlin/src/feature/max7219.cpp @@ -121,7 +121,7 @@ uint8_t Max7219::suspended; // = 0; #define CRITICAL_SECTION_START() NOOP #define CRITICAL_SECTION_END() NOOP #else - #define SIG_DELAY() DELAY_NS(188) // Delay for 0.1875µs (16MHz AVR) or 0.15µs (20MHz AVR) + #define SIG_DELAY() DELAY_NS(250) #endif void Max7219::error(const char * const func, const int32_t v1, const int32_t v2/*=-1*/) { diff --git a/Marlin/src/feature/mmu2/mmu2.cpp b/Marlin/src/feature/mmu2/mmu2.cpp index 2df34176..4506883f 100644 --- a/Marlin/src/feature/mmu2/mmu2.cpp +++ b/Marlin/src/feature/mmu2/mmu2.cpp @@ -707,14 +707,13 @@ void MMU2::filament_runout() { if (recover) { LCD_MESSAGEPGM(MSG_MMU2_EJECT_RECOVER); BUZZ(200, 404); - wait_for_user = true; #if ENABLED(HOST_PROMPT_SUPPORT) host_prompt_do(PROMPT_USER_CONTINUE, PSTR("MMU2 Eject Recover"), CONTINUE_STR); #endif #if ENABLED(EXTENSIBLE_UI) ExtUI::onUserConfirmRequired_P(PSTR("MMU2 Eject Recover")); #endif - while (wait_for_user) idle(); + wait_for_user_response(); BUZZ(200, 404); BUZZ(200, 404); diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index fb69803e..9c615b6f 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -134,15 +134,6 @@ static bool ensure_safe_temperature(const PauseMode mode=PAUSE_MODE_SAME) { return thermalManager.wait_for_hotend(active_extruder); } -void do_pause_e_move(const float &length, const feedRate_t &fr_mm_s) { - #if HAS_FILAMENT_SENSOR - runout.reset(); - #endif - current_position.e += length / planner.e_factor[active_extruder]; - line_to_current_position(fr_mm_s); - planner.synchronize(); -} - /** * Load filament into the hotend * @@ -184,7 +175,6 @@ bool load_filament(const float &slow_load_length/*=0*/, const float &fast_load_l #endif KEEPALIVE_STATE(PAUSED_FOR_USER); - wait_for_user = true; // LCD click or M108 will clear this #if ENABLED(HOST_PROMPT_SUPPORT) const char tool = '0' #if NUM_RUNOUT_SENSORS > 1 @@ -218,7 +208,7 @@ bool load_filament(const float &slow_load_length/*=0*/, const float &fast_load_l #endif // Slow Load filament - if (slow_load_length) do_pause_e_move(slow_load_length, FILAMENT_CHANGE_SLOW_LOAD_FEEDRATE); + if (slow_load_length) unscaled_e_move(slow_load_length, FILAMENT_CHANGE_SLOW_LOAD_FEEDRATE); // Fast Load Filament if (fast_load_length) { @@ -227,7 +217,7 @@ bool load_filament(const float &slow_load_length/*=0*/, const float &fast_load_l planner.settings.retract_acceleration = FILAMENT_CHANGE_FAST_LOAD_ACCEL; #endif - do_pause_e_move(fast_load_length, FILAMENT_CHANGE_FAST_LOAD_FEEDRATE); + unscaled_e_move(fast_load_length, FILAMENT_CHANGE_FAST_LOAD_FEEDRATE); #if FILAMENT_CHANGE_FAST_LOAD_ACCEL > 0 planner.settings.retract_acceleration = saved_acceleration; @@ -246,15 +236,15 @@ bool load_filament(const float &slow_load_length/*=0*/, const float &fast_load_l if (show_lcd) lcd_pause_show_message(PAUSE_MESSAGE_PURGE); #endif - wait_for_user = true; #if ENABLED(HOST_PROMPT_SUPPORT) host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Filament Purging..."), CONTINUE_STR); #endif #if ENABLED(EXTENSIBLE_UI) ExtUI::onUserConfirmRequired_P(PSTR("Filament Purging...")); #endif + wait_for_user = true; // A click or M108 breaks the purge_length loop for (float purge_count = purge_length; purge_count > 0 && wait_for_user; --purge_count) - do_pause_e_move(1, ADVANCED_PAUSE_PURGE_FEEDRATE); + unscaled_e_move(1, ADVANCED_PAUSE_PURGE_FEEDRATE); wait_for_user = false; #else @@ -267,7 +257,7 @@ bool load_filament(const float &slow_load_length/*=0*/, const float &fast_load_l #endif // Extrude filament to get into hotend - do_pause_e_move(purge_length, ADVANCED_PAUSE_PURGE_FEEDRATE); + unscaled_e_move(purge_length, ADVANCED_PAUSE_PURGE_FEEDRATE); } #if ENABLED(HOST_PROMPT_SUPPORT) @@ -332,13 +322,13 @@ bool unload_filament(const float &unload_length, const bool show_lcd/*=false*/, #endif // Retract filament - do_pause_e_move(-(FILAMENT_UNLOAD_PURGE_RETRACT) * mix_multiplier, (PAUSE_PARK_RETRACT_FEEDRATE) * mix_multiplier); + unscaled_e_move(-(FILAMENT_UNLOAD_PURGE_RETRACT) * mix_multiplier, (PAUSE_PARK_RETRACT_FEEDRATE) * mix_multiplier); // Wait for filament to cool safe_delay(FILAMENT_UNLOAD_PURGE_DELAY); // Quickly purge - do_pause_e_move((FILAMENT_UNLOAD_PURGE_RETRACT + FILAMENT_UNLOAD_PURGE_LENGTH) * mix_multiplier, + unscaled_e_move((FILAMENT_UNLOAD_PURGE_RETRACT + FILAMENT_UNLOAD_PURGE_LENGTH) * mix_multiplier, (FILAMENT_UNLOAD_PURGE_FEEDRATE) * mix_multiplier); // Unload filament @@ -347,7 +337,7 @@ bool unload_filament(const float &unload_length, const bool show_lcd/*=false*/, planner.settings.retract_acceleration = FILAMENT_CHANGE_UNLOAD_ACCEL; #endif - do_pause_e_move(unload_length * mix_multiplier, (FILAMENT_CHANGE_UNLOAD_FEEDRATE) * mix_multiplier); + unscaled_e_move(unload_length * mix_multiplier, (FILAMENT_CHANGE_UNLOAD_FEEDRATE) * mix_multiplier); #if FILAMENT_CHANGE_FAST_LOAD_ACCEL > 0 planner.settings.retract_acceleration = saved_acceleration; @@ -437,7 +427,7 @@ bool pause_print(const float &retract, const xyz_pos_t &park_point, const float // Initial retract before move to filament change position if (retract && thermalManager.hotEnoughToExtrude(active_extruder)) - do_pause_e_move(retract, PAUSE_PARK_RETRACT_FEEDRATE); + unscaled_e_move(retract, PAUSE_PARK_RETRACT_FEEDRATE); // Park the nozzle by moving up by z_lift and then moving to (x_pos, y_pos) if (!axes_need_homing()) @@ -508,13 +498,13 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep // Wait for filament insert by user and press button KEEPALIVE_STATE(PAUSED_FOR_USER); - wait_for_user = true; // LCD click or M108 will clear this #if ENABLED(HOST_PROMPT_SUPPORT) host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Nozzle Parked"), CONTINUE_STR); #endif #if ENABLED(EXTENSIBLE_UI) ExtUI::onUserConfirmRequired_P(PSTR("Nozzle Parked")); #endif + wait_for_user = true; // LCD click or M108 will clear this while (wait_for_user) { #if HAS_BUZZER filament_change_beep(max_beep_count); @@ -540,8 +530,7 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep ExtUI::onUserConfirmRequired_P(PSTR("HeaterTimeout")); #endif - // Wait for LCD click or M108 - while (wait_for_user) idle_no_sleep(); + wait_for_user_response(0, true); // Wait for LCD click or M108 #if ENABLED(HOST_PROMPT_SUPPORT) host_prompt_do(PROMPT_INFO, PSTR("Reheating")); @@ -633,11 +622,11 @@ void resume_print(const float &slow_load_length/*=0*/, const float &fast_load_le #if ENABLED(FWRETRACT) // If retracted before goto pause if (fwretract.retracted[active_extruder]) - do_pause_e_move(-fwretract.settings.retract_length, fwretract.settings.retract_feedrate_mm_s); + unscaled_e_move(-fwretract.settings.retract_length, fwretract.settings.retract_feedrate_mm_s); #endif // If resume_position is negative - if (resume_position.e < 0) do_pause_e_move(resume_position.e, feedRate_t(PAUSE_PARK_RETRACT_FEEDRATE)); + if (resume_position.e < 0) unscaled_e_move(resume_position.e, feedRate_t(PAUSE_PARK_RETRACT_FEEDRATE)); // Move XY to starting position, then Z do_blocking_move_to_xy(resume_position, feedRate_t(NOZZLE_PARK_XY_FEEDRATE)); @@ -646,7 +635,7 @@ void resume_print(const float &slow_load_length/*=0*/, const float &fast_load_le do_blocking_move_to_z(resume_position.z, feedRate_t(NOZZLE_PARK_Z_FEEDRATE)); #if ADVANCED_PAUSE_RESUME_PRIME != 0 - do_pause_e_move(ADVANCED_PAUSE_RESUME_PRIME, feedRate_t(ADVANCED_PAUSE_PURGE_FEEDRATE)); + unscaled_e_move(ADVANCED_PAUSE_RESUME_PRIME, feedRate_t(ADVANCED_PAUSE_PURGE_FEEDRATE)); #endif // Now all extrusion positions are resumed and ready to be confirmed diff --git a/Marlin/src/feature/pause.h b/Marlin/src/feature/pause.h index 5ac67a56..f1c8eed4 100644 --- a/Marlin/src/feature/pause.h +++ b/Marlin/src/feature/pause.h @@ -83,8 +83,6 @@ extern uint8_t did_pause_print; #define DXC_PASS #endif -void do_pause_e_move(const float &length, const feedRate_t &fr_mm_s); - bool pause_print(const float &retract, const xyz_pos_t &park_point, const float &unload_length=0, const bool show_lcd=false DXC_PARAMS); void wait_for_confirmation(const bool is_reload=false, const int8_t max_beep_count=0 DXC_PARAMS); diff --git a/Marlin/src/feature/twibus.cpp b/Marlin/src/feature/twibus.cpp index 60d78018..9dbb1deb 100644 --- a/Marlin/src/feature/twibus.cpp +++ b/Marlin/src/feature/twibus.cpp @@ -49,37 +49,27 @@ void TWIBus::address(const uint8_t adr) { addr = adr; - #if ENABLED(DEBUG_TWIBUS) - debug(PSTR("address"), adr); - #endif + debug(PSTR("address"), adr); } void TWIBus::addbyte(const char c) { if (buffer_s >= COUNT(buffer)) return; buffer[buffer_s++] = c; - #if ENABLED(DEBUG_TWIBUS) - debug(PSTR("addbyte"), c); - #endif + debug(PSTR("addbyte"), c); } void TWIBus::addbytes(char src[], uint8_t bytes) { - #if ENABLED(DEBUG_TWIBUS) - debug(PSTR("addbytes"), bytes); - #endif + debug(PSTR("addbytes"), bytes); while (bytes--) addbyte(*src++); } void TWIBus::addstring(char str[]) { - #if ENABLED(DEBUG_TWIBUS) - debug(PSTR("addstring"), str); - #endif + debug(PSTR("addstring"), str); while (char c = *str++) addbyte(c); } void TWIBus::send() { - #if ENABLED(DEBUG_TWIBUS) - debug(PSTR("send"), addr); - #endif + debug(PSTR("send"), addr); Wire.beginTransmission(I2C_ADDRESS(addr)); Wire.write(buffer, buffer_s); @@ -89,21 +79,21 @@ void TWIBus::send() { } // static -void TWIBus::echoprefix(uint8_t bytes, const char prefix[], uint8_t adr) { +void TWIBus::echoprefix(uint8_t bytes, const char pref[], uint8_t adr) { SERIAL_ECHO_START(); - serialprintPGM(prefix); + serialprintPGM(pref); SERIAL_ECHOPAIR(": from:", adr, " bytes:", bytes, " data:"); } // static -void TWIBus::echodata(uint8_t bytes, const char prefix[], uint8_t adr) { - echoprefix(bytes, prefix, adr); +void TWIBus::echodata(uint8_t bytes, const char pref[], uint8_t adr) { + echoprefix(bytes, pref, adr); while (bytes-- && Wire.available()) SERIAL_CHAR(Wire.read()); SERIAL_EOL(); } -void TWIBus::echobuffer(const char prefix[], uint8_t adr) { - echoprefix(buffer_s, prefix, adr); +void TWIBus::echobuffer(const char pref[], uint8_t adr) { + echoprefix(buffer_s, pref, adr); LOOP_L_N(i, buffer_s) SERIAL_CHAR(buffer[i]); SERIAL_EOL(); } @@ -111,15 +101,11 @@ void TWIBus::echobuffer(const char prefix[], uint8_t adr) { bool TWIBus::request(const uint8_t bytes) { if (!addr) return false; - #if ENABLED(DEBUG_TWIBUS) - debug(PSTR("request"), bytes); - #endif + debug(PSTR("request"), bytes); // requestFrom() is a blocking function if (Wire.requestFrom(addr, bytes) == 0) { - #if ENABLED(DEBUG_TWIBUS) - debug("request fail", addr); - #endif + debug("request fail", addr); return false; } @@ -127,9 +113,7 @@ bool TWIBus::request(const uint8_t bytes) { } void TWIBus::relay(const uint8_t bytes) { - #if ENABLED(DEBUG_TWIBUS) - debug(PSTR("relay"), bytes); - #endif + debug(PSTR("relay"), bytes); if (request(bytes)) echodata(bytes, PSTR("i2c-reply"), addr); @@ -141,9 +125,7 @@ uint8_t TWIBus::capture(char *dst, const uint8_t bytes) { while (count < bytes && Wire.available()) dst[count++] = Wire.read(); - #if ENABLED(DEBUG_TWIBUS) - debug(PSTR("capture"), count); - #endif + debug(PSTR("capture"), count); return count; } @@ -156,16 +138,12 @@ void TWIBus::flush() { #if I2C_SLAVE_ADDRESS > 0 void TWIBus::receive(uint8_t bytes) { - #if ENABLED(DEBUG_TWIBUS) - debug(PSTR("receive"), bytes); - #endif + debug(PSTR("receive"), bytes); echodata(bytes, PSTR("i2c-receive"), 0); } void TWIBus::reply(char str[]/*=nullptr*/) { - #if ENABLED(DEBUG_TWIBUS) - debug(PSTR("reply"), str); - #endif + debug(PSTR("reply"), str); if (str) { reset(); diff --git a/Marlin/src/feature/twibus.h b/Marlin/src/feature/twibus.h index faf9eb38..2c1b20da 100644 --- a/Marlin/src/feature/twibus.h +++ b/Marlin/src/feature/twibus.h @@ -223,7 +223,6 @@ class TWIBus { #endif #if ENABLED(DEBUG_TWIBUS) - /** * @brief Prints a debug message * @details Prints a simple debug message "TWIBus::function: value" @@ -233,6 +232,10 @@ class TWIBus { static void debug(const char func[], char c); static void debug(const char func[], char adr[]); static inline void debug(const char func[], uint8_t v) { debug(func, (uint32_t)v); } - + #else + static inline void debug(const char[], uint32_t) {} + static inline void debug(const char[], char) {} + static inline void debug(const char[], char[]) {} + static inline void debug(const char[], uint8_t) {} #endif }; diff --git a/Marlin/src/gcode/calibrate/G28.cpp b/Marlin/src/gcode/calibrate/G28.cpp index 4603c769..fafce9a8 100644 --- a/Marlin/src/gcode/calibrate/G28.cpp +++ b/Marlin/src/gcode/calibrate/G28.cpp @@ -255,28 +255,28 @@ void GcodeSuite::G28() { #define HAS_HOMING_CURRENT (HAS_CURRENT_HOME(X) || HAS_CURRENT_HOME(X2) || HAS_CURRENT_HOME(Y) || HAS_CURRENT_HOME(Y2)) #if HAS_HOMING_CURRENT - auto debug_current = [](const char * const s, const int16_t a, const int16_t b){ - DEBUG_ECHO(s); DEBUG_ECHOLNPAIR(" current: ", a, " -> ", b); + auto debug_current = [](PGM_P const s, const int16_t a, const int16_t b){ + serialprintPGM(s); DEBUG_ECHOLNPAIR(" current: ", a, " -> ", b); }; #if HAS_CURRENT_HOME(X) const int16_t tmc_save_current_X = stepperX.getMilliamps(); stepperX.rms_current(X_CURRENT_HOME); - if (DEBUGGING(LEVELING)) debug_current("X", tmc_save_current_X, X_CURRENT_HOME); + if (DEBUGGING(LEVELING)) debug_current(PSTR("X"), tmc_save_current_X, X_CURRENT_HOME); #endif #if HAS_CURRENT_HOME(X2) const int16_t tmc_save_current_X2 = stepperX2.getMilliamps(); stepperX2.rms_current(X2_CURRENT_HOME); - if (DEBUGGING(LEVELING)) debug_current("X2", tmc_save_current_X2, X2_CURRENT_HOME); + if (DEBUGGING(LEVELING)) debug_current(PSTR("X2"), tmc_save_current_X2, X2_CURRENT_HOME); #endif #if HAS_CURRENT_HOME(Y) const int16_t tmc_save_current_Y = stepperY.getMilliamps(); stepperY.rms_current(Y_CURRENT_HOME); - if (DEBUGGING(LEVELING)) debug_current("Y", tmc_save_current_Y, Y_CURRENT_HOME); + if (DEBUGGING(LEVELING)) debug_current(PSTR("Y"), tmc_save_current_Y, Y_CURRENT_HOME); #endif #if HAS_CURRENT_HOME(Y2) const int16_t tmc_save_current_Y2 = stepperY2.getMilliamps(); stepperY2.rms_current(Y2_CURRENT_HOME); - if (DEBUGGING(LEVELING)) debug_current("Y2", tmc_save_current_Y2, Y2_CURRENT_HOME); + if (DEBUGGING(LEVELING)) debug_current(PSTR("Y2"), tmc_save_current_Y2, Y2_CURRENT_HOME); #endif #endif @@ -345,12 +345,8 @@ void GcodeSuite::G28() { #endif // Home Y (before X) - #if ENABLED(HOME_Y_BEFORE_X) - - if (doY || (doX && ENABLED(CODEPENDENT_XY_HOMING))) - homeaxis(Y_AXIS); - - #endif + if (ENABLED(HOME_Y_BEFORE_X) && (doY || (ENABLED(CODEPENDENT_XY_HOMING) && doX))) + homeaxis(Y_AXIS); // Home X if (doX || (doY && ENABLED(CODEPENDENT_XY_HOMING) && DISABLED(HOME_Y_BEFORE_X))) { diff --git a/Marlin/src/gcode/calibrate/G425.cpp b/Marlin/src/gcode/calibrate/G425.cpp index 69fb2916..42c56fe5 100644 --- a/Marlin/src/gcode/calibrate/G425.cpp +++ b/Marlin/src/gcode/calibrate/G425.cpp @@ -37,6 +37,21 @@ #include "../../module/endstops.h" #include "../../feature/bedlevel/bedlevel.h" +#if !AXIS_CAN_CALIBRATE(X) + #undef CALIBRATION_MEASURE_LEFT + #undef CALIBRATION_MEASURE_RIGHT +#endif + +#if !AXIS_CAN_CALIBRATE(Y) + #undef CALIBRATION_MEASURE_FRONT + #undef CALIBRATION_MEASURE_BACK +#endif + +#if !AXIS_CAN_CALIBRATE(Z) + #undef CALIBRATION_MEASURE_AT_TOP_EDGES +#endif + + /** * G425 backs away from the calibration object by various distances * depending on the confidence level: @@ -207,42 +222,52 @@ inline float measure(const AxisEnum axis, const int dir, const bool stop_state, inline void probe_side(measurements_t &m, const float uncertainty, const side_t side, const bool probe_top_at_edge=false) { const xyz_float_t dimensions = CALIBRATION_OBJECT_DIMENSIONS; AxisEnum axis; - float dir; + float dir = 1; park_above_object(m, uncertainty); switch (side) { - case TOP: { - const float measurement = measure(Z_AXIS, -1, true, &m.backlash[TOP], uncertainty); - m.obj_center.z = measurement - dimensions.z / 2; - m.obj_side[TOP] = measurement; - return; - } - case RIGHT: axis = X_AXIS; dir = -1; break; - case FRONT: axis = Y_AXIS; dir = 1; break; - case LEFT: axis = X_AXIS; dir = 1; break; - case BACK: axis = Y_AXIS; dir = -1; break; + #if AXIS_CAN_CALIBRATE(Z) + case TOP: { + const float measurement = measure(Z_AXIS, -1, true, &m.backlash[TOP], uncertainty); + m.obj_center.z = measurement - dimensions.z / 2; + m.obj_side[TOP] = measurement; + return; + } + #endif + #if AXIS_CAN_CALIBRATE(X) + case LEFT: axis = X_AXIS; break; + case RIGHT: axis = X_AXIS; dir = -1; break; + #endif + #if AXIS_CAN_CALIBRATE(Y) + case FRONT: axis = Y_AXIS; break; + case BACK: axis = Y_AXIS; dir = -1; break; + #endif default: return; } if (probe_top_at_edge) { - // Probe top nearest the side we are probing - current_position[axis] = m.obj_center[axis] + (-dir) * (dimensions[axis] / 2 - m.nozzle_outer_dimension[axis]); - calibration_move(); - m.obj_side[TOP] = measure(Z_AXIS, -1, true, &m.backlash[TOP], uncertainty); - m.obj_center.z = m.obj_side[TOP] - dimensions.z / 2; + #if AXIS_CAN_CALIBRATE(Z) + // Probe top nearest the side we are probing + current_position[axis] = m.obj_center[axis] + (-dir) * (dimensions[axis] / 2 - m.nozzle_outer_dimension[axis]); + calibration_move(); + m.obj_side[TOP] = measure(Z_AXIS, -1, true, &m.backlash[TOP], uncertainty); + m.obj_center.z = m.obj_side[TOP] - dimensions.z / 2; + #endif } - // Move to safe distance to the side of the calibration object - current_position[axis] = m.obj_center[axis] + (-dir) * (dimensions[axis] / 2 + m.nozzle_outer_dimension[axis] / 2 + uncertainty); - calibration_move(); + if (AXIS_CAN_CALIBRATE(X) && axis == X_AXIS || AXIS_CAN_CALIBRATE(Y) && axis == Y_AXIS) { + // Move to safe distance to the side of the calibration object + current_position[axis] = m.obj_center[axis] + (-dir) * (dimensions[axis] / 2 + m.nozzle_outer_dimension[axis] / 2 + uncertainty); + calibration_move(); - // Plunge below the side of the calibration object and measure - current_position.z = m.obj_side[TOP] - CALIBRATION_NOZZLE_TIP_HEIGHT * 0.7; - calibration_move(); - const float measurement = measure(axis, dir, true, &m.backlash[side], uncertainty); - m.obj_center[axis] = measurement + dir * (dimensions[axis] / 2 + m.nozzle_outer_dimension[axis] / 2); - m.obj_side[side] = measurement; + // Plunge below the side of the calibration object and measure + current_position.z = m.obj_side[TOP] - (CALIBRATION_NOZZLE_TIP_HEIGHT) * 0.7f; + calibration_move(); + const float measurement = measure(axis, dir, true, &m.backlash[side], uncertainty); + m.obj_center[axis] = measurement + dir * (dimensions[axis] / 2 + m.nozzle_outer_dimension[axis] / 2); + m.obj_side[side] = measurement; + } } /** @@ -252,7 +277,7 @@ inline void probe_side(measurements_t &m, const float uncertainty, const side_t * uncertainty in - How far away from the calibration object to begin probing */ inline void probe_sides(measurements_t &m, const float uncertainty) { - #ifdef CALIBRATION_MEASURE_AT_TOP_EDGES + #if ENABLED(CALIBRATION_MEASURE_AT_TOP_EDGES) constexpr bool probe_top_at_edge = true; #else // Probing at the exact center only works if the center is flat. Probing on a washer @@ -261,18 +286,18 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { probe_side(m, uncertainty, TOP); #endif - #ifdef CALIBRATION_MEASURE_RIGHT + #if ENABLED(CALIBRATION_MEASURE_RIGHT) probe_side(m, uncertainty, RIGHT, probe_top_at_edge); #endif - #ifdef CALIBRATION_MEASURE_FRONT + #if ENABLED(CALIBRATION_MEASURE_FRONT) probe_side(m, uncertainty, FRONT, probe_top_at_edge); #endif - #ifdef CALIBRATION_MEASURE_LEFT + #if ENABLED(CALIBRATION_MEASURE_LEFT) probe_side(m, uncertainty, LEFT, probe_top_at_edge); #endif - #ifdef CALIBRATION_MEASURE_BACK + #if ENABLED(CALIBRATION_MEASURE_BACK) probe_side(m, uncertainty, BACK, probe_top_at_edge); #endif @@ -313,7 +338,9 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { #if ENABLED(CALIBRATION_REPORTING) inline void report_measured_faces(const measurements_t &m) { SERIAL_ECHOLNPGM("Sides:"); - SERIAL_ECHOLNPAIR(" Top: ", m.obj_side[TOP]); + #if AXIS_CAN_CALIBRATE(Z) + SERIAL_ECHOLNPAIR(" Top: ", m.obj_side[TOP]); + #endif #if ENABLED(CALIBRATION_MEASURE_LEFT) SERIAL_ECHOLNPAIR(" Left: ", m.obj_side[LEFT]); #endif @@ -343,19 +370,25 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { inline void report_measured_backlash(const measurements_t &m) { SERIAL_ECHOLNPGM("Backlash:"); - #if ENABLED(CALIBRATION_MEASURE_LEFT) - SERIAL_ECHOLNPAIR(" Left: ", m.backlash[LEFT]); - #endif - #if ENABLED(CALIBRATION_MEASURE_RIGHT) - SERIAL_ECHOLNPAIR(" Right: ", m.backlash[RIGHT]); + #if AXIS_CAN_CALIBRATE(X) + #if ENABLED(CALIBRATION_MEASURE_LEFT) + SERIAL_ECHOLNPAIR(" Left: ", m.backlash[LEFT]); + #endif + #if ENABLED(CALIBRATION_MEASURE_RIGHT) + SERIAL_ECHOLNPAIR(" Right: ", m.backlash[RIGHT]); + #endif #endif - #if ENABLED(CALIBRATION_MEASURE_FRONT) - SERIAL_ECHOLNPAIR(" Front: ", m.backlash[FRONT]); + #if AXIS_CAN_CALIBRATE(Y) + #if ENABLED(CALIBRATION_MEASURE_FRONT) + SERIAL_ECHOLNPAIR(" Front: ", m.backlash[FRONT]); + #endif + #if ENABLED(CALIBRATION_MEASURE_BACK) + SERIAL_ECHOLNPAIR(" Back: ", m.backlash[BACK]); + #endif #endif - #if ENABLED(CALIBRATION_MEASURE_BACK) - SERIAL_ECHOLNPAIR(" Back: ", m.backlash[BACK]); + #if AXIS_CAN_CALIBRATE(Z) + SERIAL_ECHOLNPAIR(" Top: ", m.backlash[TOP]); #endif - SERIAL_ECHOLNPAIR(" Top: ", m.backlash[TOP]); SERIAL_EOL(); } @@ -369,7 +402,7 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { #if HAS_Y_CENTER SERIAL_ECHOLNPAIR_P(SP_Y_STR, m.pos_error.y); #endif - SERIAL_ECHOLNPAIR_P(SP_Z_STR, m.pos_error.z); + if (AXIS_CAN_CALIBRATE(Z)) SERIAL_ECHOLNPAIR_P(SP_Z_STR, m.pos_error.z); SERIAL_EOL(); } @@ -417,6 +450,7 @@ inline void calibrate_backlash(measurements_t &m, const float uncertainty) { probe_sides(m, uncertainty); #if ENABLED(BACKLASH_GCODE) + #if HAS_X_CENTER backlash.distance_mm.x = (m.backlash[LEFT] + m.backlash[RIGHT]) / 2; #elif ENABLED(CALIBRATION_MEASURE_LEFT) @@ -433,18 +467,18 @@ inline void calibrate_backlash(measurements_t &m, const float uncertainty) { backlash.distance_mm.y = m.backlash[BACK]; #endif - backlash.distance_mm.z = m.backlash[TOP]; + if (AXIS_CAN_CALIBRATE(Z)) backlash.distance_mm.z = m.backlash[TOP]; #endif } #if ENABLED(BACKLASH_GCODE) // Turn on backlash compensation and move in all - // directions to take up any backlash + // allowed directions to take up any backlash { // New scope for TEMPORARY_BACKLASH_CORRECTION TEMPORARY_BACKLASH_CORRECTION(all_on); TEMPORARY_BACKLASH_SMOOTHING(0.0f); - const xyz_float_t move = { 3, 3, 3 }; + const xyz_float_t move = { AXIS_CAN_CALIBRATE(X) * 3, AXIS_CAN_CALIBRATE(Y) * 3, AXIS_CAN_CALIBRATE(Z) * 3 }; current_position += move; calibration_move(); current_position -= move; calibration_move(); } @@ -482,26 +516,18 @@ inline void calibrate_toolhead(measurements_t &m, const float uncertainty, const // Adjust the hotend offset #if HAS_HOTEND_OFFSET - #if HAS_X_CENTER - hotend_offset[extruder].x += m.pos_error.x; - #endif - #if HAS_Y_CENTER - hotend_offset[extruder].y += m.pos_error.y; - #endif - hotend_offset[extruder].z += m.pos_error.z; + if (ENABLED(HAS_X_CENTER) && AXIS_CAN_CALIBRATE(X)) hotend_offset[extruder].x += m.pos_error.x; + if (ENABLED(HAS_Y_CENTER) && AXIS_CAN_CALIBRATE(Y)) hotend_offset[extruder].y += m.pos_error.y; + if (AXIS_CAN_CALIBRATE(Z)) hotend_offset[extruder].z += m.pos_error.z; normalize_hotend_offsets(); #endif // Correct for positional error, so the object // is at the known actual spot planner.synchronize(); - #if HAS_X_CENTER - update_measurements(m, X_AXIS); - #endif - #if HAS_Y_CENTER - update_measurements(m, Y_AXIS); - #endif - update_measurements(m, Z_AXIS); + if (ENABLED(HAS_X_CENTER) && AXIS_CAN_CALIBRATE(X)) update_measurements(m, X_AXIS); + if (ENABLED(HAS_Y_CENTER) && AXIS_CAN_CALIBRATE(Y)) update_measurements(m, Y_AXIS); + if (AXIS_CAN_CALIBRATE(Z)) update_measurements(m, Z_AXIS); sync_plan_position(); } diff --git a/Marlin/src/gcode/calibrate/M425.cpp b/Marlin/src/gcode/calibrate/M425.cpp index 41c80daf..980152a4 100644 --- a/Marlin/src/gcode/calibrate/M425.cpp +++ b/Marlin/src/gcode/calibrate/M425.cpp @@ -47,7 +47,7 @@ void GcodeSuite::M425() { bool noArgs = true; LOOP_XYZ(a) { - if (parser.seen(XYZ_CHAR(a))) { + if (CAN_CALIBRATE(a) && parser.seen(XYZ_CHAR(a))) { planner.synchronize(); backlash.distance_mm[a] = parser.has_value() ? parser.value_linear_units() : backlash.get_measurement(AxisEnum(a)); noArgs = false; @@ -74,7 +74,7 @@ void GcodeSuite::M425() { SERIAL_ECHOLNPGM("active:"); SERIAL_ECHOLNPAIR(" Correction Amount/Fade-out: F", backlash.get_correction(), " (F1.0 = full, F0.0 = none)"); SERIAL_ECHOPGM(" Backlash Distance (mm): "); - LOOP_XYZ(a) { + LOOP_XYZ(a) if (CAN_CALIBRATE(a)) { SERIAL_CHAR(' ', XYZ_CHAR(a)); SERIAL_ECHO(backlash.distance_mm[a]); SERIAL_EOL(); @@ -87,7 +87,7 @@ void GcodeSuite::M425() { #if ENABLED(MEASURE_BACKLASH_WHEN_PROBING) SERIAL_ECHOPGM(" Average measured backlash (mm):"); if (backlash.has_any_measurement()) { - LOOP_XYZ(a) if (backlash.has_measurement(AxisEnum(a))) { + LOOP_XYZ(a) if (CAN_CALIBRATE(a) && backlash.has_measurement(AxisEnum(a))) { SERIAL_CHAR(' ', XYZ_CHAR(a)); SERIAL_ECHO(backlash.get_measurement(AxisEnum(a))); } diff --git a/Marlin/src/gcode/config/M43.cpp b/Marlin/src/gcode/config/M43.cpp index 2c28da62..baf5efb1 100644 --- a/Marlin/src/gcode/config/M43.cpp +++ b/Marlin/src/gcode/config/M43.cpp @@ -67,7 +67,11 @@ inline void toggle_pins() { else { watchdog_refresh(); report_pin_state_extended(pin, ignore_protection, true, PSTR("Pulsing ")); - const bool prior_mode = GET_PINMODE(pin); + #ifdef __STM32F1__ + const auto prior_mode = _GET_MODE(i); + #else + const bool prior_mode = GET_PINMODE(pin); + #endif #if AVR_AT90USB1286_FAMILY // Teensy IDEs don't know about these pins so must use FASTIO if (pin == TEENSY_E2) { SET_OUTPUT(TEENSY_E2); @@ -96,7 +100,11 @@ inline void toggle_pins() { watchdog_refresh(); } } - pinMode(pin, prior_mode); + #ifdef __STM32F1__ + _SET_MODE(i, prior_mode); + #else + pinMode(pin, prior_mode); + #endif } SERIAL_EOL(); } diff --git a/Marlin/src/gcode/feature/camera/M240.cpp b/Marlin/src/gcode/feature/camera/M240.cpp index 3c045a7e..33ef9bf1 100644 --- a/Marlin/src/gcode/feature/camera/M240.cpp +++ b/Marlin/src/gcode/feature/camera/M240.cpp @@ -48,14 +48,8 @@ #ifdef PHOTO_RETRACT_MM inline void e_move_m240(const float length, const feedRate_t &fr_mm_s) { - if (length && thermalManager.hotEnoughToExtrude(active_extruder)) { - #if ENABLED(ADVANCED_PAUSE_FEATURE) - do_pause_e_move(length, fr_mm_s); - #else - current_position.e += length / planner.e_factor[active_extruder]; - line_to_current_position(fr_mm_s); - #endif - } + if (length && thermalManager.hotEnoughToExtrude(active_extruder)) + unscaled_e_move(length, fr_mm_s); } #endif diff --git a/Marlin/src/gcode/feature/powerloss/M1000.cpp b/Marlin/src/gcode/feature/powerloss/M1000.cpp index ea2c6e3d..8d8cdc75 100644 --- a/Marlin/src/gcode/feature/powerloss/M1000.cpp +++ b/Marlin/src/gcode/feature/powerloss/M1000.cpp @@ -63,7 +63,7 @@ void GcodeSuite::M1000() { #if HAS_LCD_MENU ui.goto_screen(menu_job_recovery); #elif ENABLED(EXTENSIBLE_UI) - ExtUI::OnPowerLossResume(); + ExtUI::onPowerLossResume(); #else SERIAL_ECHO_MSG("Resume requires LCD."); #endif diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index 1ce1e3d5..1f9d710b 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -857,7 +857,11 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { #if ENABLED(POWER_LOSS_RECOVERY) case 413: M413(); break; // M413: Enable/disable/query Power-Loss Recovery - case 1000: M1000(); break; // M1000: Resume from power-loss + case 1000: M1000(); break; // M1000: [INTERNAL] Resume from power-loss + #endif + + #if ENABLED(SDSUPPORT) + case 1001: M1001(); break; // M1001: [INTERNAL] Handle SD completion #endif #if ENABLED(MAX7219_GCODE) diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index c1024ac4..8e5d054d 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -968,6 +968,10 @@ class GcodeSuite { static void M1000(); #endif + #if ENABLED(SDSUPPORT) + static void M1001(); + #endif + #if ENABLED(MAX7219_GCODE) static void M7219(); #endif diff --git a/Marlin/src/gcode/lcd/M0_M1.cpp b/Marlin/src/gcode/lcd/M0_M1.cpp index 21766932..190023b0 100644 --- a/Marlin/src/gcode/lcd/M0_M1.cpp +++ b/Marlin/src/gcode/lcd/M0_M1.cpp @@ -24,23 +24,19 @@ #if HAS_RESUME_CONTINUE +#include "../../inc/MarlinConfig.h" + #include "../gcode.h" -#include "../../module/planner.h" -#include "../../inc/MarlinConfig.h" +#include "../../module/planner.h" // for synchronize() +#include "../../MarlinCore.h" // for wait_for_user_response() #if HAS_LCD_MENU #include "../../lcd/ultralcd.h" -#endif - -#if ENABLED(EXTENSIBLE_UI) +#elif ENABLED(EXTENSIBLE_UI) #include "../../lcd/extui/ui_api.h" #endif -#if HAS_LEDS_OFF_FLAG - #include "../../feature/leds/printer_event_leds.h" -#endif - #if ENABLED(HOST_PROMPT_SUPPORT) #include "../../feature/host_actions.h" #endif @@ -56,16 +52,11 @@ void GcodeSuite::M0_M1() { planner.synchronize(); - const bool seenQ = parser.seen('Q'); - #if HAS_LEDS_OFF_FLAG - if (seenQ) printerEventLEDs.onPrintCompleted(); // Change LED color for Print Completed - #endif - #if HAS_LCD_MENU if (parser.string_arg) ui.set_status(parser.string_arg, true); - else if (!seenQ) { + else { LCD_MESSAGEPGM(MSG_USERWAIT); #if ENABLED(LCD_PROGRESS_BAR) && PROGRESS_MSG_EXPIRE > 0 ui.reset_progress_bar_timeout(); @@ -73,12 +64,10 @@ void GcodeSuite::M0_M1() { } #elif ENABLED(EXTENSIBLE_UI) - if (parser.string_arg) ExtUI::onUserConfirmRequired(parser.string_arg); // Can this take an SRAM string?? else ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_USERWAIT)); - #else if (parser.string_arg) { @@ -88,25 +77,15 @@ void GcodeSuite::M0_M1() { #endif - KEEPALIVE_STATE(PAUSED_FOR_USER); - wait_for_user = true; - #if ENABLED(HOST_PROMPT_SUPPORT) host_prompt_do(PROMPT_USER_CONTINUE, parser.codenum ? PSTR("M1 Stop") : PSTR("M0 Stop"), CONTINUE_STR); #endif - if (ms > 0) ms += millis(); // wait until this time for a click - while (wait_for_user && (ms == 0 || PENDING(millis(), ms))) idle(); - - #if HAS_LEDS_OFF_FLAG - printerEventLEDs.onResumeAfterWait(); - #endif + wait_for_user_response(ms); #if HAS_LCD_MENU - if (!seenQ) ui.reset_status(); + ui.reset_status(); #endif - - wait_for_user = false; } #endif // HAS_RESUME_CONTINUE diff --git a/Marlin/src/gcode/motion/G2_G3.cpp b/Marlin/src/gcode/motion/G2_G3.cpp index b11b1136..b0fb299a 100644 --- a/Marlin/src/gcode/motion/G2_G3.cpp +++ b/Marlin/src/gcode/motion/G2_G3.cpp @@ -236,7 +236,7 @@ void plan_arc( planner.apply_leveling(raw); #endif - planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, seg_length + planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, 0 #if ENABLED(SCARA_FEEDRATE_SCALING) , inv_duration #endif diff --git a/Marlin/src/gcode/sd/M1001.cpp b/Marlin/src/gcode/sd/M1001.cpp new file mode 100644 index 00000000..4261b57f --- /dev/null +++ b/Marlin/src/gcode/sd/M1001.cpp @@ -0,0 +1,109 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#include "../../inc/MarlinConfig.h" + +#if ENABLED(SDSUPPORT) + +#include "../gcode.h" +#include "../../module/printcounter.h" + +#if EITHER(LCD_SET_PROGRESS_MANUALLY, SD_REPRINT_LAST_SELECTED_FILE) + #include "../../lcd/ultralcd.h" +#endif + +#if ENABLED(POWER_LOSS_RECOVERY) + #include "../../feature/powerloss.h" +#endif + +#if HAS_LEDS_OFF_FLAG + #include "../../feature/leds/printer_event_leds.h" +#endif + +#if ENABLED(EXTENSIBLE_UI) + #include "../../lcd/extui/ui_api.h" +#endif + +#if ENABLED(HOST_ACTION_COMMANDS) + #include "../../feature/host_actions.h" +#endif + +#if ENABLED(SD_FINISHED_STEPPERRELEASE) && defined(SD_FINISHED_RELEASECOMMAND) + #include "../../module/planner.h" +#endif + +#ifndef PE_LEDS_COMPLETED_TIME + #define PE_LEDS_COMPLETED_TIME (30*60) +#endif + +/** + * M1001: Execute actions for SD print completion + */ +void GcodeSuite::M1001() { + + // Report total print time + const bool long_print = print_job_timer.duration() > 60; + if (long_print) gcode.process_subcommands_now_P(PSTR("M31")); + + // Stop the print job timer + gcode.process_subcommands_now_P(PSTR("M77")); + + // Set the progress bar "done" state + #if ENABLED(LCD_SET_PROGRESS_MANUALLY) + ui.set_progress_done(); + #endif + + // Purge the recovery file + #if ENABLED(POWER_LOSS_RECOVERY) + recovery.purge(); + #endif + + // Announce SD file completion + SERIAL_ECHOLNPGM(STR_FILE_PRINTED); + + // Update the status LED color + #if HAS_LEDS_OFF_FLAG + if (long_print) { + printerEventLEDs.onPrintCompleted(); + #if ENABLED(EXTENSIBLE_UI) + ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_PRINT_DONE)); + #endif + #if ENABLED(HOST_PROMPT_SUPPORT) + host_prompt_do(PROMPT_USER_CONTINUE, GET_TEXT(MSG_PRINT_DONE), CONTINUE_STR); + #endif + wait_for_user_response(1000UL * TERN(HAS_LCD_MENU, PE_LEDS_COMPLETED_TIME, 30)); + printerEventLEDs.onResumeAfterWait(); + } + #endif + + // Wait for the queue to empty (and "clean"), inject SD_FINISHED_RELEASECOMMAND + #if ENABLED(SD_FINISHED_STEPPERRELEASE) && defined(SD_FINISHED_RELEASECOMMAND) + planner.finish_and_disable(); + #endif + + // Re-select the last printed file in the UI + #if ENABLED(SD_REPRINT_LAST_SELECTED_FILE) + ui.reselect_last_file(); + #endif +} + +#endif // SDSUPPORT diff --git a/Marlin/src/gcode/temp/M303.cpp b/Marlin/src/gcode/temp/M303.cpp index 63dcc3f4..358a1436 100644 --- a/Marlin/src/gcode/temp/M303.cpp +++ b/Marlin/src/gcode/temp/M303.cpp @@ -34,12 +34,31 @@ /** * M303: PID relay autotune * - * S sets the target temperature. (default 150C / 70C) - * E (-1 for the bed) (default 0) - * C Minimum 3. Default 5. - * U with a non-zero value will apply the result to current settings + * S Set the target temperature. (Default: 150C / 70C) + * E Extruder number to tune, or -1 for the bed. (Default: E0) + * C Number of times to repeat the procedure. (Minimum: 3, Default: 5) + * U Flag to apply the result to the current PID values + * + * With PID_DEBUG: + * D Toggle PID debugging and EXIT without further action. */ + +#if ENABLED(PID_DEBUG) + bool pid_debug_flag = 0; +#endif + void GcodeSuite::M303() { + + #if ENABLED(PID_DEBUG) + if (parser.seen('D')) { + pid_debug_flag = !pid_debug_flag; + SERIAL_ECHO_START(); + SERIAL_ECHOPGM("PID Debug "); + serialprintln_onoff(pid_debug_flag); + return; + } + #endif + #if ENABLED(PIDTEMPBED) #define SI H_BED #else @@ -54,7 +73,7 @@ void GcodeSuite::M303() { if (!WITHIN(e, SI, EI)) { SERIAL_ECHOLNPGM(STR_PID_BAD_EXTRUDER_NUM); #if ENABLED(EXTENSIBLE_UI) - ExtUI::OnPidTuning(ExtUI::result_t::PID_BAD_EXTRUDER_NUM); + ExtUI::onPidTuning(ExtUI::result_t::PID_BAD_EXTRUDER_NUM); #endif return; } diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h index 09de5d89..a52ae1af 100644 --- a/Marlin/src/inc/Conditionals_adv.h +++ b/Marlin/src/inc/Conditionals_adv.h @@ -93,7 +93,7 @@ #if EITHER(MIN_SOFTWARE_ENDSTOPS, MAX_SOFTWARE_ENDSTOPS) #define HAS_SOFTWARE_ENDSTOPS 1 #endif -#if ANY(EXTENSIBLE_UI, NEWPANEL, EMERGENCY_PARSER) +#if ANY(EXTENSIBLE_UI, NEWPANEL, EMERGENCY_PARSER, HAS_ADC_BUTTONS) #define HAS_RESUME_CONTINUE 1 #endif diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index ebc77b93..9ea298f0 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -35,16 +35,19 @@ #define HAS_LINEAR_E_JERK 1 #endif -// If no real EEPROM, Flash emulation, or SRAM emulation is available fall back to SD emulation +// Determine which type of 'EEPROM' is in use #if ENABLED(EEPROM_SETTINGS) - #if NONE(FLASH_EEPROM_EMULATION, SRAM_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) && EITHER(I2C_EEPROM, SPI_EEPROM) - #define USE_REAL_EEPROM 1 + // EEPROM type may be defined by compile flags, configs, HALs, or pins + // Set additional flags to let HALs choose in their Conditionals_post.h + #if NONE(FLASH_EEPROM_EMULATION, SRAM_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION) && ANY(I2C_EEPROM, SPI_EEPROM, QSPI_EEPROM) + #define USE_WIRED_EEPROM 1 #else - #define USE_EMULATED_EEPROM 1 + #define USE_FALLBACK_EEPROM 1 #endif #else #undef I2C_EEPROM #undef SPI_EEPROM + #undef QSPI_EEPROM #undef SDCARD_EEPROM_EMULATION #undef SRAM_EEPROM_EMULATION #undef FLASH_EEPROM_EMULATION @@ -136,6 +139,19 @@ #define CORESIGN(n) (ANY(COREYX, COREZX, COREZY) ? (-(n)) : (n)) #endif +// Calibration codes only for non-core axes +#if EITHER(BACKLASH_GCODE, CALIBRATION_GCODE) + #if IS_CORE + #define X_AXIS_INDEX 0 + #define Y_AXIS_INDEX 1 + #define Z_AXIS_INDEX 2 + #define CAN_CALIBRATE(A,B) (A##_AXIS_INDEX == B##_INDEX) + #else + #define CAN_CALIBRATE(...) 1 + #endif +#endif +#define AXIS_CAN_CALIBRATE(A) CAN_CALIBRATE(A,NORMAL_AXIS) + /** * No adjustable bed on non-cartesians */ diff --git a/Marlin/src/inc/MarlinConfig.h b/Marlin/src/inc/MarlinConfig.h index d3250670..c1655015 100644 --- a/Marlin/src/inc/MarlinConfig.h +++ b/Marlin/src/inc/MarlinConfig.h @@ -35,11 +35,12 @@ #include "Conditionals_post.h" #include HAL_PATH(../HAL, inc/Conditionals_post.h) +#include "../core/types.h" // Ahead of sanity-checks + #include "SanityCheck.h" #include HAL_PATH(../HAL, inc/SanityCheck.h) // Include all core headers -#include "../core/types.h" #include "../core/language.h" #include "../core/utility.h" #include "../core/serial.h" diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 6022c166..a5960c16 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -25,7 +25,7 @@ * Release version. Leave the Marlin version or apply a custom scheme. */ #ifndef SHORT_BUILD_VERSION - #define SHORT_BUILD_VERSION "2.0.5.2" + #define SHORT_BUILD_VERSION "2.0.5.3" #endif /** @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-03-24" + #define STRING_DISTRIBUTION_DATE "2020-03-31" #endif /** diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.cpp index 7f666be4..6621ea3c 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.cpp @@ -38,6 +38,11 @@ namespace FTDI { SET_OUTPUT(CLCD_SPI_CS); WRITE(CLCD_SPI_CS, 1); + #ifdef CLCD_SPI_EXTRA_CS + SET_OUTPUT(CLCD_SPI_EXTRA_CS); + WRITE(CLCD_SPI_EXTRA_CS, 1); + #endif + #ifdef SPI_FLASH_SS SET_OUTPUT(SPI_FLASH_SS); WRITE(SPI_FLASH_SS, 1); @@ -111,12 +116,18 @@ namespace FTDI { ::SPI.beginTransaction(spi_settings); #endif WRITE(CLCD_SPI_CS, 0); + #ifdef CLCD_SPI_EXTRA_CS + WRITE(CLCD_SPI_EXTRA_CS, 0); + #endif delayMicroseconds(1); } // CLCD SPI - Chip Deselect void SPI::spi_ftdi_deselect() { WRITE(CLCD_SPI_CS, 1); + #ifdef CLCD_SPI_EXTRA_CS + WRITE(CLCD_SPI_EXTRA_CS, 1); + #endif #ifndef CLCD_USE_SOFT_SPI ::SPI.endTransaction(); #endif diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h index ef2b23a3..3023a1c6 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h @@ -176,11 +176,12 @@ #undef MAKE_ARDUINO_PINS } // namespace fast_io - #define SET_INPUT(pin) fast_io::pin::set_input() - #define SET_INPUT_PULLUP(pin) fast_io::pin::set_input(); fast_io::pin::set_high() - #define SET_OUTPUT(pin) fast_io::pin::set_output() - #define READ(pin) fast_io::pin::read() - #define WRITE(pin, value) fast_io::pin::write(value) + #define SET_INPUT(pin) fast_io::pin::set_input() + #define SET_INPUT_PULLUP(pin) do{ fast_io::pin::set_input(); fast_io::pin::set_high(); }while(0) + #define SET_INPUT_PULLDOWN SET_INPUT + #define SET_OUTPUT(pin) fast_io::pin::set_output() + #define READ(pin) fast_io::pin::read() + #define WRITE(pin, value) fast_io::pin::write(value) #ifndef pgm_read_word_far #define pgm_read_word_far pgm_read_word @@ -195,11 +196,11 @@ #endif #define SERIAL_ECHO_START() - #define SERIAL_ECHOLNPGM(str) Serial.println(F(str)) - #define SERIAL_ECHOPGM(str) Serial.print(F(str)) - #define SERIAL_ECHO_MSG(str) Serial.println(str) - #define SERIAL_ECHOLNPAIR(str, val) {Serial.print(F(str)); Serial.println(val);} - #define SERIAL_ECHOPAIR(str, val) {Serial.print(F(str)); Serial.print(val);} + #define SERIAL_ECHOLNPGM(str) Serial.println(F(str)) + #define SERIAL_ECHOPGM(str) Serial.print(F(str)) + #define SERIAL_ECHO_MSG(str) Serial.println(str) + #define SERIAL_ECHOLNPAIR(str, val) do{ Serial.print(F(str)); Serial.println(val); }while(0) + #define SERIAL_ECHOPAIR(str, val) do{ Serial.print(F(str)); Serial.print(val); }while(0) #define safe_delay delay diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.cpp index f0f693bf..b338758e 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.cpp @@ -191,7 +191,7 @@ namespace FTDI { #if ENABLED(TOUCH_UI_DEBUG) SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR("Touch end: ", tag); + SERIAL_ECHOLNPAIR("Touch end: ", pressed_tag); #endif const uint8_t saved_pressed_tag = pressed_tag; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/language/language_en.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/language/language_en.h index e59e1d94..ebd60aed 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/language/language_en.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/language/language_en.h @@ -70,13 +70,15 @@ namespace Language_en { PROGMEM Language_Str MSG_PRINT_FINISHED = u8"Print finished"; PROGMEM Language_Str MSG_PRINT_ERROR = u8"Print error"; PROGMEM Language_Str MSG_ABOUT_TOUCH_PANEL_1 = u8"Color Touch Panel"; - PROGMEM Language_Str MSG_ABOUT_TOUCH_PANEL_2 = u8"Portions " COPYRIGHT_SIGN " 2019 Aleph Objects, Inc.\n" - "Portions " COPYRIGHT_SIGN " 2019 Cocoa Press"; - PROGMEM Language_Str MSG_FIRMWARE_FOR_TOOLHEAD = u8"Firmware for toolhead:\n%s\n\n"; + PROGMEM Language_Str MSG_ABOUT_TOUCH_PANEL_2 = WEBSITE_URL; + PROGMEM Language_Str MSG_LICENSE = u8"This program is free software: you can redistribute it and/or modify it under the terms of " + "the GNU General Public License as published by the Free Software Foundation, either version 3 " + "of the License, or (at your option) any later version.\n\nTo view a copy of the GNU General " + "Public License, go to the following location: http://www.gnu.org/licenses."; PROGMEM Language_Str MSG_RUNOUT_1 = u8"Runout 1"; PROGMEM Language_Str MSG_RUNOUT_2 = u8"Runout 2"; PROGMEM Language_Str MSG_DISPLAY_MENU = u8"Display"; - PROGMEM Language_Str MSG_INTERFACE_SETTINGS = u8"Interface Settings"; + PROGMEM Language_Str MSG_INTERFACE = u8"Interface"; PROGMEM Language_Str MSG_MEASURE_AUTOMATICALLY = u8"Measure automatically"; PROGMEM Language_Str MSG_H_OFFSET = u8"H Offset"; PROGMEM Language_Str MSG_V_OFFSET = u8"V Offset"; @@ -129,7 +131,7 @@ namespace Language_en { PROGMEM Language_Str MSG_SOUND_VOLUME = u8"Sound volume"; PROGMEM Language_Str MSG_SCREEN_LOCK = u8"Screen lock"; PROGMEM Language_Str MSG_BOOT_SCREEN = u8"Boot screen"; - PROGMEM Language_Str MSG_INTERFACE_SOUNDS = u8"Interface Sounds"; + PROGMEM Language_Str MSG_SOUNDS = u8"Sounds"; PROGMEM Language_Str MSG_CLICK_SOUNDS = u8"Click sounds"; PROGMEM Language_Str MSG_EEPROM_RESTORED = u8"Settings restored from backup"; PROGMEM Language_Str MSG_EEPROM_RESET = u8"Settings restored to default"; @@ -144,12 +146,12 @@ namespace Language_en { PROGMEM Language_Str MSG_TOUCH_CALIBRATION_START = u8"Release to begin screen calibration"; PROGMEM Language_Str MSG_TOUCH_CALIBRATION_PROMPT = u8"Touch the dots to calibrate"; + PROGMEM Language_Str MSG_AUTOLEVEL_X_AXIS = u8"Level X Axis"; #ifdef TOUCH_UI_LULZBOT_BIO PROGMEM Language_Str MSG_MOVE_TO_HOME = u8"Move to Home"; PROGMEM Language_Str MSG_RAISE_PLUNGER = u8"Raise Plunger"; PROGMEM Language_Str MSG_RELEASE_XY_AXIS = u8"Release X and Y Axis"; - PROGMEM Language_Str MSG_AUTOLEVEL_X_AXIS = u8"Auto-level X Axis"; PROGMEM Language_Str MSG_BED_TEMPERATURE = u8"Bed Temperature"; PROGMEM Language_Str MSG_HOME_XYZ_WARNING = u8"About to move to home position. Ensure the top and the bed of the printer are clear.\n\nContinue?"; PROGMEM Language_Str MSG_HOME_E_WARNING = u8"About to re-home plunger and auto-level. Remove syringe prior to proceeding.\n\nContinue?"; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/marlin_events.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/marlin_events.cpp index 96845d40..bed32cc6 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/marlin_events.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/marlin_events.cpp @@ -131,8 +131,14 @@ namespace ExtUI { } #endif + #if ENABLED(POWER_LOSS_RECOVERY) + void onPowerLossResume() { + // Called on resume from power-loss + } + #endif + #if HAS_PID_HEATING - void OnPidTuning(const result_t rst) { + void onPidTuning(const result_t rst) { // Called for temperature PID tuning result SERIAL_ECHOLNPAIR("OnPidTuning:", rst); switch (rst) { diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h index 548c6c74..b5b0f22e 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/pin_mappings.h @@ -129,12 +129,13 @@ * 9 GND GND GND --> GND * 10 5V 5V 5V --> KILL [3] * - * [1] This configuration is not compatible with the - * EinsyRetro 1.1a because there is a level shifter - * on MISO enabled by SD/USB chip select. + * [1] This configuration allows daisy-chaining of the + * display and SD/USB on EXP2, except for [2] * - * [2] This configuration allows daisy-chaining of the - * display and SD/USB on EXP2. + * [2] The Ultimachine Einsy boards have a level shifter + * on MISO enabled by SD_CSEL chip select, hence it + * is not possible to run both the display and the + * SD/USB on EXP2. * * [3] Archim Rambo provides 5V on this pin. On any other * board, divert this wire from the ribbon cable and @@ -148,4 +149,8 @@ #define CLCD_SPI_CS BTN_EN1 #define CLCD_MOD_RESET BTN_EN2 + + #if MB(EINSY_RAMBO, EINSY_RETRO) && DISABLED(SDSUPPORT) + #define CLCD_SPI_EXTRA_CS SDSS + #endif #endif diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/about_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/about_screen.cpp index afd4402f..70acc090 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/about_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/about_screen.cpp @@ -27,7 +27,7 @@ #include "screens.h" #define GRID_COLS 4 -#define GRID_ROWS 9 +#define GRID_ROWS 7 using namespace FTDI; using namespace Theme; @@ -45,50 +45,62 @@ void AboutScreen::onRedraw(draw_mode_t) { .cmd(COLOR_RGB(bg_text_enabled)) .tag(0); - draw_text_box(cmd, BTN_POS(1,2), BTN_SIZE(4,1), - #ifdef CUSTOM_MACHINE_NAME - F(CUSTOM_MACHINE_NAME) - #else - GET_TEXT_F(MSG_ABOUT_TOUCH_PANEL_1) - #endif - , OPT_CENTER, font_xlarge - ); + #define HEADING_POS BTN_POS(1,2), BTN_SIZE(4,1) + #define FW_VERS_POS BTN_POS(1,3), BTN_SIZE(4,1) + #define FW_INFO_POS BTN_POS(1,4), BTN_SIZE(4,1) + #define LICENSE_POS BTN_POS(1,5), BTN_SIZE(4,2) + #define STATS_POS BTN_POS(1,7), BTN_SIZE(2,1) + #define BACK_POS BTN_POS(3,7), BTN_SIZE(2,1) - #ifdef TOOLHEAD_NAME - char about_str[ - strlen_P(GET_TEXT(FIRMWARE_FOR_TOOLHEAD)) + - strlen_P(TOOLHEAD_NAME) + - strlen_P(GET_TEXT(MSG_ABOUT_TOUCH_PANEL_2)) + 1 - ]; + #define _INSET_POS(x,y,w,h) x + w/10, y, w - w/5, h + #define INSET_POS(pos) _INSET_POS(pos) - sprintf_P(about_str, GET_TEXT(MSG_FIRMWARE_FOR_TOOLHEAD), TOOLHEAD_NAME); - strcat_P (about_str, GET_TEXT(MSG_ABOUT_TOUCH_PANEL_2)); + char about_str[ + strlen_P(GET_TEXT(MSG_ABOUT_TOUCH_PANEL_2)) + + strlen_P(TOOLHEAD_NAME) + 1 + ]; + #ifdef TOOLHEAD_NAME + // If MSG_ABOUT_TOUCH_PANEL_2 has %s, substitute in the toolhead name. + // But this is optional, so squelch the compiler warning here. + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wformat-extra-args" + sprintf_P(about_str, GET_TEXT(MSG_ABOUT_TOUCH_PANEL_2), TOOLHEAD_NAME); + #pragma GCC diagnostic pop + #else + strcpy_P(about_str, GET_TEXT(MSG_ABOUT_TOUCH_PANEL_2)); #endif - cmd.tag(2); - draw_text_box(cmd, BTN_POS(1,3), BTN_SIZE(4,3), - #ifdef TOOLHEAD_NAME - about_str + draw_text_box(cmd, HEADING_POS, + #ifdef CUSTOM_MACHINE_NAME + F(CUSTOM_MACHINE_NAME) #else - GET_TEXT_F(MSG_ABOUT_TOUCH_PANEL_2) + GET_TEXT_F(MSG_ABOUT_TOUCH_PANEL_1) #endif - , OPT_CENTER, font_medium + , OPT_CENTER, font_xlarge ); - - cmd.tag(0); - draw_text_box(cmd, BTN_POS(1,6), BTN_SIZE(4,2), progmem_str(getFirmwareName_str()), OPT_CENTER, font_medium); - - cmd.font(font_medium).colors(action_btn).tag(1).button(BTN_POS(2,8), BTN_SIZE(2,1), GET_TEXT_F(MSG_BUTTON_OKAY)); + draw_text_box(cmd, FW_VERS_POS, progmem_str(getFirmwareName_str()), OPT_CENTER, font_medium); + draw_text_box(cmd, FW_INFO_POS, about_str, OPT_CENTER, font_medium); + draw_text_box(cmd, INSET_POS(LICENSE_POS), GET_TEXT_F(MSG_LICENSE), OPT_CENTER, font_tiny); + + cmd.font(font_medium) + .colors(normal_btn) + .tag(2).button(STATS_POS, GET_TEXT_F(MSG_INFO_STATS_MENU)) + .colors(action_btn) + .tag(1).button(BACK_POS, GET_TEXT_F(MSG_BACK)); } bool AboutScreen::onTouchEnd(uint8_t tag) { switch (tag) { - case 1: GOTO_PREVIOUS(); return true; -#if ENABLED(TOUCH_UI_DEVELOPER_MENU) - case 2: GOTO_SCREEN(DeveloperMenu); return true; -#endif - default: return false; + case 1: GOTO_PREVIOUS(); break; + #if ENABLED(PRINTCOUNTER) + case 2: GOTO_SCREEN(StatisticsScreen); break; + #endif + #if ENABLED(TOUCH_UI_DEVELOPER_MENU) + case 3: GOTO_SCREEN(DeveloperMenu); break; + #endif + default: return false; } + return true; } #endif // TOUCH_UI_FTDI_EVE diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp index 60293828..57137c5d 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp @@ -37,127 +37,116 @@ void AdvancedSettingsMenu::onRedraw(draw_mode_t what) { .cmd(CLEAR(true,true,true)); } + #ifdef TOUCH_UI_PORTRAIT + #if HAS_CASE_LIGHT || ENABLED(SENSORLESS_HOMING) + #define GRID_ROWS 9 + #else + #define GRID_ROWS 8 + #endif + #define GRID_COLS 2 + #define RESTORE_DEFAULTS_POS BTN_POS(1,1), BTN_SIZE(2,1) + #define DISPLAY_POS BTN_POS(1,2), BTN_SIZE(1,1) + #define INTERFACE_POS BTN_POS(2,2), BTN_SIZE(1,1) + #define ZPROBE_ZOFFSET_POS BTN_POS(1,3), BTN_SIZE(1,1) + #define STEPS_PER_MM_POS BTN_POS(2,3), BTN_SIZE(1,1) + #define FILAMENT_POS BTN_POS(1,4), BTN_SIZE(1,1) + #define VELOCITY_POS BTN_POS(2,4), BTN_SIZE(1,1) + #define TMC_CURRENT_POS BTN_POS(1,5), BTN_SIZE(1,1) + #define ACCELERATION_POS BTN_POS(2,5), BTN_SIZE(1,1) + #define ENDSTOPS_POS BTN_POS(1,6), BTN_SIZE(1,1) + #define JERK_POS BTN_POS(2,6), BTN_SIZE(1,1) + #define OFFSETS_POS BTN_POS(1,7), BTN_SIZE(1,1) + #define BACKLASH_POS BTN_POS(2,7), BTN_SIZE(1,1) + #define CASE_LIGHT_POS BTN_POS(1,8), BTN_SIZE(1,1) + #define TMC_HOMING_THRS_POS BTN_POS(2,8), BTN_SIZE(1,1) + #if HAS_CASE_LIGHT || ENABLED(SENSORLESS_HOMING) + #define BACK_POS BTN_POS(1,9), BTN_SIZE(2,1) + #else + #define BACK_POS BTN_POS(1,8), BTN_SIZE(2,1) + #endif + #else + #define GRID_ROWS 6 + #define GRID_COLS 3 + #define ZPROBE_ZOFFSET_POS BTN_POS(1,1), BTN_SIZE(1,1) + #define CASE_LIGHT_POS BTN_POS(1,4), BTN_SIZE(1,1) + #define STEPS_PER_MM_POS BTN_POS(2,1), BTN_SIZE(1,1) + #define TMC_CURRENT_POS BTN_POS(3,1), BTN_SIZE(1,1) + #define TMC_HOMING_THRS_POS BTN_POS(3,2), BTN_SIZE(1,1) + #define BACKLASH_POS BTN_POS(3,3), BTN_SIZE(1,1) + #define FILAMENT_POS BTN_POS(1,3), BTN_SIZE(1,1) + #define ENDSTOPS_POS BTN_POS(3,4), BTN_SIZE(1,1) + #define DISPLAY_POS BTN_POS(3,5), BTN_SIZE(1,1) + #define INTERFACE_POS BTN_POS(1,5), BTN_SIZE(2,1) + #define RESTORE_DEFAULTS_POS BTN_POS(1,6), BTN_SIZE(2,1) + #define VELOCITY_POS BTN_POS(2,2), BTN_SIZE(1,1) + #define ACCELERATION_POS BTN_POS(2,3), BTN_SIZE(1,1) + #define JERK_POS BTN_POS(2,4), BTN_SIZE(1,1) + #define OFFSETS_POS BTN_POS(1,2), BTN_SIZE(1,1) + #define BACK_POS BTN_POS(3,6), BTN_SIZE(1,1) + #endif + if (what & FOREGROUND) { CommandProcessor cmd; cmd.colors(normal_btn) .font(Theme::font_medium) - #ifdef TOUCH_UI_PORTRAIT - #define GRID_ROWS 10 - #define GRID_COLS 2 .enabled( #if HAS_BED_PROBE 1 #endif ) - .tag(2) .button( BTN_POS(1,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_ZPROBE_ZOFFSET)) + .tag(2) .button( ZPROBE_ZOFFSET_POS, GET_TEXT_F(MSG_ZPROBE_ZOFFSET)) .enabled( #if HAS_CASE_LIGHT 1 #endif ) - .tag(16).button( BTN_POS(1,6), BTN_SIZE(1,1), GET_TEXT_F(MSG_CASE_LIGHT)) - .tag(3) .button( BTN_POS(2,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_STEPS_PER_MM)) + .tag(16).button( CASE_LIGHT_POS, GET_TEXT_F(MSG_CASE_LIGHT)) + .tag(3) .button( STEPS_PER_MM_POS, GET_TEXT_F(MSG_STEPS_PER_MM)) .enabled( #if HAS_TRINAMIC_CONFIG 1 #endif ) - .tag(13).button( BTN_POS(1,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_TMC_CURRENT)) + .tag(13).button( TMC_CURRENT_POS, GET_TEXT_F(MSG_TMC_CURRENT)) .enabled( - #if HAS_TRINAMIC_CONFIG + #if ENABLED(SENSORLESS_HOMING) 1 #endif ) - .tag(14).button( BTN_POS(1,7), BTN_SIZE(2,1), GET_TEXT_F(MSG_TMC_HOMING_THRS)) + .tag(14).button( TMC_HOMING_THRS_POS, GET_TEXT_F(MSG_TMC_HOMING_THRS)) .enabled( #if HOTENDS > 1 1 #endif ) - .tag(4) .button( BTN_POS(1,2), BTN_SIZE(1,1), GET_TEXT_F(MSG_OFFSETS_MENU)) + .tag(4) .button( OFFSETS_POS, GET_TEXT_F(MSG_OFFSETS_MENU)) .enabled( #if EITHER(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR) 1 #endif ) - .tag(11).button( BTN_POS(1,3), BTN_SIZE(1,1), GET_TEXT_F(MSG_FILAMENT)) - .tag(12).button( BTN_POS(1,5), BTN_SIZE(1,1), GET_TEXT_F(MSG_LCD_ENDSTOPS)) - .tag(15).button( BTN_POS(2,6), BTN_SIZE(1,1), GET_TEXT_F(MSG_DISPLAY_MENU)) - .tag(9) .button( BTN_POS(1,8), BTN_SIZE(2,1), GET_TEXT_F(MSG_INTERFACE_SETTINGS)) - .tag(10).button( BTN_POS(1,9), BTN_SIZE(2,1), GET_TEXT_F(MSG_RESTORE_DEFAULTS)) - .tag(5) .button( BTN_POS(2,2), BTN_SIZE(1,1), GET_TEXT_F(MSG_VELOCITY)) - .tag(6) .button( BTN_POS(2,3), BTN_SIZE(1,1), GET_TEXT_F(MSG_ACCELERATION)) - #if DISABLED(CLASSIC_JERK) - .tag(7) .button( BTN_POS(2,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_JUNCTION_DEVIATION)) - #else - .tag(7) .button( BTN_POS(2,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_JERK)) - #endif - .enabled( - #if ENABLED(BACKLASH_GCODE) - 1 - #endif - ) - .tag(8).button( BTN_POS(2,5), BTN_SIZE(1,1), GET_TEXT_F(MSG_BACKLASH)) - .colors(action_btn) - .tag(1) .button( BTN_POS(1,10), BTN_SIZE(2,1), GET_TEXT_F(MSG_BACK)); - #undef GRID_COLS - #undef GRID_ROWS - #else - #define GRID_ROWS 6 - #define GRID_COLS 3 - .enabled( - #if HAS_BED_PROBE - 1 - #endif - ) - .tag(2) .button( BTN_POS(1,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_ZPROBE_ZOFFSET)) - .enabled( - #if HAS_CASE_LIGHT - 1 - #endif - ) - .tag(16).button( BTN_POS(1,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_CASE_LIGHT)) - .enabled(1) - .tag(3) .button( BTN_POS(2,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_STEPS_PER_MM)) - .enabled( - #if HAS_TRINAMIC_CONFIG - 1 - #endif - ) - .tag(13).button( BTN_POS(3,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_TMC_CURRENT)) - .enabled( - #if HAS_TRINAMIC_CONFIG - 1 + .tag(11).button( FILAMENT_POS, GET_TEXT_F(MSG_FILAMENT)) + .tag(12).button( ENDSTOPS_POS, GET_TEXT_F(MSG_LCD_ENDSTOPS)) + .tag(15).button( DISPLAY_POS, GET_TEXT_F(MSG_DISPLAY_MENU)) + .tag(9) .button( INTERFACE_POS, GET_TEXT_F(MSG_INTERFACE)) + .tag(10).button( RESTORE_DEFAULTS_POS, GET_TEXT_F(MSG_RESTORE_DEFAULTS)) + .tag(5) .button( VELOCITY_POS, GET_TEXT_F(MSG_VELOCITY)) + .tag(6) .button( ACCELERATION_POS, GET_TEXT_F(MSG_ACCELERATION)) + .tag(7) .button( JERK_POS, GET_TEXT_F( + #if DISABLED(CLASSIC_JERK) + MSG_JUNCTION_DEVIATION + #else + JERK_POS #endif - ) - .tag(14).button( BTN_POS(3,2), BTN_SIZE(1,1), GET_TEXT_F(MSG_TMC_HOMING_THRS)) + )) .enabled( #if ENABLED(BACKLASH_GCODE) 1 #endif ) - .tag(8).button( BTN_POS(3,3), BTN_SIZE(1,1), GET_TEXT_F(MSG_BACKLASH)) - .enabled( - #if HOTENDS > 1 - 1 - #endif - ) - .tag(4) .button( BTN_POS(1,2), BTN_SIZE(1,1), GET_TEXT_F(MSG_OFFSETS_MENU)) - .tag(12).button( BTN_POS(3,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_LCD_ENDSTOPS)) - .tag(5) .button( BTN_POS(2,2), BTN_SIZE(1,1), GET_TEXT_F(MSG_VELOCITY)) - .tag(6) .button( BTN_POS(2,3), BTN_SIZE(1,1), GET_TEXT_F(MSG_ACCELERATION)) - #if DISABLED(CLASSIC_JERK) - .tag(7) .button( BTN_POS(2,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_JUNCTION_DEVIATION)) - #else - .tag(7) .button( BTN_POS(2,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_JERK)) - #endif - .tag(11).button( BTN_POS(1,3), BTN_SIZE(1,1), GET_TEXT_F(MSG_FILAMENT)) - .tag(15).button( BTN_POS(3,5), BTN_SIZE(1,1), GET_TEXT_F(MSG_DISPLAY_MENU)) - .tag(9) .button( BTN_POS(1,5), BTN_SIZE(2,1), GET_TEXT_F(MSG_INTERFACE_SETTINGS)) - .tag(10).button( BTN_POS(1,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_RESTORE_DEFAULTS)) + .tag(8).button( BACKLASH_POS, GET_TEXT_F(MSG_BACKLASH)) .colors(action_btn) - .tag(1) .button( BTN_POS(3,6), BTN_SIZE(1,1), GET_TEXT_F(MSG_BACK)); - #endif + .tag(1).button( BACK_POS, GET_TEXT_F(MSG_BACK)); } } @@ -191,6 +180,8 @@ bool AdvancedSettingsMenu::onTouchEnd(uint8_t tag) { case 12: GOTO_SCREEN(EndstopStatesScreen); break; #if HAS_TRINAMIC_CONFIG case 13: GOTO_SCREEN(StepperCurrentScreen); break; + #endif + #if ENABLED(SENSORLESS_HOMING) case 14: GOTO_SCREEN(StepperBumpSensitivityScreen); break; #endif case 15: GOTO_SCREEN(DisplayTuningScreen); break; @@ -201,5 +192,4 @@ bool AdvancedSettingsMenu::onTouchEnd(uint8_t tag) { } return true; } - #endif // TOUCH_UI_FTDI_EVE diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_numeric_adjustment_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_numeric_adjustment_screen.cpp index 97e399a4..3e3f1d48 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_numeric_adjustment_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_numeric_adjustment_screen.cpp @@ -345,10 +345,14 @@ void BaseNumericAdjustmentScreen::widgets_t::home_buttons(uint8_t tag) { } cmd.font(LAYOUT_FONT); - _button(cmd, tag+0, BTN_POS(5,_line), BTN_SIZE(2,1), GET_TEXT_F(MSG_AXIS_X)); - _button(cmd, tag+1, BTN_POS(7,_line), BTN_SIZE(2,1), GET_TEXT_F(MSG_AXIS_Y)); - _button(cmd, tag+2, BTN_POS(9,_line), BTN_SIZE(2,1), GET_TEXT_F(MSG_AXIS_Z)); - _button(cmd, tag+3, BTN_POS(11,_line), BTN_SIZE(3,1), GET_TEXT_F(MSG_AXIS_ALL)); + _button(cmd, tag+0, BTN_POS(5,_line), BTN_SIZE(2,1), GET_TEXT_F(MSG_AXIS_X)); + _button(cmd, tag+1, BTN_POS(7,_line), BTN_SIZE(2,1), GET_TEXT_F(MSG_AXIS_Y)); + #if DISABLED(Z_SAFE_HOMING) + _button(cmd, tag+2, BTN_POS(9,_line), BTN_SIZE(2,1), GET_TEXT_F(MSG_AXIS_Z)); + _button(cmd, tag+3, BTN_POS(11,_line), BTN_SIZE(3,1), GET_TEXT_F(MSG_AXIS_ALL)); + #else + _button(cmd, tag+3, BTN_POS(9,_line), BTN_SIZE(3,1), GET_TEXT_F(MSG_AXIS_ALL)); + #endif _line++; } diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_screen.cpp index 77cadabc..7e88b788 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/base_screen.cpp @@ -46,7 +46,7 @@ bool BaseScreen::buttonStyleCallback(CommandProcessor &cmd, uint8_t tag, uint8_t return false; } - #ifdef LCD_TIMEOUT_TO_STATUS + #if LCD_TIMEOUT_TO_STATUS if (EventLoop::get_pressed_tag() != 0) { reset_menu_timeout(); } @@ -66,7 +66,7 @@ bool BaseScreen::buttonStyleCallback(CommandProcessor &cmd, uint8_t tag, uint8_t } void BaseScreen::onIdle() { - #ifdef LCD_TIMEOUT_TO_STATUS + #if LCD_TIMEOUT_TO_STATUS if ((millis() - last_interaction) > LCD_TIMEOUT_TO_STATUS) { reset_menu_timeout(); #if ENABLED(TOUCH_UI_DEBUG) @@ -78,12 +78,12 @@ void BaseScreen::onIdle() { } void BaseScreen::reset_menu_timeout() { - #ifdef LCD_TIMEOUT_TO_STATUS + #if LCD_TIMEOUT_TO_STATUS last_interaction = millis(); #endif } -#ifdef LCD_TIMEOUT_TO_STATUS +#if LCD_TIMEOUT_TO_STATUS uint32_t BaseScreen::last_interaction; #endif diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_advanced_settings.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_advanced_settings.cpp index 6c9f74f9..ed8bcee5 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_advanced_settings.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_advanced_settings.cpp @@ -85,7 +85,7 @@ void AdvancedSettingsMenu::onRedraw(draw_mode_t what) { #endif ) .tag(12) .button( BTN_POS(1,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_LINEAR_ADVANCE)) - .tag(13) .button( BTN_POS(1,7), BTN_SIZE(2,1), GET_TEXT_F(MSG_INTERFACE_SETTINGS)) + .tag(13) .button( BTN_POS(1,7), BTN_SIZE(2,1), GET_TEXT_F(MSG_INTERFACE)) .tag(14) .button( BTN_POS(1,8), BTN_SIZE(2,1), GET_TEXT_F(MSG_RESTORE_DEFAULTS)) .colors(action_btn) .tag(1). button( BTN_POS(1,9), BTN_SIZE(2,1), GET_TEXT_F(MSG_BACK)); diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_e.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_e.cpp index a3254bae..79a6112e 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_e.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_e.cpp @@ -36,11 +36,13 @@ void BioConfirmHomeE::onRedraw(draw_mode_t) { bool BioConfirmHomeE::onTouchEnd(uint8_t tag) { switch (tag) { case 1: - SpinnerDialogBox::enqueueAndWait_P(F( - "G28 E\n" - AXIS_LEVELING_COMMANDS "\n" - PARK_AND_RELEASE_COMMANDS - )); + #if defined(AXIS_LEVELING_COMMANDS) && defined(PARK_AND_RELEASE_COMMANDS) + SpinnerDialogBox::enqueueAndWait_P(F( + "G28 E\n" + AXIS_LEVELING_COMMANDS "\n" + PARK_AND_RELEASE_COMMANDS + )); + #endif current_screen.forget(); break; case 2: diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_xyz.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_xyz.cpp index 883a446b..3ae2d680 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_xyz.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_xyz.cpp @@ -36,10 +36,12 @@ void BioConfirmHomeXYZ::onRedraw(draw_mode_t) { bool BioConfirmHomeXYZ::onTouchEnd(uint8_t tag) { switch (tag) { case 1: - SpinnerDialogBox::enqueueAndWait_P(F( - "G28\n" - PARK_AND_RELEASE_COMMANDS - )); + #ifdef PARK_AND_RELEASE_COMMANDS + SpinnerDialogBox::enqueueAndWait_P(F( + "G28\n" + PARK_AND_RELEASE_COMMANDS + )); + #endif current_screen.forget(); break; case 2: diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_main_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_main_menu.cpp index 40ed8479..1f6aa45c 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_main_menu.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_main_menu.cpp @@ -51,7 +51,7 @@ void MainMenu::onRedraw(draw_mode_t what) { .tag(4).button( BTN_POS(1,4), BTN_SIZE(2,1), GET_TEXT_F(MSG_RELEASE_XY_AXIS)) .tag(5).button( BTN_POS(1,5), BTN_SIZE(2,1), GET_TEXT_F(MSG_AUTOLEVEL_X_AXIS)) .tag(6).button( BTN_POS(1,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_BED_TEMPERATURE)) - .tag(7).button( BTN_POS(1,7), BTN_SIZE(2,1), GET_TEXT_F(MSG_INTERFACE_SETTINGS)) + .tag(7).button( BTN_POS(1,7), BTN_SIZE(2,1), GET_TEXT_F(MSG_INTERFACE)) .tag(8).button( BTN_POS(1,8), BTN_SIZE(2,1), GET_TEXT_F(MSG_ADVANCED_SETTINGS)) .tag(9).button( BTN_POS(1,9), BTN_SIZE(2,1), GET_TEXT_F(MSG_INFO_MENU)) .colors(action_btn) @@ -72,7 +72,9 @@ bool MainMenu::onTouchEnd(uint8_t tag) { case 2: GOTO_SCREEN(BioConfirmHomeXYZ); break; case 3: SpinnerDialogBox::enqueueAndWait_P(e_homed ? F("G0 E0 F120") : F("G112")); break; case 4: StatusScreen::unlockMotors(); break; + #ifdef AXIS_LEVELING_COMMANDS case 5: SpinnerDialogBox::enqueueAndWait_P(F(AXIS_LEVELING_COMMANDS)); break; + #endif case 6: GOTO_SCREEN(TemperatureScreen); break; case 7: GOTO_SCREEN(InterfaceSettingsScreen); break; case 8: GOTO_SCREEN(AdvancedSettingsMenu); break; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/boot_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/boot_screen.cpp index 996c12cf..5e022b58 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/boot_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/boot_screen.cpp @@ -80,12 +80,14 @@ void BootScreen::onIdle() { SpinnerDialogBox::hide(); } - if (UIData::animations_enabled()) { - // If there is a startup video in the flash SPI, play - // that, otherwise show a static splash screen. - if (!MediaPlayerScreen::playBootMedia()) - showSplashScreen(); - } + #if DISABLED(TOUCH_UI_NO_BOOTSCREEN) + if (UIData::animations_enabled()) { + // If there is a startup video in the flash SPI, play + // that, otherwise show a static splash screen. + if (!MediaPlayerScreen::playBootMedia()) + showSplashScreen(); + } + #endif StatusScreen::loadBitmaps(); diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/change_filament_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/change_filament_screen.cpp index 2d1e0d66..2b5963fd 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/change_filament_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/change_filament_screen.cpp @@ -111,6 +111,7 @@ void ChangeFilamentScreen::onRedraw(draw_mode_t what) { if (what & BACKGROUND) { cmd.cmd(CLEAR_COLOR_RGB(bg_color)) .cmd(CLEAR(true,true,true)) + .cmd(COLOR_RGB(bg_text_enabled)) .tag(0) #ifdef TOUCH_UI_PORTRAIT .font(font_large) @@ -119,7 +120,7 @@ void ChangeFilamentScreen::onRedraw(draw_mode_t what) { #endif .text(BTN_POS(1,1), BTN_SIZE(2,1), GET_TEXT_F(MSG_EXTRUDER_SELECTION)) #ifdef TOUCH_UI_PORTRAIT - .text(BTN_POS(1,7), BTN_SIZE(1,1), F("")) + .text(BTN_POS(1,7), BTN_SIZE(1,1), GET_TEXT_F(MSG_CURRENT_TEMPERATURE)) #else .text(BTN_POS(3,1), BTN_SIZE(2,1), GET_TEXT_F(MSG_CURRENT_TEMPERATURE)) .font(font_small) diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp index 61875c52..4e165aa4 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_settings_screen.cpp @@ -69,7 +69,7 @@ void InterfaceSettingsScreen::onRedraw(draw_mode_t what) { .cmd(COLOR_RGB(bg_text_enabled)) .tag(0) .font(font_medium) - .text(BTN_POS(1,1), BTN_SIZE(4,1), GET_TEXT_F(MSG_INTERFACE_SETTINGS)) + .text(BTN_POS(1,1), BTN_SIZE(4,1), GET_TEXT_F(MSG_INTERFACE)) #undef EDGE_R #define EDGE_R 30 .font(font_small) @@ -77,7 +77,9 @@ void InterfaceSettingsScreen::onRedraw(draw_mode_t what) { .text(BTN_POS(1,2), BTN_SIZE(2,1), GET_TEXT_F(MSG_LCD_BRIGHTNESS), OPT_RIGHTX | OPT_CENTERY) .text(BTN_POS(1,3), BTN_SIZE(2,1), GET_TEXT_F(MSG_SOUND_VOLUME), OPT_RIGHTX | OPT_CENTERY) .text(BTN_POS(1,4), BTN_SIZE(2,1), GET_TEXT_F(MSG_SCREEN_LOCK), OPT_RIGHTX | OPT_CENTERY); + #if DISABLED(TOUCH_UI_NO_BOOTSCREEN) cmd.text(BTN_POS(1,5), BTN_SIZE(2,1), GET_TEXT_F(MSG_BOOT_SCREEN), OPT_RIGHTX | OPT_CENTERY); + #endif #undef EDGE_R } @@ -95,16 +97,18 @@ void InterfaceSettingsScreen::onRedraw(draw_mode_t what) { .tag(3).slider(BTN_POS(3,3), BTN_SIZE(2,1), screen_data.InterfaceSettingsScreen.volume, 0xFF) .colors(ui_toggle) .tag(4).toggle2(BTN_POS(3,4), BTN_SIZE(w,1), GET_TEXT_F(MSG_NO), GET_TEXT_F(MSG_YES), LockScreen::is_enabled()) + #if DISABLED(TOUCH_UI_NO_BOOTSCREEN) .tag(5).toggle2(BTN_POS(3,5), BTN_SIZE(w,1), GET_TEXT_F(MSG_NO), GET_TEXT_F(MSG_YES), UIData::animations_enabled()) + #endif #undef EDGE_R #define EDGE_R 0 #ifdef TOUCH_UI_PORTRAIT .colors(normal_btn) - .tag(6).button (BTN_POS(1,6), BTN_SIZE(4,1), GET_TEXT_F(MSG_INTERFACE_SOUNDS)) + .tag(6).button (BTN_POS(1,6), BTN_SIZE(4,1), GET_TEXT_F(MSG_SOUNDS)) .colors(action_btn) .tag(1).button (BTN_POS(1,7), BTN_SIZE(4,1), GET_TEXT_F(MSG_BACK)); #else - .tag(6).button (BTN_POS(1,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_INTERFACE_SOUNDS)) + .tag(6).button (BTN_POS(1,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_SOUNDS)) .colors(action_btn) .tag(1).button (BTN_POS(3,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_BACK)); #endif @@ -252,7 +256,7 @@ void InterfaceSettingsScreen::loadSettings(const char *buff) { } #ifdef ARCHIM2_SPI_FLASH_EEPROM_BACKUP_SIZE - #include "../../../../../HAL/shared/persistent_store_api.h" + #include "../../../../../HAL/shared/eeprom_api.h" bool restoreEEPROM() { uint8_t data[ARCHIM2_SPI_FLASH_EEPROM_BACKUP_SIZE]; diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_sounds_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_sounds_screen.cpp index 57f520e8..48fae863 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_sounds_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/interface_sounds_screen.cpp @@ -71,7 +71,7 @@ void InterfaceSoundsScreen::onRedraw(draw_mode_t what) { #define GRID_ROWS 9 .font(font_medium) - .text(BTN_POS(1,1), BTN_SIZE(4,1), GET_TEXT_F(MSG_INTERFACE_SOUNDS)) + .text(BTN_POS(1,1), BTN_SIZE(4,1), GET_TEXT_F(MSG_SOUNDS)) #undef EDGE_R #define EDGE_R 30 .font(font_small) diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/main_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/main_menu.cpp index 016996e2..5d165ede 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/main_menu.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/main_menu.cpp @@ -37,81 +37,89 @@ void MainMenu::onRedraw(draw_mode_t what) { .cmd(CLEAR(true,true,true)); } + #ifdef TOUCH_UI_PORTRAIT + #define GRID_ROWS 8 + #define GRID_COLS 2 + #define ABOUT_PRINTER_POS BTN_POS(1,1), BTN_SIZE(2,1) + #define ADVANCED_SETTINGS_POS BTN_POS(1,2), BTN_SIZE(2,1) + #define FILAMENTCHANGE_POS BTN_POS(1,3), BTN_SIZE(2,1) + #define TEMPERATURE_POS BTN_POS(1,4), BTN_SIZE(2,1) + #define MOVE_AXIS_POS BTN_POS(1,5), BTN_SIZE(1,1) + #define DISABLE_STEPPERS_POS BTN_POS(2,5), BTN_SIZE(1,1) + #define AUTO_HOME_POS BTN_POS(1,6), BTN_SIZE(1,1) + #define CLEAN_NOZZLE_POS BTN_POS(2,6), BTN_SIZE(1,1) + #define LEVEL_BED_POS BTN_POS(1,7), BTN_SIZE(1,1) + #define LEVEL_AXIS_POS BTN_POS(2,7), BTN_SIZE(1,1) + #define BACK_POS BTN_POS(1,8), BTN_SIZE(2,1) + #else + #define GRID_ROWS 6 + #define GRID_COLS 2 + #define ADVANCED_SETTINGS_POS BTN_POS(1,1), BTN_SIZE(1,1) + #define ABOUT_PRINTER_POS BTN_POS(2,1), BTN_SIZE(1,1) + #define AUTO_HOME_POS BTN_POS(1,2), BTN_SIZE(1,1) + #define CLEAN_NOZZLE_POS BTN_POS(2,2), BTN_SIZE(1,1) + #define MOVE_AXIS_POS BTN_POS(1,3), BTN_SIZE(1,1) + #define DISABLE_STEPPERS_POS BTN_POS(2,3), BTN_SIZE(1,1) + #define TEMPERATURE_POS BTN_POS(1,4), BTN_SIZE(1,1) + #define FILAMENTCHANGE_POS BTN_POS(2,4), BTN_SIZE(1,1) + #define LEVEL_BED_POS BTN_POS(1,5), BTN_SIZE(1,1) + #define LEVEL_AXIS_POS BTN_POS(2,5), BTN_SIZE(1,1) + #define BACK_POS BTN_POS(1,6), BTN_SIZE(2,1) + #endif + if (what & FOREGROUND) { CommandProcessor cmd; cmd.colors(normal_btn) .font(Theme::font_medium) - #ifdef TOUCH_UI_PORTRAIT - #define GRID_ROWS 8 - #define GRID_COLS 2 - .tag(2).button( BTN_POS(1,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_AUTO_HOME)) - .enabled( - #if ENABLED(NOZZLE_CLEAN_FEATURE) - 1 - #endif - ) - .tag(3).button( BTN_POS(2,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_CLEAN_NOZZLE)) - .tag(4).button( BTN_POS(1,2), BTN_SIZE(1,1), GET_TEXT_F(MSG_MOVE_AXIS)) - .tag(5).button( BTN_POS(2,2), BTN_SIZE(1,1), GET_TEXT_F(MSG_DISABLE_STEPPERS)) - .tag(6).button( BTN_POS(1,3), BTN_SIZE(2,1), GET_TEXT_F(MSG_TEMPERATURE)) - .enabled( - #if NONE(TOUCH_UI_LULZBOT_BIO, TOUCH_UI_COCOA_PRESS) - 1 - #endif + .tag(2).button( AUTO_HOME_POS, GET_TEXT_F(MSG_AUTO_HOME)) + .enabled( + #if ANY(NOZZLE_CLEAN_FEATURE, TOUCH_UI_COCOA_PRESS) + 1 + #endif + ) + .tag(3).button( CLEAN_NOZZLE_POS, GET_TEXT_F( + #if ENABLED(TOUCH_UI_COCOA_PRESS) + MSG_PREHEAT_1 + #else + MSG_CLEAN_NOZZLE + #endif + )) + .tag(4).button( MOVE_AXIS_POS, GET_TEXT_F(MSG_MOVE_AXIS)) + .tag(5).button( DISABLE_STEPPERS_POS, GET_TEXT_F(MSG_DISABLE_STEPPERS)) + .tag(6).button( TEMPERATURE_POS, GET_TEXT_F(MSG_TEMPERATURE)) + .enabled( + #if DISABLED(TOUCH_UI_LULZBOT_BIO) + 1 + #endif + ) + .tag(7).button( FILAMENTCHANGE_POS, GET_TEXT_F( + #if ENABLED(TOUCH_UI_COCOA_PRESS) + MSG_CASE_LIGHT + #else + MSG_FILAMENTCHANGE + #endif + )) + .tag(8).button( ADVANCED_SETTINGS_POS, GET_TEXT_F(MSG_ADVANCED_SETTINGS)) + .enabled( + #ifdef PRINTCOUNTER + 1 + #endif ) - .tag(7).button( BTN_POS(1,4), BTN_SIZE(2,1), GET_TEXT_F(MSG_FILAMENTCHANGE)) - .tag(8).button( BTN_POS(1,5), BTN_SIZE(2,1), GET_TEXT_F(MSG_ADVANCED_SETTINGS)) - .enabled( - #ifdef PRINTCOUNTER - 1 - #endif + .enabled( + #ifdef AXIS_LEVELING_COMMANDS + 1 + #endif ) - .tag(9).button( BTN_POS(1,7), BTN_SIZE(2,1), GET_TEXT_F(MSG_INFO_STATS_MENU)) - .tag(10).button( BTN_POS(1,6), BTN_SIZE(2,1), GET_TEXT_F(MSG_INFO_MENU)) - .colors(action_btn) - .tag(1).button( BTN_POS(1,8), BTN_SIZE(2,1), GET_TEXT_F(MSG_BACK)); - #undef GRID_COLS - #undef GRID_ROWS - #else - #define GRID_ROWS 5 - #define GRID_COLS 2 - .tag(2).button( BTN_POS(1,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_AUTO_HOME)) - #if ENABLED(TOUCH_UI_COCOA_PRESS) - .tag(3).button( BTN_POS(2,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_PREHEAT_1)) - #else - .enabled( - #if ENABLED(NOZZLE_CLEAN_FEATURE) - 1 - #endif - ) - .tag(3).button( BTN_POS(2,1), BTN_SIZE(1,1), GET_TEXT_F(MSG_CLEAN_NOZZLE)) - #endif - .tag(4).button( BTN_POS(1,2), BTN_SIZE(1,1), GET_TEXT_F(MSG_MOVE_AXIS)) - .tag(5).button( BTN_POS(2,2), BTN_SIZE(1,1), GET_TEXT_F(MSG_DISABLE_STEPPERS)) - .tag(6).button( BTN_POS(1,3), BTN_SIZE(1,1), GET_TEXT_F(MSG_TEMPERATURE)) - #if ENABLED(TOUCH_UI_COCOA_PRESS) - .tag(7).button( BTN_POS(2,3), BTN_SIZE(1,1), GET_TEXT_F(MSG_CASE_LIGHT)) - #else - .enabled( - #if DISABLED(TOUCH_UI_LULZBOT_BIO) - 1 - #endif - ) - .tag(7).button( BTN_POS(2,3), BTN_SIZE(1,1), GET_TEXT_F(MSG_FILAMENTCHANGE)) - #endif - .tag(8).button( BTN_POS(1,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_ADVANCED_SETTINGS)) - .enabled( - #ifdef PRINTCOUNTER - 1 - #endif + .tag(9).button( LEVEL_AXIS_POS, GET_TEXT_F(MSG_AUTOLEVEL_X_AXIS)) + .enabled( + #ifdef HAS_LEVELING + 1 + #endif ) - .tag(9).button( BTN_POS(2,4), BTN_SIZE(1,1), GET_TEXT_F(MSG_INFO_STATS_MENU)) - .tag(10).button( BTN_POS(1,5), BTN_SIZE(1,1), GET_TEXT_F(MSG_INFO_MENU)) - .colors(action_btn) - .tag(1).button( BTN_POS(2,5), BTN_SIZE(1,1), GET_TEXT_F(MSG_BACK)); - #undef GRID_COLS - #undef GRID_ROWS - #endif + .tag(10).button( LEVEL_BED_POS, GET_TEXT_F(MSG_LEVEL_BED)) + .tag(11).button( ABOUT_PRINTER_POS, GET_TEXT_F(MSG_INFO_MENU)) + .colors(action_btn) + .tag(1).button( BACK_POS, GET_TEXT_F(MSG_BACK)); } } @@ -122,23 +130,32 @@ bool MainMenu::onTouchEnd(uint8_t tag) { case 1: SaveSettingsDialogBox::promptToSaveSettings(); break; case 2: SpinnerDialogBox::enqueueAndWait_P(F("G28")); break; #if ENABLED(TOUCH_UI_COCOA_PRESS) - case 3: GOTO_SCREEN(PreheatTimerScreen); break; + case 3: GOTO_SCREEN(PreheatMenu); break; #elif ENABLED(NOZZLE_CLEAN_FEATURE) case 3: injectCommands_P(PSTR("G12")); GOTO_SCREEN(StatusScreen); break; #endif case 4: GOTO_SCREEN(MoveAxisScreen); break; case 5: injectCommands_P(PSTR("M84")); break; case 6: GOTO_SCREEN(TemperatureScreen); break; - #if ENABLED(TOUCH_UI_COCOA_PRESS) + #if ENABLED(TOUCH_UI_COCOA_PRESS) && HAS_CASE_LIGHT case 7: GOTO_SCREEN(CaseLightScreen); break; #else case 7: GOTO_SCREEN(ChangeFilamentScreen); break; #endif case 8: GOTO_SCREEN(AdvancedSettingsMenu); break; -#if ENABLED(PRINTCOUNTER) - case 9: GOTO_SCREEN(StatisticsScreen); break; -#endif - case 10: GOTO_SCREEN(AboutScreen); break; + #ifdef AXIS_LEVELING_COMMANDS + case 9: SpinnerDialogBox::enqueueAndWait_P(F(AXIS_LEVELING_COMMANDS)); break; + #endif + #ifdef HAS_LEVELING + case 10: SpinnerDialogBox::enqueueAndWait_P(F( + #ifdef BED_LEVELING_COMMANDS + BED_LEVELING_COMMANDS + #else + "G29" + #endif + )); break; + #endif + case 11: GOTO_SCREEN(AboutScreen); break; default: return false; } diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/preheat_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/preheat_menu.cpp new file mode 100644 index 00000000..f0b5dd88 --- /dev/null +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/preheat_menu.cpp @@ -0,0 +1,83 @@ +/******************** + * preheat_menu.cpp * + ********************/ + +/**************************************************************************** + * Written By Marcio Teixeira 2020 - Cocoa Press * + * * + * This program is free software: you can redistribute it and/or modify * + * it under the terms of the GNU General Public License as published by * + * the Free Software Foundation, either version 3 of the License, or * + * (at your option) any later version. * + * * + * This program is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * + * GNU General Public License for more details. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +#include "../config.h" + +#if ENABLED(TOUCH_UI_FTDI_EVE) && defined(TOUCH_UI_COCOA_PRESS) + +#include "screens.h" + +using namespace FTDI; +using namespace ExtUI; +using namespace Theme; + +void PreheatMenu::onRedraw(draw_mode_t what) { + if (what & BACKGROUND) { + CommandProcessor cmd; + cmd.cmd(CLEAR_COLOR_RGB(Theme::bg_color)) + .cmd(CLEAR(true,true,true)) + .tag(0); + } + + #define GRID_ROWS 3 + #define GRID_COLS 2 + + if (what & FOREGROUND) { + CommandProcessor cmd; + cmd.cmd(COLOR_RGB(bg_text_enabled)) + .font(Theme::font_medium) + .text ( BTN_POS(1,1), BTN_SIZE(2,1), GET_TEXT_F(MSG_PREHEAT_1)) + .colors(normal_btn) + .tag(2).button( BTN_POS(1,2), BTN_SIZE(1,1), F("Dark Chocolate")) + .tag(3).button( BTN_POS(2,2), BTN_SIZE(1,1), F("Milk Chocolate")) + .tag(4).button( BTN_POS(1,3), BTN_SIZE(1,1), F("White Chocolate")) + .colors(action_btn) + .tag(1) .button( BTN_POS(2,3), BTN_SIZE(1,1), GET_TEXT_F(MSG_BACK)); + } +} + +bool PreheatMenu::onTouchEnd(uint8_t tag) { + switch (tag) { + case 1: GOTO_PREVIOUS(); break; + case 2: + #ifdef COCOA_PRESS_PREHEAT_DARK_CHOCOLATE_SCRIPT + injectCommands_P(PSTR(COCOA_PRESS_PREHEAT_DARK_CHOCOLATE_SCRIPT)); + #endif + GOTO_SCREEN(PreheatTimerScreen); + break; + case 3: + #ifdef COCOA_PRESS_PREHEAT_MILK_CHOCOLATE_SCRIPT + injectCommands_P(PSTR(COCOA_PRESS_PREHEAT_MILK_CHOCOLATE_SCRIPT)); + #endif + GOTO_SCREEN(PreheatTimerScreen); + break; + case 4: + #ifdef COCOA_PRESS_PREHEAT_WHITE_CHOCOLATE_SCRIPT + injectCommands_P(PSTR(COCOA_PRESS_PREHEAT_WHITE_CHOCOLATE_SCRIPT)); + #endif + GOTO_SCREEN(PreheatTimerScreen); + break; + default: return false; + } + return true; +} + +#endif // TOUCH_UI_FTDI_EVE diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/preheat_timer_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/preheat_timer_screen.cpp index 0a24c300..7d68ae2d 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/preheat_timer_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/preheat_timer_screen.cpp @@ -77,9 +77,6 @@ void PreheatTimerScreen::draw_interaction_buttons(draw_mode_t what) { void PreheatTimerScreen::onEntry() { screen_data.PreheatTimerScreen.start_ms = millis(); - #ifdef COCOA_PRESS_PREHEAT_SCRIPT - injectCommands_P(PSTR(COCOA_PRESS_PREHEAT_SCRIPT)); - #endif } void PreheatTimerScreen::onRedraw(draw_mode_t what) { diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.cpp index 69c1cf14..ce754620 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.cpp @@ -105,6 +105,7 @@ SCREEN_TABLE { DECL_SCREEN(BioConfirmHomeE), #endif #if ENABLED(TOUCH_UI_COCOA_PRESS) + DECL_SCREEN(PreheatMenu), DECL_SCREEN(PreheatTimerScreen), #endif #if ENABLED(TOUCH_UI_DEVELOPER_MENU) diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h index 02c5b148..346d122a 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/screens.h @@ -76,6 +76,7 @@ enum { PRINTING_SCREEN_CACHE, #endif #if ENABLED(TOUCH_UI_COCOA_PRESS) + PREHEAT_MENU_CACHE, PREHEAT_TIMER_SCREEN_CACHE, #endif CHANGE_FILAMENT_SCREEN_CACHE, @@ -99,7 +100,7 @@ enum { class BaseScreen : public UIScreen { protected: - #ifdef LCD_TIMEOUT_TO_STATUS + #if LCD_TIMEOUT_TO_STATUS static uint32_t last_interaction; #endif @@ -314,6 +315,12 @@ class StatusScreen : public BaseScreen, public CachedScreen { + public: + static void onRedraw(draw_mode_t); + static bool onTouchEnd(uint8_t tag); + }; + class PreheatTimerScreen : public BaseScreen, public CachedScreen { private: static uint16_t secondsRemaining(); diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/status_screen.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/status_screen.cpp index e71f200a..98d0bba7 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/status_screen.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/status_screen.cpp @@ -33,9 +33,9 @@ using namespace FTDI; using namespace Theme; #ifdef TOUCH_UI_PORTRAIT - #define GRID_ROWS 8 + #define GRID_ROWS 8 #else - #define GRID_ROWS 8 + #define GRID_ROWS 8 #endif void StatusScreen::draw_axis_position(draw_mode_t what) { @@ -43,41 +43,41 @@ void StatusScreen::draw_axis_position(draw_mode_t what) { #define GRID_COLS 3 + #ifdef TOUCH_UI_PORTRAIT + #define X_LBL_POS BTN_POS(1,5), BTN_SIZE(1,1) + #define Y_LBL_POS BTN_POS(1,6), BTN_SIZE(1,1) + #define Z_LBL_POS BTN_POS(1,7), BTN_SIZE(1,1) + #define X_VAL_POS BTN_POS(2,5), BTN_SIZE(2,1) + #define Y_VAL_POS BTN_POS(2,6), BTN_SIZE(2,1) + #define Z_VAL_POS BTN_POS(2,7), BTN_SIZE(2,1) + #else + #define X_LBL_POS BTN_POS(1,5), BTN_SIZE(1,1) + #define Y_LBL_POS BTN_POS(2,5), BTN_SIZE(1,1) + #define Z_LBL_POS BTN_POS(3,5), BTN_SIZE(1,1) + #define X_VAL_POS BTN_POS(1,6), BTN_SIZE(1,1) + #define Y_VAL_POS BTN_POS(2,6), BTN_SIZE(1,1) + #define Z_VAL_POS BTN_POS(3,6), BTN_SIZE(1,1) + #endif + + #define _UNION_POS(x1,y1,w1,h1,x2,y2,w2,h2) x1,y1,max(x1+w1,x2+w2)-x1,max(y1+h1,y2+h2)-y1 + #define UNION_POS(p1, p2) _UNION_POS(p1, p2) + if (what & BACKGROUND) { cmd.tag(6) - #ifdef TOUCH_UI_PORTRAIT - .fgcolor(Theme::axis_label) - .font(Theme::font_large) - .button( BTN_POS(1,5), BTN_SIZE(2,1), F(""), OPT_FLAT) - .button( BTN_POS(1,6), BTN_SIZE(2,1), F(""), OPT_FLAT) - .button( BTN_POS(1,7), BTN_SIZE(2,1), F(""), OPT_FLAT) - - .font(Theme::font_small) - .text ( BTN_POS(1,5), BTN_SIZE(1,1), GET_TEXT_F(MSG_AXIS_X)) - .text ( BTN_POS(1,6), BTN_SIZE(1,1), GET_TEXT_F(MSG_AXIS_Y)) - .text ( BTN_POS(1,7), BTN_SIZE(1,1), GET_TEXT_F(MSG_AXIS_Z)) - - .font(Theme::font_medium) - .fgcolor(Theme::x_axis) .button( BTN_POS(2,5), BTN_SIZE(2,1), F(""), OPT_FLAT) - .fgcolor(Theme::y_axis) .button( BTN_POS(2,6), BTN_SIZE(2,1), F(""), OPT_FLAT) - .fgcolor(Theme::z_axis) .button( BTN_POS(2,7), BTN_SIZE(2,1), F(""), OPT_FLAT); - #else - .fgcolor(Theme::axis_label) - .font(Theme::font_large) - .button( BTN_POS(1,5), BTN_SIZE(1,2), F(""), OPT_FLAT) - .button( BTN_POS(2,5), BTN_SIZE(1,2), F(""), OPT_FLAT) - .button( BTN_POS(3,5), BTN_SIZE(1,2), F(""), OPT_FLAT) - - .font(Theme::font_small) - .text ( BTN_POS(1,5), BTN_SIZE(1,1), GET_TEXT_F(MSG_AXIS_X)) - .text ( BTN_POS(2,5), BTN_SIZE(1,1), GET_TEXT_F(MSG_AXIS_Y)) - .text ( BTN_POS(3,5), BTN_SIZE(1,1), GET_TEXT_F(MSG_AXIS_Z)) - .font(Theme::font_medium) - - .fgcolor(Theme::x_axis) .button( BTN_POS(1,6), BTN_SIZE(1,1), F(""), OPT_FLAT) - .fgcolor(Theme::y_axis) .button( BTN_POS(2,6), BTN_SIZE(1,1), F(""), OPT_FLAT) - .fgcolor(Theme::z_axis) .button( BTN_POS(3,6), BTN_SIZE(1,1), F(""), OPT_FLAT); - #endif + .fgcolor(Theme::axis_label) + .font(Theme::font_large) + .button( UNION_POS(X_LBL_POS, X_VAL_POS), F(""), OPT_FLAT) + .button( UNION_POS(Y_LBL_POS, Y_VAL_POS), F(""), OPT_FLAT) + .button( UNION_POS(Z_LBL_POS, Z_VAL_POS), F(""), OPT_FLAT) + .font(Theme::font_medium) + .fgcolor(Theme::x_axis) .button( X_VAL_POS, F(""), OPT_FLAT) + .fgcolor(Theme::y_axis) .button( Y_VAL_POS, F(""), OPT_FLAT) + .fgcolor(Theme::z_axis) .button( Z_VAL_POS, F(""), OPT_FLAT) + .font(Theme::font_small) + .text ( X_LBL_POS, GET_TEXT_F(MSG_AXIS_X)) + .text ( Y_LBL_POS, GET_TEXT_F(MSG_AXIS_Y)) + .text ( Z_LBL_POS, GET_TEXT_F(MSG_AXIS_Z)) + .colors(normal_btn); } if (what & FOREGROUND) { @@ -101,16 +101,11 @@ void StatusScreen::draw_axis_position(draw_mode_t what) { else strcpy_P(z_str, PSTR("?")); - cmd.tag(6).font(Theme::font_medium) - #ifdef TOUCH_UI_PORTRAIT - .text ( BTN_POS(2,5), BTN_SIZE(2,1), x_str) - .text ( BTN_POS(2,6), BTN_SIZE(2,1), y_str) - .text ( BTN_POS(2,7), BTN_SIZE(2,1), z_str); - #else - .text ( BTN_POS(1,6), BTN_SIZE(1,1), x_str) - .text ( BTN_POS(2,6), BTN_SIZE(1,1), y_str) - .text ( BTN_POS(3,6), BTN_SIZE(1,1), z_str); - #endif + cmd.tag(6) + .font(Theme::font_medium) + .text ( X_VAL_POS, x_str) + .text ( Y_VAL_POS, y_str) + .text ( Z_VAL_POS, z_str); } #undef GRID_COLS @@ -125,49 +120,49 @@ void StatusScreen::draw_axis_position(draw_mode_t what) { void StatusScreen::draw_temperature(draw_mode_t what) { using namespace Theme; + #define TEMP_RECT_1 BTN_POS(1,1), BTN_SIZE(4,2) + #define TEMP_RECT_2 BTN_POS(1,1), BTN_SIZE(8,1) + #define NOZ_1_POS BTN_POS(1,1), BTN_SIZE(4,1) + #define NOZ_2_POS BTN_POS(5,1), BTN_SIZE(4,1) + #define BED_POS BTN_POS(1,2), BTN_SIZE(4,1) + #define FAN_POS BTN_POS(5,2), BTN_SIZE(4,1) + + #define _ICON_POS(x,y,w,h) x, y, w/4, h + #define _TEXT_POS(x,y,w,h) x + w/4, y, w - w/4, h + #define ICON_POS(pos) _ICON_POS(pos) + #define TEXT_POS(pos) _TEXT_POS(pos) + CommandProcessor cmd; if (what & BACKGROUND) { cmd.font(Theme::font_small) - #ifdef TOUCH_UI_PORTRAIT - .tag(5) - .fgcolor(temp) .button( BTN_POS(1,1), BTN_SIZE(4,2), F(""), OPT_FLAT) - .button( BTN_POS(1,1), BTN_SIZE(8,1), F(""), OPT_FLAT) - .fgcolor(fan_speed) .button( BTN_POS(5,2), BTN_SIZE(4,1), F(""), OPT_FLAT) - .tag(0) - .fgcolor(progress) .button( BTN_POS(1,3), BTN_SIZE(4,1), F(""), OPT_FLAT) - .button( BTN_POS(5,3), BTN_SIZE(4,1), F(""), OPT_FLAT); - #else .tag(5) - .fgcolor(temp) .button( BTN_POS(1,1), BTN_SIZE(4,2), F(""), OPT_FLAT) - .button( BTN_POS(1,1), BTN_SIZE(8,1), F(""), OPT_FLAT) - .fgcolor(fan_speed) .button( BTN_POS(5,2), BTN_SIZE(4,1), F(""), OPT_FLAT) - .tag(0) - .fgcolor(progress) .button( BTN_POS(9,1), BTN_SIZE(4,1), F(""), OPT_FLAT) - .button( BTN_POS(9,2), BTN_SIZE(4,1), F(""), OPT_FLAT); - #endif + .fgcolor(temp) .button( TEMP_RECT_1, F(""), OPT_FLAT) + .button( TEMP_RECT_2, F(""), OPT_FLAT) + .fgcolor(fan_speed).button( FAN_POS, F(""), OPT_FLAT) + .tag(0); // Draw Extruder Bitmap on Extruder Temperature Button cmd.tag(5) - .cmd(BITMAP_SOURCE(Extruder_Icon_Info)) - .cmd(BITMAP_LAYOUT(Extruder_Icon_Info)) - .cmd(BITMAP_SIZE (Extruder_Icon_Info)) - .icon (BTN_POS(1,1), BTN_SIZE(1,1), Extruder_Icon_Info, icon_scale) - .icon (BTN_POS(5,1), BTN_SIZE(1,1), Extruder_Icon_Info, icon_scale); + .cmd (BITMAP_SOURCE(Extruder_Icon_Info)) + .cmd (BITMAP_LAYOUT(Extruder_Icon_Info)) + .cmd (BITMAP_SIZE (Extruder_Icon_Info)) + .icon(ICON_POS(NOZ_1_POS), Extruder_Icon_Info, icon_scale) + .icon(ICON_POS(NOZ_2_POS), Extruder_Icon_Info, icon_scale); // Draw Bed Heat Bitmap on Bed Heat Button - cmd.cmd(BITMAP_SOURCE(Bed_Heat_Icon_Info)) - .cmd(BITMAP_LAYOUT(Bed_Heat_Icon_Info)) - .cmd(BITMAP_SIZE (Bed_Heat_Icon_Info)) - .icon (BTN_POS(1,2), BTN_SIZE(1,1), Bed_Heat_Icon_Info, icon_scale); + cmd.cmd (BITMAP_SOURCE(Bed_Heat_Icon_Info)) + .cmd (BITMAP_LAYOUT(Bed_Heat_Icon_Info)) + .cmd (BITMAP_SIZE (Bed_Heat_Icon_Info)) + .icon(ICON_POS(BED_POS), Bed_Heat_Icon_Info, icon_scale); // Draw Fan Percent Bitmap on Bed Heat Button - cmd.cmd(BITMAP_SOURCE(Fan_Icon_Info)) - .cmd(BITMAP_LAYOUT(Fan_Icon_Info)) - .cmd(BITMAP_SIZE (Fan_Icon_Info)) - .icon (BTN_POS(5,2), BTN_SIZE(1,1), Fan_Icon_Info, icon_scale); + cmd.cmd (BITMAP_SOURCE(Fan_Icon_Info)) + .cmd (BITMAP_LAYOUT(Fan_Icon_Info)) + .cmd (BITMAP_SIZE (Fan_Icon_Info)) + .icon(ICON_POS(FAN_POS), Fan_Icon_Info, icon_scale); #ifdef TOUCH_UI_USE_UTF8 load_utf8_bitmaps(cmd); // Restore font bitmap handles @@ -212,10 +207,10 @@ void StatusScreen::draw_temperature(draw_mode_t what) { cmd.tag(5) .font(font_medium) - .text(BTN_POS(2,1), BTN_SIZE(3,1), e0_str) - .text(BTN_POS(6,1), BTN_SIZE(3,1), e1_str) - .text(BTN_POS(2,2), BTN_SIZE(3,1), bed_str) - .text(BTN_POS(6,2), BTN_SIZE(3,1), fan_str); + .text(TEXT_POS(NOZ_1_POS), e0_str) + .text(TEXT_POS(NOZ_2_POS), e1_str) + .text(TEXT_POS(BED_POS), bed_str) + .text(TEXT_POS(FAN_POS), fan_str); } } @@ -225,15 +220,18 @@ void StatusScreen::draw_progress(draw_mode_t what) { CommandProcessor cmd; + #if ENABLED(TOUCH_UI_PORTRAIT) + #define TIME_POS BTN_POS(1,3), BTN_SIZE(4,1) + #define PROGRESS_POS BTN_POS(5,3), BTN_SIZE(4,1) + #else + #define TIME_POS BTN_POS(9,1), BTN_SIZE(4,1) + #define PROGRESS_POS BTN_POS(9,2), BTN_SIZE(4,1) + #endif + if (what & BACKGROUND) { cmd.tag(0).font(font_medium) - #ifdef TOUCH_UI_PORTRAIT - .fgcolor(progress) .button(BTN_POS(1,3), BTN_SIZE(4,1), F(""), OPT_FLAT) - .button(BTN_POS(5,3), BTN_SIZE(4,1), F(""), OPT_FLAT); - #else - .fgcolor(progress) .button(BTN_POS(9,1), BTN_SIZE(4,1), F(""), OPT_FLAT) - .button(BTN_POS(9,2), BTN_SIZE(4,1), F(""), OPT_FLAT); - #endif + .fgcolor(progress).button(TIME_POS, F(""), OPT_FLAT) + .button(PROGRESS_POS, F(""), OPT_FLAT); } if (what & FOREGROUND) { @@ -248,13 +246,8 @@ void StatusScreen::draw_progress(draw_mode_t what) { sprintf_P(progress_str, PSTR("%-3d %%"), getProgress_percent() ); cmd.font(font_medium) - #ifdef TOUCH_UI_PORTRAIT - .tag(0).text(BTN_POS(1,3), BTN_SIZE(4,1), time_str) - .text(BTN_POS(5,3), BTN_SIZE(4,1), progress_str); - #else - .tag(0).text(BTN_POS(9,1), BTN_SIZE(4,1), time_str) - .text(BTN_POS(9,2), BTN_SIZE(4,1), progress_str); - #endif + .tag(0).text(TIME_POS, time_str) + .text(PROGRESS_POS, progress_str); } } @@ -266,6 +259,14 @@ void StatusScreen::draw_interaction_buttons(draw_mode_t what) { if (what & FOREGROUND) { using namespace ExtUI; + #if ENABLED(TOUCH_UI_PORTRAIT) + #define MEDIA_BTN_POS BTN_POS(1,8), BTN_SIZE(2,1) + #define MENU_BTN_POS BTN_POS(3,8), BTN_SIZE(2,1) + #else + #define MEDIA_BTN_POS BTN_POS(1,7), BTN_SIZE(2,2) + #define MENU_BTN_POS BTN_POS(3,7), BTN_SIZE(2,2) + #endif + const bool has_media = isMediaInserted() && !isPrintingFromMedia(); CommandProcessor cmd; @@ -273,42 +274,29 @@ void StatusScreen::draw_interaction_buttons(draw_mode_t what) { .font(Theme::font_medium) .enabled(has_media) .colors(has_media ? action_btn : normal_btn) - .tag(3).button( - #ifdef TOUCH_UI_PORTRAIT - BTN_POS(1,8), BTN_SIZE(2,1), - #else - BTN_POS(1,7), BTN_SIZE(2,2), - #endif - isPrintingFromMedia() ? GET_TEXT_F(MSG_PRINTING) : GET_TEXT_F(MSG_BUTTON_MEDIA) - ).colors(!has_media ? action_btn : normal_btn) - #ifdef TOUCH_UI_PORTRAIT - .tag(4).button( BTN_POS(3,8), BTN_SIZE(2,1), GET_TEXT_F(MSG_BUTTON_MENU)); - #else - .tag(4).button( BTN_POS(3,7), BTN_SIZE(2,2), GET_TEXT_F(MSG_BUTTON_MENU)); - #endif + .tag(3).button(MEDIA_BTN_POS, isPrintingFromMedia() ? GET_TEXT_F(MSG_PRINTING) : GET_TEXT_F(MSG_BUTTON_MEDIA)) + .colors(!has_media ? action_btn : normal_btn) + .tag(4).button( MENU_BTN_POS, GET_TEXT_F(MSG_BUTTON_MENU)); } #undef GRID_COLS } void StatusScreen::draw_status_message(draw_mode_t what, const char* message) { #define GRID_COLS 1 + + #if ENABLED(TOUCH_UI_PORTRAIT) + #define STATUS_POS BTN_POS(1,4), BTN_SIZE(1,1) + #else + #define STATUS_POS BTN_POS(1,3), BTN_SIZE(1,2) + #endif + if (what & BACKGROUND) { CommandProcessor cmd; cmd.fgcolor(Theme::status_msg) .tag(0) - #ifdef TOUCH_UI_PORTRAIT - .button( BTN_POS(1,4), BTN_SIZE(1,1), F(""), OPT_FLAT); - #else - .button( BTN_POS(1,3), BTN_SIZE(1,2), F(""), OPT_FLAT); - #endif + .button( STATUS_POS, F(""), OPT_FLAT); - draw_text_box(cmd, - #ifdef TOUCH_UI_PORTRAIT - BTN_POS(1,4), BTN_SIZE(1,1), - #else - BTN_POS(1,3), BTN_SIZE(1,2), - #endif - message, OPT_CENTER, font_large); + draw_text_box(cmd, STATUS_POS, message, OPT_CENTER, font_large); } #undef GRID_COLS } @@ -326,10 +314,10 @@ void StatusScreen::setStatusMessage(const char* message) { .cmd(CLEAR(true,true,true)); draw_temperature(BACKGROUND); - draw_progress(BACKGROUND); - draw_axis_position(BACKGROUND); draw_status_message(BACKGROUND, message); draw_interaction_buttons(BACKGROUND); + draw_progress(BACKGROUND); + draw_axis_position(BACKGROUND); storeBackground(); diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/colors.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/colors.h index 933e91db..e2770d81 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/colors.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/colors.h @@ -24,121 +24,149 @@ #pragma once namespace Theme { - #ifdef TOUCH_UI_LULZBOT_BIO - // The Lulzbot Bio uses the color PANTONE 2175C on the case silkscreen. - // This translates to HSL(208°, 100%, 39%) as an accent color on the GUI. - - constexpr int accent_hue = 208; - constexpr float accent_sat = 0.5; - - constexpr uint32_t logo_bg_rgb = 0xffffff; - constexpr uint32_t logo_fill_rgb = 0xffffff; - constexpr uint32_t logo_stroke_rgb = hsl_to_rgb(accent_hue, 1.0, 0.39); + #if ENABLED(TOUCH_UI_COCOA_THEME) + constexpr int accent_hue = 23; + + // Browns and Oranges + constexpr uint32_t accent_color_1 = hsl_to_rgb(12.8,0.597,0.263); // Darkest + constexpr uint32_t accent_color_2 = hsl_to_rgb(12.8,0.597,0.263); + constexpr uint32_t accent_color_3 = hsl_to_rgb( 9.6,0.664,0.443); + constexpr uint32_t accent_color_4 = hsl_to_rgb(16.3,0.873,0.537); + constexpr uint32_t accent_color_5 = hsl_to_rgb(23.0,0.889,0.539); + constexpr uint32_t accent_color_6 = hsl_to_rgb(23.0,0.889,0.539); // Lightest #else - // The Lulzbot logo uses the color PANTONE 382c. - // This translates to HSL(68°, 68%, 52%) as an accent color on the GUI. - - constexpr int accent_hue = 68; - constexpr float accent_sat = 0.68; - - constexpr uint32_t logo_bg_rgb = hsl_to_rgb(accent_hue, 0.77, 0.64); - constexpr uint32_t logo_fill_rgb = hsl_to_rgb(accent_hue, 0.68, 0.52); // Lulzbot Green - constexpr uint32_t logo_stroke_rgb = 0x000000; + // Use linear accent colors + + #if ANY(TOUCH_UI_ROYAL_THEME, TOUCH_UI_FROZEN_THEME) + // Dark blue accent colors + constexpr int accent_hue = 216; + constexpr float accent_sat = 0.7; + #else + // Green accent colors + constexpr int accent_hue = 68; + constexpr float accent_sat = 0.68; + #endif + + // Shades of accent color + constexpr uint32_t accent_color_0 = hsl_to_rgb(accent_hue, accent_sat, 0.15); // Darkest + constexpr uint32_t accent_color_1 = hsl_to_rgb(accent_hue, accent_sat, 0.26); + constexpr uint32_t accent_color_2 = hsl_to_rgb(accent_hue, accent_sat, 0.39); + constexpr uint32_t accent_color_3 = hsl_to_rgb(accent_hue, accent_sat, 0.52); + constexpr uint32_t accent_color_4 = hsl_to_rgb(accent_hue, accent_sat, 0.65); + constexpr uint32_t accent_color_5 = hsl_to_rgb(accent_hue, accent_sat, 0.78); + constexpr uint32_t accent_color_6 = hsl_to_rgb(accent_hue, accent_sat, 0.91); // Lightest #endif - // Shades of accent color + // Shades of gray - #ifdef TOUCH_UI_COCOA_PRESS - constexpr uint32_t accent_color_1 = hsl_to_rgb(12.8,0.597,0.263); // Darkest - constexpr uint32_t accent_color_2 = hsl_to_rgb(12.8,0.597,0.263); - constexpr uint32_t accent_color_3 = hsl_to_rgb( 9.6,0.664,0.443); - constexpr uint32_t accent_color_4 = hsl_to_rgb(16.3,0.873,0.537); - constexpr uint32_t accent_color_5 = hsl_to_rgb(23.0,0.889,0.539); - constexpr uint32_t accent_color_6 = hsl_to_rgb(23.0,0.889,0.539); // Lightest + constexpr float gray_sat = 0.14; + constexpr uint32_t gray_color_0 = hsl_to_rgb(accent_hue, gray_sat, 0.15); // Darkest + constexpr uint32_t gray_color_1 = hsl_to_rgb(accent_hue, gray_sat, 0.26); + constexpr uint32_t gray_color_2 = hsl_to_rgb(accent_hue, gray_sat, 0.39); + constexpr uint32_t gray_color_3 = hsl_to_rgb(accent_hue, gray_sat, 0.52); + constexpr uint32_t gray_color_4 = hsl_to_rgb(accent_hue, gray_sat, 0.65); + constexpr uint32_t gray_color_5 = hsl_to_rgb(accent_hue, gray_sat, 0.78); + constexpr uint32_t gray_color_6 = hsl_to_rgb(accent_hue, gray_sat, 0.91); // Lightest + + #if ENABLED(TOUCH_UI_ROYAL_THEME) + constexpr uint32_t theme_darkest = accent_color_1; + constexpr uint32_t theme_dark = accent_color_4; + + constexpr uint32_t bg_color = gray_color_0; + constexpr uint32_t axis_label = gray_color_1; + + constexpr uint32_t bg_text_enabled = accent_color_6; + constexpr uint32_t bg_text_disabled = gray_color_0; + constexpr uint32_t bg_normal = accent_color_4; + constexpr uint32_t fg_disabled = gray_color_0; + constexpr uint32_t fg_normal = accent_color_0; + constexpr uint32_t fg_action = accent_color_1; + + constexpr uint32_t logo_bg_rgb = accent_color_1; + constexpr uint32_t logo_fill_rgb = accent_color_0; + constexpr uint32_t logo_stroke_rgb = accent_color_4; + #elif ANY(TOUCH_UI_COCOA_THEME, TOUCH_UI_FROZEN_THEME) + constexpr uint32_t theme_darkest = accent_color_1; + constexpr uint32_t theme_dark = accent_color_4; + + constexpr uint32_t bg_color = 0xFFFFFF; + constexpr uint32_t axis_label = gray_color_5; + + constexpr uint32_t bg_text_enabled = accent_color_1; + constexpr uint32_t bg_text_disabled = gray_color_1; + constexpr uint32_t bg_normal = accent_color_4; + constexpr uint32_t fg_disabled = gray_color_6; + constexpr uint32_t fg_normal = accent_color_1; + constexpr uint32_t fg_action = accent_color_4; + + constexpr uint32_t logo_bg_rgb = accent_color_5; + constexpr uint32_t logo_fill_rgb = accent_color_6; + constexpr uint32_t logo_stroke_rgb = accent_color_2; #else - constexpr uint32_t accent_color_1 = hsl_to_rgb(accent_hue, accent_sat, 0.26); // Darkest - constexpr uint32_t accent_color_2 = hsl_to_rgb(accent_hue, accent_sat, 0.39); - constexpr uint32_t accent_color_3 = hsl_to_rgb(accent_hue, accent_sat, 0.52); - constexpr uint32_t accent_color_4 = hsl_to_rgb(accent_hue, accent_sat, 0.65); - constexpr uint32_t accent_color_5 = hsl_to_rgb(accent_hue, accent_sat, 0.78); - constexpr uint32_t accent_color_6 = hsl_to_rgb(accent_hue, accent_sat, 0.91); // Lightest + constexpr uint32_t theme_darkest = gray_color_1; + constexpr uint32_t theme_dark = gray_color_2; + + constexpr uint32_t bg_color = gray_color_1; + constexpr uint32_t axis_label = gray_color_2; + + constexpr uint32_t bg_text_enabled = 0xFFFFFF; + constexpr uint32_t bg_text_disabled = gray_color_2; + constexpr uint32_t bg_normal = gray_color_1; + constexpr uint32_t fg_disabled = gray_color_1; + constexpr uint32_t fg_normal = gray_color_2; + constexpr uint32_t fg_action = accent_color_2; + + constexpr uint32_t logo_bg_rgb = accent_color_4; + constexpr uint32_t logo_fill_rgb = accent_color_3; + constexpr uint32_t logo_stroke_rgb = 0x000000; #endif - // Shades of gray - - constexpr float gray_sat = 0.14; + constexpr uint32_t shadow_rgb = gray_color_6; + constexpr uint32_t stroke_rgb = accent_color_1; + constexpr uint32_t fill_rgb = accent_color_3; + constexpr uint32_t syringe_rgb = accent_color_5; - constexpr uint32_t gray_color_1 = hsl_to_rgb(accent_hue, gray_sat, 0.26); // Darkest - constexpr uint32_t gray_color_2 = hsl_to_rgb(accent_hue, gray_sat, 0.39); - constexpr uint32_t gray_color_3 = hsl_to_rgb(accent_hue, gray_sat, 0.52); - constexpr uint32_t gray_color_4 = hsl_to_rgb(accent_hue, gray_sat, 0.65); - constexpr uint32_t gray_color_5 = hsl_to_rgb(accent_hue, gray_sat, 0.78); - constexpr uint32_t gray_color_6 = hsl_to_rgb(accent_hue, gray_sat, 0.91); // Lightest - - #if NONE(TOUCH_UI_LULZBOT_BIO, TOUCH_UI_COCOA_PRESS) - // Lulzbot TAZ Pro - constexpr uint32_t theme_darkest = gray_color_1; - constexpr uint32_t theme_dark = gray_color_2; - - constexpr uint32_t bg_color = theme_darkest; - constexpr uint32_t bg_text_disabled = theme_dark; - constexpr uint32_t bg_text_enabled = 0xFFFFFF; - constexpr uint32_t bg_normal = theme_darkest; - - constexpr uint32_t fg_normal = theme_dark; - constexpr uint32_t fg_action = accent_color_2; - constexpr uint32_t fg_disabled = theme_darkest; + #if ENABLED(TOUCH_UI_ROYAL_THEME) + constexpr uint32_t x_axis = hsl_to_rgb(0, 1.00, 0.26); + constexpr uint32_t y_axis = hsl_to_rgb(120, 1.00, 0.13); + constexpr uint32_t z_axis = hsl_to_rgb(240, 1.00, 0.10); #else - // Lulzbot Bio - constexpr uint32_t theme_darkest = accent_color_1; - constexpr uint32_t theme_dark = accent_color_4; - - constexpr uint32_t bg_color = 0xFFFFFF; - constexpr uint32_t bg_text_disabled = gray_color_1; - constexpr uint32_t bg_text_enabled = accent_color_1; - constexpr uint32_t bg_normal = accent_color_4; - - constexpr uint32_t fg_normal = accent_color_1; - constexpr uint32_t fg_action = accent_color_4; - constexpr uint32_t fg_disabled = gray_color_6; - - constexpr uint32_t shadow_rgb = gray_color_6; - constexpr uint32_t stroke_rgb = accent_color_1; - constexpr uint32_t fill_rgb = accent_color_3; - constexpr uint32_t syringe_rgb = accent_color_5; + constexpr uint32_t x_axis = hsl_to_rgb(0, 1.00, 0.5); + constexpr uint32_t y_axis = hsl_to_rgb(120, 1.00, 0.37); + constexpr uint32_t z_axis = hsl_to_rgb(240, 1.00, 0.37); #endif - - constexpr uint32_t x_axis = 0xFF0000; - constexpr uint32_t y_axis = 0x00BB00; - constexpr uint32_t z_axis = 0x0000BF; - constexpr uint32_t e_axis = gray_color_2; - constexpr uint32_t feedrate = gray_color_2; - constexpr uint32_t other = gray_color_2; + constexpr uint32_t e_axis = axis_label; + constexpr uint32_t feedrate = axis_label; + constexpr uint32_t other = axis_label; // Status screen - constexpr uint32_t progress = gray_color_2; - constexpr uint32_t status_msg = gray_color_2; - constexpr uint32_t fan_speed = 0x377198; - constexpr uint32_t temp = 0x892c78; - constexpr uint32_t axis_label = gray_color_2; + constexpr uint32_t progress = axis_label; + constexpr uint32_t status_msg = axis_label; + #if ENABLED(TOUCH_UI_ROYAL_THEME) + constexpr uint32_t fan_speed = hsl_to_rgb(240, 0.5, 0.13); + constexpr uint32_t temp = hsl_to_rgb(343, 1.0, 0.23); + #else + constexpr uint32_t fan_speed = hsl_to_rgb(204, 0.47, 0.41); + constexpr uint32_t temp = hsl_to_rgb(311, 0.51, 0.35); + #endif - constexpr uint32_t disabled_icon = gray_color_1; + constexpr uint32_t disabled_icon = gray_color_1; // Calibration Registers Screen - constexpr uint32_t transformA = 0x3010D0; - constexpr uint32_t transformB = 0x4010D0; - constexpr uint32_t transformC = 0x5010D0; - constexpr uint32_t transformD = 0x6010D0; - constexpr uint32_t transformE = 0x7010D0; - constexpr uint32_t transformF = 0x8010D0; - constexpr uint32_t transformVal = 0x104010; - - constexpr btn_colors disabled_btn = {.bg = bg_color, .grad = fg_disabled, .fg = fg_disabled, .rgb = fg_disabled }; - constexpr btn_colors normal_btn = {.bg = fg_action, .grad = 0xFFFFFF, .fg = fg_normal, .rgb = 0xFFFFFF }; - constexpr btn_colors action_btn = {.bg = bg_color, .grad = 0xFFFFFF, .fg = fg_action, .rgb = 0xFFFFFF }; - constexpr btn_colors red_btn = {.bg = 0xFF5555, .grad = 0xFFFFFF, .fg = 0xFF0000, .rgb = 0xFFFFFF }; - constexpr btn_colors ui_slider = {.bg = theme_darkest, .grad = 0xFFFFFF, .fg = theme_dark, .rgb = accent_color_3 }; - constexpr btn_colors ui_toggle = {.bg = theme_darkest, .grad = 0xFFFFFF, .fg = theme_dark, .rgb = 0xFFFFFF }; + constexpr uint32_t transformA = 0x3010D0; + constexpr uint32_t transformB = 0x4010D0; + constexpr uint32_t transformC = 0x5010D0; + constexpr uint32_t transformD = 0x6010D0; + constexpr uint32_t transformE = 0x7010D0; + constexpr uint32_t transformF = 0x8010D0; + constexpr uint32_t transformVal = 0x104010; + + constexpr btn_colors disabled_btn = {.bg = bg_color, .grad = fg_disabled, .fg = fg_disabled, .rgb = fg_disabled }; + constexpr btn_colors normal_btn = {.bg = fg_action, .grad = 0xFFFFFF, .fg = fg_normal, .rgb = 0xFFFFFF }; + constexpr btn_colors action_btn = {.bg = bg_color, .grad = 0xFFFFFF, .fg = fg_action, .rgb = 0xFFFFFF }; + constexpr btn_colors red_btn = {.bg = 0xFF5555, .grad = 0xFFFFFF, .fg = 0xFF0000, .rgb = 0xFFFFFF }; + constexpr btn_colors ui_slider = {.bg = theme_darkest, .grad = 0xFFFFFF, .fg = theme_dark, .rgb = accent_color_3 }; + constexpr btn_colors ui_toggle = {.bg = theme_darkest, .grad = 0xFFFFFF, .fg = theme_dark, .rgb = 0xFFFFFF }; // Temperature color scale diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/marlin_bootscreen_landscape.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/marlin_bootscreen_landscape.h index 5e01f047..a65cbea5 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/marlin_bootscreen_landscape.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/marlin_bootscreen_landscape.h @@ -35,5 +35,5 @@ const PROGMEM uint16_t logo_stroke[] = {0xADF3, 0x546C, 0x419D, 0x546F, 0x3D05, #define LOGO_BACKGROUND logo_bg_rgb #define LOGO_PAINT_PATHS \ - LOGO_PAINT_PATH(logo_stroke_rgb, logo_stroke) \ - LOGO_PAINT_PATH(logo_fill_rgb, logo_fill) + LOGO_PAINT_PATH(logo_fill_rgb, logo_fill) \ + LOGO_PAINT_PATH(logo_stroke_rgb, logo_stroke) diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/marlin_bootscreen_portrait.h b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/marlin_bootscreen_portrait.h index a5af7a14..a9c1d404 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/marlin_bootscreen_portrait.h +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/theme/marlin_bootscreen_portrait.h @@ -35,5 +35,5 @@ const PROGMEM uint16_t logo_stroke[] = {0x3C19, 0x70C5, 0x371A, 0x7159, 0x3302, #define LOGO_BACKGROUND logo_bg_rgb #define LOGO_PAINT_PATHS \ - LOGO_PAINT_PATH(logo_stroke_rgb, logo_stroke) \ - LOGO_PAINT_PATH(logo_fill_rgb, logo_fill) + LOGO_PAINT_PATH(logo_fill_rgb, logo_fill) \ + LOGO_PAINT_PATH(logo_stroke_rgb, logo_stroke) diff --git a/Marlin/src/lcd/extui/ui_api.h b/Marlin/src/lcd/extui/ui_api.h index 61fecaed..01e0d1b7 100644 --- a/Marlin/src/lcd/extui/ui_api.h +++ b/Marlin/src/lcd/extui/ui_api.h @@ -341,10 +341,10 @@ namespace ExtUI { void onConfigurationStoreWritten(bool success); void onConfigurationStoreRead(bool success); #if ENABLED(POWER_LOSS_RECOVERY) - void OnPowerLossResume(); + void onPowerLossResume(); #endif #if HAS_PID_HEATING - void OnPidTuning(const result_t rst); + void onPidTuning(const result_t rst); #endif }; diff --git a/Marlin/src/lcd/extui_dgus_lcd.cpp b/Marlin/src/lcd/extui_dgus_lcd.cpp index 66a58f82..855d0903 100644 --- a/Marlin/src/lcd/extui_dgus_lcd.cpp +++ b/Marlin/src/lcd/extui_dgus_lcd.cpp @@ -123,7 +123,7 @@ namespace ExtUI { } #if ENABLED(POWER_LOSS_RECOVERY) - void OnPowerLossResume() { + void onPowerLossResume() { // Called on resume from power-loss ScreenHandler.GotoScreen(DGUSLCD_SCREEN_POWER_LOSS); } @@ -131,9 +131,9 @@ namespace ExtUI { #if HAS_PID_HEATING - void OnPidTuning(const result_t rst) { + void onPidTuning(const result_t rst) { // Called for temperature PID tuning result - SERIAL_ECHOLNPAIR("OnPidTuning:",rst); + SERIAL_ECHOLNPAIR("onPidTuning:",rst); switch(rst) { case PID_BAD_EXTRUDER_NUM: ScreenHandler.setstatusmessagePGM(PSTR(STR_PID_BAD_EXTRUDER_NUM)); diff --git a/Marlin/src/lcd/extui_example.cpp b/Marlin/src/lcd/extui_example.cpp index 741787db..5c9a193d 100644 --- a/Marlin/src/lcd/extui_example.cpp +++ b/Marlin/src/lcd/extui_example.cpp @@ -94,13 +94,13 @@ namespace ExtUI { } #if ENABLED(POWER_LOSS_RECOVERY) - void OnPowerLossResume() { + void onPowerLossResume() { // Called on resume from power-loss } #endif #if HAS_PID_HEATING - void OnPidTuning(const result_t rst) { + void onPidTuning(const result_t rst) { // Called for temperature PID tuning result } #endif diff --git a/Marlin/src/lcd/extui_malyan_lcd.cpp b/Marlin/src/lcd/extui_malyan_lcd.cpp index 0bb8060b..ddb8b846 100644 --- a/Marlin/src/lcd/extui_malyan_lcd.cpp +++ b/Marlin/src/lcd/extui_malyan_lcd.cpp @@ -483,7 +483,7 @@ namespace ExtUI { void onLoadSettings(const char*) {} void onConfigurationStoreWritten(bool) {} void onConfigurationStoreRead(bool) {} - void OnPidTuning(const result_t) {} + void onPidTuning(const result_t) {} } #endif // MALYAN_LCD diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index 75c13de9..a52d9652 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -352,6 +352,7 @@ namespace Language_en { PROGMEM Language_Str MSG_PRINT_PAUSED = _UxGT("Print Paused"); PROGMEM Language_Str MSG_PRINTING = _UxGT("Printing..."); PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("Print Aborted"); + PROGMEM Language_Str MSG_PRINT_DONE = _UxGT("Print Done"); PROGMEM Language_Str MSG_NO_MOVE = _UxGT("No Move."); PROGMEM Language_Str MSG_KILLED = _UxGT("KILLED. "); PROGMEM Language_Str MSG_STOPPED = _UxGT("STOPPED. "); @@ -601,6 +602,9 @@ namespace Language_en { PROGMEM Language_Str MSG_BACKLASH_C = LCD_STR_C; PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Correction"); PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Smoothing"); + + PROGMEM Language_Str MSG_LEVEL_X_AXIS = _UxGT("Level X Axis"); + PROGMEM Language_Str MSG_AUTO_CALIBRATE = _UxGT("Auto Calibrate"); } #if FAN_COUNT == 1 diff --git a/Marlin/src/lcd/language/language_fr.h b/Marlin/src/lcd/language/language_fr.h index ffa12f39..e691d26a 100644 --- a/Marlin/src/lcd/language/language_fr.h +++ b/Marlin/src/lcd/language/language_fr.h @@ -93,7 +93,7 @@ namespace Language_fr { PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Allumer alim."); PROGMEM Language_Str MSG_SWITCH_PS_OFF = _UxGT("Eteindre alim."); PROGMEM Language_Str MSG_EXTRUDE = _UxGT("Extrusion"); - PROGMEM Language_Str MSG_RETRACT = _UxGT("Rétraction"); + PROGMEM Language_Str MSG_RETRACT = _UxGT("Rétractation"); PROGMEM Language_Str MSG_MOVE_AXIS = _UxGT("Déplacer un axe"); PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Régler Niv. lit"); PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Niveau du lit"); @@ -317,7 +317,7 @@ namespace Language_fr { PROGMEM Language_Str MSG_NO_MOVE = _UxGT("Moteurs bloqués"); PROGMEM Language_Str MSG_KILLED = _UxGT("KILLED"); PROGMEM Language_Str MSG_STOPPED = _UxGT("STOPPÉ"); - PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("Rétraction mm"); + PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("Rétractation mm"); PROGMEM Language_Str MSG_CONTROL_RETRACT_SWAP = _UxGT("Ech. rétr. mm"); PROGMEM Language_Str MSG_CONTROL_RETRACTF = _UxGT("Vit. rétract°"); PROGMEM Language_Str MSG_CONTROL_RETRACT_ZHOP = _UxGT("Saut Z mm"); diff --git a/Marlin/src/lcd/language/language_it.h b/Marlin/src/lcd/language/language_it.h index ae4dd813..8d8112d5 100644 --- a/Marlin/src/lcd/language/language_it.h +++ b/Marlin/src/lcd/language/language_it.h @@ -245,6 +245,11 @@ namespace Language_it { PROGMEM Language_Str MSG_STORED_FAN_N = _UxGT("Ventola mem. ~"); // Max 15 characters PROGMEM Language_Str MSG_EXTRA_FAN_SPEED = _UxGT("Extra vel.vent."); // Max 15 characters PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("Extra v.vent. ~"); // Max 15 characters + PROGMEM Language_Str MSG_CONTROLLER_FAN = _UxGT("Controller vent."); + PROGMEM Language_Str MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("Vel. inattivo"); + PROGMEM Language_Str MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Modo autom."); + PROGMEM Language_Str MSG_CONTROLLER_FAN_SPEED = _UxGT("Vel. attivo"); + PROGMEM Language_Str MSG_CONTROLLER_FAN_DURATION = _UxGT("Tempo inattivo"); PROGMEM Language_Str MSG_FLOW = _UxGT("Flusso"); PROGMEM Language_Str MSG_FLOW_N = _UxGT("Flusso ~"); PROGMEM Language_Str MSG_CONTROL = _UxGT("Controllo"); @@ -312,6 +317,9 @@ namespace Language_it { PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Carica impostazioni"); PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("Ripristina imp."); PROGMEM Language_Str MSG_INIT_EEPROM = _UxGT("Inizializza EEPROM"); + PROGMEM Language_Str MSG_ERR_EEPROM_CRC = _UxGT("Err: CRC EEPROM"); + PROGMEM Language_Str MSG_ERR_EEPROM_INDEX = _UxGT("Err: Indice EEPROM"); + PROGMEM Language_Str MSG_ERR_EEPROM_VERSION = _UxGT("Err: Versione EEPROM"); PROGMEM Language_Str MSG_MEDIA_UPDATE = _UxGT("Aggiorna media"); PROGMEM Language_Str MSG_RESET_PRINTER = _UxGT("Resetta stampante"); PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT("Aggiorna"); diff --git a/Marlin/src/lcd/language/language_ru.h b/Marlin/src/lcd/language/language_ru.h index 82c91c65..a7c971e8 100644 --- a/Marlin/src/lcd/language/language_ru.h +++ b/Marlin/src/lcd/language/language_ru.h @@ -222,6 +222,11 @@ namespace Language_ru { PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Кулер ~"); PROGMEM Language_Str MSG_EXTRA_FAN_SPEED = _UxGT("Кулер доп."); PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("Кулер доп. ~"); + PROGMEM Language_Str MSG_CONTROLLER_FAN = _UxGT("Обдув платы"); + PROGMEM Language_Str MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("Обороты простоя"); + PROGMEM Language_Str MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Автовключение"); + PROGMEM Language_Str MSG_CONTROLLER_FAN_SPEED = _UxGT("Рабочие обороты"); + PROGMEM Language_Str MSG_CONTROLLER_FAN_DURATION = _UxGT("Простой после"); PROGMEM Language_Str MSG_FLOW = _UxGT("Поток"); PROGMEM Language_Str MSG_FLOW_N = _UxGT("Поток ~"); PROGMEM Language_Str MSG_CONTROL = _UxGT("Настройки"); diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index 1577e59f..f2327b75 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -84,7 +84,7 @@ void menu_cancelobject(); START_MENU(); BACK_ITEM(MSG_ADVANCED_SETTINGS); #define EDIT_CURRENT_PWM(LABEL,I) EDIT_ITEM_P(long5, PSTR(LABEL), &stepper.motor_current_setting[I], 100, 2000, stepper.refresh_motor_power) - #if PIN_EXISTS(MOTOR_CURRENT_PWM_XY) + #if ANY_PIN(MOTOR_CURRENT_PWM_XY, MOTOR_CURRENT_PWM_X, MOTOR_CURRENT_PWM_Y) EDIT_CURRENT_PWM(STR_X STR_Y, 0); #endif #if PIN_EXISTS(MOTOR_CURRENT_PWM_Z) diff --git a/Marlin/src/lcd/menu/menu_backlash.cpp b/Marlin/src/lcd/menu/menu_backlash.cpp index ad9c51d4..720694bf 100644 --- a/Marlin/src/lcd/menu/menu_backlash.cpp +++ b/Marlin/src/lcd/menu/menu_backlash.cpp @@ -39,9 +39,9 @@ void menu_backlash() { EDIT_ITEM_FAST(percent, MSG_BACKLASH_CORRECTION, &backlash.correction, all_off, all_on); #define EDIT_BACKLASH_DISTANCE(N) EDIT_ITEM_FAST(float43, MSG_BACKLASH_##N, &backlash.distance_mm[_AXIS(N)], 0.0f, 9.9f); - EDIT_BACKLASH_DISTANCE(A); - EDIT_BACKLASH_DISTANCE(B); - EDIT_BACKLASH_DISTANCE(C); + if (AXIS_CAN_CALIBRATE(A)) EDIT_BACKLASH_DISTANCE(A); + if (AXIS_CAN_CALIBRATE(B)) EDIT_BACKLASH_DISTANCE(B); + if (AXIS_CAN_CALIBRATE(C)) EDIT_BACKLASH_DISTANCE(C); #ifdef BACKLASH_SMOOTHING_MM EDIT_ITEM_FAST(float43, MSG_BACKLASH_SMOOTHING, &backlash.smoothing_mm, 0.0f, 9.9f); diff --git a/Marlin/src/lcd/menu/menu_delta_calibrate.cpp b/Marlin/src/lcd/menu/menu_delta_calibrate.cpp index a27e2c97..ac80870a 100644 --- a/Marlin/src/lcd/menu/menu_delta_calibrate.cpp +++ b/Marlin/src/lcd/menu/menu_delta_calibrate.cpp @@ -61,16 +61,14 @@ void _man_probe_pt(const xy_pos_t &xy) { float lcd_probe_pt(const xy_pos_t &xy) { _man_probe_pt(xy); - KEEPALIVE_STATE(PAUSED_FOR_USER); ui.defer_status_screen(); - wait_for_user = true; #if ENABLED(HOST_PROMPT_SUPPORT) host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Delta Calibration in progress"), CONTINUE_STR); #endif #if ENABLED(EXTENSIBLE_UI) ExtUI::onUserConfirmRequired_P(PSTR("Delta Calibration in progress")); #endif - while (wait_for_user) idle(); + wait_for_user_response(); ui.goto_previous_screen_no_defer(); return current_position.z; } diff --git a/Marlin/src/lcd/ultralcd.cpp b/Marlin/src/lcd/ultralcd.cpp index 1cb23baa..bbcb678d 100644 --- a/Marlin/src/lcd/ultralcd.cpp +++ b/Marlin/src/lcd/ultralcd.cpp @@ -524,7 +524,7 @@ void MarlinUI::status_screen() { #if PROGRESS_MSG_EXPIRE > 0 // Handle message expire - if (expire_status_ms > 0) { + if (expire_status_ms) { // Expire the message if a job is active and the bar has ticks if (get_progress_percent() > 2 && !print_job_timer.isPaused()) { @@ -776,6 +776,13 @@ void MarlinUI::update() { // If the action button is pressed... static bool wait_for_unclick; // = false + auto do_click = [&]{ + wait_for_unclick = true; // - Set debounce flag to ignore continous clicks + lcd_clicked = !wait_for_user && !no_reentry; // - Keep the click if not waiting for a user-click + wait_for_user = false; // - Any click clears wait for user + quick_feedback(); // - Always make a click sound + }; + #if ENABLED(TOUCH_BUTTONS) if (touch_buttons) { RESET_STATUS_TIMEOUT(); @@ -796,12 +803,8 @@ void MarlinUI::update() { } } } - else if (!wait_for_unclick && (buttons & EN_C)) { // OK button, if not waiting for a debounce release: - wait_for_unclick = true; // - Set debounce flag to ignore continous clicks - lcd_clicked = !wait_for_user && !no_reentry; // - Keep the click if not waiting for a user-click - wait_for_user = false; // - Any click clears wait for user - quick_feedback(); // - Always make a click sound - } + else if (!wait_for_unclick && (buttons & EN_C)) // OK button, if not waiting for a debounce release: + do_click(); } else // keep wait_for_unclick value @@ -810,12 +813,7 @@ void MarlinUI::update() { { // Integrated LCD click handling via button_pressed if (!external_control && button_pressed()) { - if (!wait_for_unclick) { // If not waiting for a debounce release: - wait_for_unclick = true; // - Set debounce flag to ignore continous clicks - lcd_clicked = !wait_for_user && !no_reentry; // - Keep the click if not waiting for a user-click - wait_for_user = false; // - Any click clears wait for user - quick_feedback(); // - Always make a click sound - } + if (!wait_for_unclick) do_click(); // Handle the click } else wait_for_unclick = false; @@ -1337,15 +1335,19 @@ void MarlinUI::update() { UNUSED(persist); #endif + #if ENABLED(LCD_PROGRESS_BAR) || BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) + const millis_t ms = millis(); + #endif + #if ENABLED(LCD_PROGRESS_BAR) - progress_bar_ms = millis(); + progress_bar_ms = ms; #if PROGRESS_MSG_EXPIRE > 0 - expire_status_ms = persist ? 0 : progress_bar_ms + PROGRESS_MSG_EXPIRE; + expire_status_ms = persist ? 0 : ms + PROGRESS_MSG_EXPIRE; #endif #endif #if BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) - next_filament_display = millis() + 5000UL; // Show status message for 5s + next_filament_display = ms + 5000UL; // Show status message for 5s #endif #if HAS_SPI_LCD && ENABLED(STATUS_MESSAGE_SCROLLING) diff --git a/Marlin/src/libs/numtostr.cpp b/Marlin/src/libs/numtostr.cpp index ac82bf16..1ed315ae 100644 --- a/Marlin/src/libs/numtostr.cpp +++ b/Marlin/src/libs/numtostr.cpp @@ -312,7 +312,7 @@ const char* ftostr52sign(const float &f) { // Convert signed float to string with +12.345 format const char* ftostr53sign(const float &f) { - long i = (f * 1000 + (f < 0 ? -5: 5)) / 10; + long i = (f * 10000 + (f < 0 ? -5: 5)) / 10; conv[0] = MINUSOR(i, '+'); conv[1] = DIGIMOD(i, 10000); conv[2] = DIGIMOD(i, 1000); diff --git a/Marlin/src/module/configuration_store.cpp b/Marlin/src/module/configuration_store.cpp index 4b7946c6..2ecc9299 100644 --- a/Marlin/src/module/configuration_store.cpp +++ b/Marlin/src/module/configuration_store.cpp @@ -57,7 +57,7 @@ #include "../MarlinCore.h" #if EITHER(EEPROM_SETTINGS, SD_FIRMWARE_UPDATE) - #include "../HAL/shared/persistent_store_api.h" + #include "../HAL/shared/eeprom_api.h" #endif #include "probe.h" @@ -127,6 +127,11 @@ void M710_report(const bool forReplay); #endif +#define HAS_CASE_LIGHT_BRIGHTNESS (ENABLED(CASE_LIGHT_MENU) && DISABLED(CASE_LIGHT_NO_BRIGHTNESS)) +#if HAS_CASE_LIGHT_BRIGHTNESS + #include "../feature/caselight.h" +#endif + #pragma pack(push, 1) // No padding between variables typedef struct { uint16_t X, Y, Z, X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5; } tmc_stepper_current_t; @@ -376,6 +381,13 @@ typedef struct SettingsDataStruct { uint8_t extui_data[ExtUI::eeprom_data_size]; #endif + // + // HAS_CASE_LIGHT_BRIGHTNESS + // + #if HAS_CASE_LIGHT_BRIGHTNESS + uint8_t case_light_brightness; + #endif + } SettingsData; //static_assert(sizeof(SettingsData) <= E2END + 1, "EEPROM too small to contain SettingsData!"); @@ -441,6 +453,10 @@ void MarlinSettings::postprocess() { planner.recalculate_max_e_jerk(); #endif + #if HAS_CASE_LIGHT_BRIGHTNESS + update_case_light(); + #endif + // Refresh steps_to_mm with the reciprocal of axis_steps_per_mm // and init stepper.count[], planner.position[] with current_position planner.refresh_positioning(); @@ -1231,7 +1247,7 @@ void MarlinSettings::postprocess() { #if HAS_MOTOR_CURRENT_PWM EEPROM_WRITE(stepper.motor_current_setting); #else - const xyz_ulong_t no_current{0}; + const uint32_t no_current[3] = { 0 }; EEPROM_WRITE(no_current); #endif } @@ -1309,6 +1325,13 @@ void MarlinSettings::postprocess() { } #endif + // + // Case Light Brightness + // + #if HAS_CASE_LIGHT_BRIGHTNESS + EEPROM_WRITE(case_light_brightness); + #endif + // // Validate CRC and Data Size // @@ -2163,6 +2186,14 @@ void MarlinSettings::postprocess() { } #endif + // + // Case Light Brightness + // + #if HAS_CASE_LIGHT_BRIGHTNESS + _FIELD_TEST(case_light_brightness); + EEPROM_READ(case_light_brightness); + #endif + eeprom_error = size_error(eeprom_index - (EEPROM_OFFSET)); if (eeprom_error) { DEBUG_ECHO_START(); @@ -2458,6 +2489,14 @@ void MarlinSettings::reset() { ExtUI::onFactoryReset(); #endif + // + // Case Light Brightness + // + + #if HAS_CASE_LIGHT_BRIGHTNESS + case_light_brightness = CASE_LIGHT_DEFAULT_BRIGHTNESS; + #endif + // // Magnetic Parking Extruder // @@ -2696,7 +2735,7 @@ void MarlinSettings::reset() { #if HAS_MOTOR_CURRENT_PWM constexpr uint32_t tmp_motor_current_setting[3] = PWM_MOTOR_CURRENT; - for (uint8_t q = 3; q--;) + LOOP_L_N(q, 3) stepper.digipot_current(q, (stepper.motor_current_setting[q] = tmp_motor_current_setting[q])); #endif diff --git a/Marlin/src/module/configuration_store.h b/Marlin/src/module/configuration_store.h index a2c8d97d..f2e84c96 100644 --- a/Marlin/src/module/configuration_store.h +++ b/Marlin/src/module/configuration_store.h @@ -24,7 +24,7 @@ #include "../inc/MarlinConfig.h" #if ENABLED(EEPROM_SETTINGS) - #include "../HAL/shared/persistent_store_api.h" + #include "../HAL/shared/eeprom_api.h" #endif class MarlinSettings { diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index 14da9b47..1cc0a047 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -55,6 +55,10 @@ #include "../lcd/ultralcd.h" #endif +#if HAS_FILAMENT_SENSOR + #include "../feature/runout.h" +#endif + #if ENABLED(SENSORLESS_HOMING) #include "../feature/tmc_util.h" #endif @@ -332,6 +336,17 @@ void line_to_current_position(const feedRate_t &fr_mm_s/*=feedrate_mm_s*/) { planner.buffer_line(current_position, fr_mm_s, active_extruder); } +#if EXTRUDERS + void unscaled_e_move(const float &length, const feedRate_t &fr_mm_s) { + #if HAS_FILAMENT_SENSOR + runout.reset(); + #endif + current_position.e += length / planner.e_factor[active_extruder]; + line_to_current_position(fr_mm_s); + planner.synchronize(); + } +#endif + #if IS_KINEMATIC /** @@ -1292,12 +1307,14 @@ feedRate_t get_homing_bump_feedrate(const AxisEnum axis) { */ void do_homing_move(const AxisEnum axis, const float distance, const feedRate_t fr_mm_s=0.0) { + const feedRate_t real_fr_mm_s = fr_mm_s ?: homing_feedrate(axis); + if (DEBUGGING(LEVELING)) { DEBUG_ECHOPAIR(">>> do_homing_move(", axis_codes[axis], ", ", distance, ", "); if (fr_mm_s) DEBUG_ECHO(fr_mm_s); else - DEBUG_ECHOPAIR("[", homing_feedrate(axis), "]"); + DEBUG_ECHOPAIR("[", real_fr_mm_s, "]"); DEBUG_ECHOLNPGM(")"); } @@ -1331,7 +1348,6 @@ void do_homing_move(const AxisEnum axis, const float distance, const feedRate_t #endif } - const feedRate_t real_fr_mm_s = fr_mm_s ?: homing_feedrate(axis); #if IS_SCARA // Tell the planner the axis is at 0 current_position[axis] = 0; @@ -1344,14 +1360,14 @@ void do_homing_move(const AxisEnum axis, const float distance, const feedRate_t planner.set_machine_position_mm(target); target[axis] = distance; - #if IS_KINEMATIC && DISABLED(CLASSIC_JERK) - const xyze_float_t delta_mm_cart{0}; + #if HAS_DIST_MM_ARG + const xyze_float_t cart_dist_mm{0}; #endif // Set delta/cartesian axes directly planner.buffer_segment(target - #if IS_KINEMATIC && DISABLED(CLASSIC_JERK) - , delta_mm_cart + #if HAS_DIST_MM_ARG + , cart_dist_mm #endif , real_fr_mm_s, active_extruder ); diff --git a/Marlin/src/module/motion.h b/Marlin/src/module/motion.h index f6a75a91..e504f187 100644 --- a/Marlin/src/module/motion.h +++ b/Marlin/src/module/motion.h @@ -184,6 +184,10 @@ void sync_plan_position_e(); */ void line_to_current_position(const feedRate_t &fr_mm_s=feedrate_mm_s); +#if EXTRUDERS + void unscaled_e_move(const float &length, const feedRate_t &fr_mm_s); +#endif + void prepare_line_to_destination(); void _internal_move_to_destination(const feedRate_t &fr_mm_s=0.0f diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 3b2daf18..e1a050a4 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -1519,10 +1519,6 @@ void Planner::check_axes_activity() { #endif } - - #if ENABLED(SKEW_CORRECTION) - unskew(raw); - #endif } #endif // HAS_LEVELING @@ -1648,8 +1644,8 @@ bool Planner::_buffer_steps(const xyze_long_t &target #if HAS_POSITION_FLOAT , const xyze_pos_t &target_float #endif - #if IS_KINEMATIC && DISABLED(CLASSIC_JERK) - , const xyze_float_t &delta_mm_cart + #if HAS_DIST_MM_ARG + , const xyze_float_t &cart_dist_mm #endif , feedRate_t fr_mm_s, const uint8_t extruder, const float &millimeters ) { @@ -1666,8 +1662,8 @@ bool Planner::_buffer_steps(const xyze_long_t &target #if HAS_POSITION_FLOAT , target_float #endif - #if IS_KINEMATIC && DISABLED(CLASSIC_JERK) - , delta_mm_cart + #if HAS_DIST_MM_ARG + , cart_dist_mm #endif , fr_mm_s, extruder, millimeters )) { @@ -1712,8 +1708,8 @@ bool Planner::_populate_block(block_t * const block, bool split_move, #if HAS_POSITION_FLOAT , const xyze_pos_t &target_float #endif - #if IS_KINEMATIC && DISABLED(CLASSIC_JERK) - , const xyze_float_t &delta_mm_cart + #if HAS_DIST_MM_ARG + , const xyze_float_t &cart_dist_mm #endif , feedRate_t fr_mm_s, const uint8_t extruder, const float &millimeters/*=0.0*/ ) { @@ -1840,51 +1836,51 @@ bool Planner::_populate_block(block_t * const block, bool split_move, * So we need to create other 2 "AXIS", named X_HEAD and Y_HEAD, meaning the real displacement of the Head. * Having the real displacement of the head, we can calculate the total movement length and apply the desired speed. */ - struct DeltaMM : abce_float_t { + struct DistanceMM : abce_float_t { #if IS_CORE xyz_pos_t head; #endif - } delta_mm; + } steps_dist_mm; #if IS_CORE #if CORE_IS_XY - delta_mm.head.x = da * steps_to_mm[A_AXIS]; - delta_mm.head.y = db * steps_to_mm[B_AXIS]; - delta_mm.z = dc * steps_to_mm[Z_AXIS]; - delta_mm.a = (da + db) * steps_to_mm[A_AXIS]; - delta_mm.b = CORESIGN(da - db) * steps_to_mm[B_AXIS]; + steps_dist_mm.head.x = da * steps_to_mm[A_AXIS]; + steps_dist_mm.head.y = db * steps_to_mm[B_AXIS]; + steps_dist_mm.z = dc * steps_to_mm[Z_AXIS]; + steps_dist_mm.a = (da + db) * steps_to_mm[A_AXIS]; + steps_dist_mm.b = CORESIGN(da - db) * steps_to_mm[B_AXIS]; #elif CORE_IS_XZ - delta_mm.head.x = da * steps_to_mm[A_AXIS]; - delta_mm.y = db * steps_to_mm[Y_AXIS]; - delta_mm.head.z = dc * steps_to_mm[C_AXIS]; - delta_mm.a = (da + dc) * steps_to_mm[A_AXIS]; - delta_mm.c = CORESIGN(da - dc) * steps_to_mm[C_AXIS]; + steps_dist_mm.head.x = da * steps_to_mm[A_AXIS]; + steps_dist_mm.y = db * steps_to_mm[Y_AXIS]; + steps_dist_mm.head.z = dc * steps_to_mm[C_AXIS]; + steps_dist_mm.a = (da + dc) * steps_to_mm[A_AXIS]; + steps_dist_mm.c = CORESIGN(da - dc) * steps_to_mm[C_AXIS]; #elif CORE_IS_YZ - delta_mm.x = da * steps_to_mm[X_AXIS]; - delta_mm.head.y = db * steps_to_mm[B_AXIS]; - delta_mm.head.z = dc * steps_to_mm[C_AXIS]; - delta_mm.b = (db + dc) * steps_to_mm[B_AXIS]; - delta_mm.c = CORESIGN(db - dc) * steps_to_mm[C_AXIS]; + steps_dist_mm.x = da * steps_to_mm[X_AXIS]; + steps_dist_mm.head.y = db * steps_to_mm[B_AXIS]; + steps_dist_mm.head.z = dc * steps_to_mm[C_AXIS]; + steps_dist_mm.b = (db + dc) * steps_to_mm[B_AXIS]; + steps_dist_mm.c = CORESIGN(db - dc) * steps_to_mm[C_AXIS]; #endif #else - delta_mm.a = da * steps_to_mm[A_AXIS]; - delta_mm.b = db * steps_to_mm[B_AXIS]; - delta_mm.c = dc * steps_to_mm[C_AXIS]; + steps_dist_mm.a = da * steps_to_mm[A_AXIS]; + steps_dist_mm.b = db * steps_to_mm[B_AXIS]; + steps_dist_mm.c = dc * steps_to_mm[C_AXIS]; #endif #if EXTRUDERS - delta_mm.e = esteps_float * steps_to_mm[E_AXIS_N(extruder)]; + steps_dist_mm.e = esteps_float * steps_to_mm[E_AXIS_N(extruder)]; #else - delta_mm.e = 0.0f; + steps_dist_mm.e = 0.0f; #endif #if ENABLED(LCD_SHOW_E_TOTAL) - e_move_accumulator += delta_mm.e; + e_move_accumulator += steps_dist_mm.e; #endif if (block->steps.a < MIN_STEPS_PER_SEGMENT && block->steps.b < MIN_STEPS_PER_SEGMENT && block->steps.c < MIN_STEPS_PER_SEGMENT) { block->millimeters = (0 #if EXTRUDERS - + ABS(delta_mm.e) + + ABS(steps_dist_mm.e) #endif ); } @@ -1894,13 +1890,13 @@ bool Planner::_populate_block(block_t * const block, bool split_move, else block->millimeters = SQRT( #if CORE_IS_XY - sq(delta_mm.head.x) + sq(delta_mm.head.y) + sq(delta_mm.z) + sq(steps_dist_mm.head.x) + sq(steps_dist_mm.head.y) + sq(steps_dist_mm.z) #elif CORE_IS_XZ - sq(delta_mm.head.x) + sq(delta_mm.y) + sq(delta_mm.head.z) + sq(steps_dist_mm.head.x) + sq(steps_dist_mm.y) + sq(steps_dist_mm.head.z) #elif CORE_IS_YZ - sq(delta_mm.x) + sq(delta_mm.head.y) + sq(delta_mm.head.z) + sq(steps_dist_mm.x) + sq(steps_dist_mm.head.y) + sq(steps_dist_mm.head.z) #else - sq(delta_mm.x) + sq(delta_mm.y) + sq(delta_mm.z) + sq(steps_dist_mm.x) + sq(steps_dist_mm.y) + sq(steps_dist_mm.z) #endif ); @@ -2071,7 +2067,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, #if ENABLED(FILAMENT_WIDTH_SENSOR) if (extruder == FILAMENT_SENSOR_EXTRUDER_NUM) // Only for extruder with filament sensor - filwidth.advance_e(delta_mm.e); + filwidth.advance_e(steps_dist_mm.e); #endif // Calculate and limit speed in mm/sec @@ -2081,7 +2077,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, // Linear axes first with less logic LOOP_XYZ(i) { - current_speed[i] = delta_mm[i] * inverse_secs; + current_speed[i] = steps_dist_mm[i] * inverse_secs; const feedRate_t cs = ABS(current_speed[i]), max_fr = settings.max_feedrate_mm_s[i]; if (cs > max_fr) NOMORE(speed_factor, max_fr / cs); @@ -2090,7 +2086,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, // Limit speed on extruders, if any #if EXTRUDERS { - current_speed.e = delta_mm.e * inverse_secs; + current_speed.e = steps_dist_mm.e * inverse_secs; #if BOTH(MIXING_EXTRUDER, RETRACT_SYNC_MIXING) // Move all mixing extruders at the specified rate if (mixer.get_current_vtool() == MIXER_AUTORETRACT_TOOL) @@ -2308,10 +2304,10 @@ bool Planner::_populate_block(block_t * const block, bool split_move, static xyze_float_t prev_unit_vec; xyze_float_t unit_vec = - #if IS_KINEMATIC && DISABLED(CLASSIC_JERK) - delta_mm_cart + #if HAS_DIST_MM_ARG + cart_dist_mm #else - { delta_mm.x, delta_mm.y, delta_mm.z, delta_mm.e } + { steps_dist_mm.x, steps_dist_mm.y, steps_dist_mm.z, steps_dist_mm.e } #endif ; unit_vec *= inverse_millimeters; @@ -2572,8 +2568,8 @@ void Planner::buffer_sync_block() { * millimeters - the length of the movement, if known */ bool Planner::buffer_segment(const float &a, const float &b, const float &c, const float &e - #if IS_KINEMATIC && DISABLED(CLASSIC_JERK) - , const xyze_float_t &delta_mm_cart + #if HAS_DIST_MM_ARG + , const xyze_float_t &cart_dist_mm #endif , const feedRate_t &fr_mm_s, const uint8_t extruder, const float &millimeters/*=0.0*/ ) { @@ -2651,8 +2647,8 @@ bool Planner::buffer_segment(const float &a, const float &b, const float &c, con #if HAS_POSITION_FLOAT , target_float #endif - #if IS_KINEMATIC && DISABLED(CLASSIC_JERK) - , delta_mm_cart + #if HAS_DIST_MM_ARG + , cart_dist_mm #endif , fr_mm_s, extruder, millimeters ) @@ -2686,17 +2682,17 @@ bool Planner::buffer_line(const float &rx, const float &ry, const float &rz, con #if IS_KINEMATIC #if DISABLED(CLASSIC_JERK) - const xyze_pos_t delta_mm_cart = { + const xyze_pos_t cart_dist_mm = { rx - position_cart.x, ry - position_cart.y, rz - position_cart.z, e - position_cart.e }; #else - const xyz_pos_t delta_mm_cart = { rx - position_cart.x, ry - position_cart.y, rz - position_cart.z }; + const xyz_pos_t cart_dist_mm = { rx - position_cart.x, ry - position_cart.y, rz - position_cart.z }; #endif float mm = millimeters; if (mm == 0.0) - mm = (delta_mm_cart.x != 0.0 || delta_mm_cart.y != 0.0) ? delta_mm_cart.magnitude() : ABS(delta_mm_cart.z); + mm = (cart_dist_mm.x != 0.0 || cart_dist_mm.y != 0.0) ? cart_dist_mm.magnitude() : ABS(cart_dist_mm.z); // Cartesian XYZ to kinematic ABC, stored in global 'delta' inverse_kinematics(machine); @@ -2712,7 +2708,7 @@ bool Planner::buffer_line(const float &rx, const float &ry, const float &rz, con #endif if (buffer_segment(delta.a, delta.b, delta.c, machine.e #if DISABLED(CLASSIC_JERK) - , delta_mm_cart + , cart_dist_mm #endif , feedrate, extruder, mm )) { diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index ae104eb3..24c02c01 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -61,6 +61,10 @@ manual_feedrate_mm_s { _mf.x / 60.0f, _mf.y / 60.0f, _mf.z / 60.0f, _mf.e / 60.0f }; #endif +#if IS_KINEMATIC && DISABLED(CLASSIC_JERK) + #define HAS_DIST_MM_ARG 1 +#endif + enum BlockFlagBit : char { // Recalculate trapezoids on entry junction. For optimization. BLOCK_BIT_RECALCULATE, @@ -588,8 +592,8 @@ class Planner { #if HAS_POSITION_FLOAT , const xyze_pos_t &target_float #endif - #if IS_KINEMATIC && DISABLED(CLASSIC_JERK) - , const xyze_float_t &delta_mm_cart + #if HAS_DIST_MM_ARG + , const xyze_float_t &cart_dist_mm #endif , feedRate_t fr_mm_s, const uint8_t extruder, const float &millimeters=0.0 ); @@ -611,8 +615,8 @@ class Planner { #if HAS_POSITION_FLOAT , const xyze_pos_t &target_float #endif - #if IS_KINEMATIC && DISABLED(CLASSIC_JERK) - , const xyze_float_t &delta_mm_cart + #if HAS_DIST_MM_ARG + , const xyze_float_t &cart_dist_mm #endif , feedRate_t fr_mm_s, const uint8_t extruder, const float &millimeters=0.0 ); @@ -643,21 +647,21 @@ class Planner { * millimeters - the length of the movement, if known */ static bool buffer_segment(const float &a, const float &b, const float &c, const float &e - #if IS_KINEMATIC && DISABLED(CLASSIC_JERK) - , const xyze_float_t &delta_mm_cart + #if HAS_DIST_MM_ARG + , const xyze_float_t &cart_dist_mm #endif , const feedRate_t &fr_mm_s, const uint8_t extruder, const float &millimeters=0.0 ); FORCE_INLINE static bool buffer_segment(abce_pos_t &abce - #if IS_KINEMATIC && DISABLED(CLASSIC_JERK) - , const xyze_float_t &delta_mm_cart + #if HAS_DIST_MM_ARG + , const xyze_float_t &cart_dist_mm #endif , const feedRate_t &fr_mm_s, const uint8_t extruder, const float &millimeters=0.0 ) { return buffer_segment(abce.a, abce.b, abce.c, abce.e - #if IS_KINEMATIC && DISABLED(CLASSIC_JERK) - , delta_mm_cart + #if HAS_DIST_MM_ARG + , cart_dist_mm #endif , fr_mm_s, extruder, millimeters); } diff --git a/Marlin/src/module/printcounter.cpp b/Marlin/src/module/printcounter.cpp index 4b4d4b60..3623c88a 100644 --- a/Marlin/src/module/printcounter.cpp +++ b/Marlin/src/module/printcounter.cpp @@ -35,7 +35,7 @@ Stopwatch print_job_timer; // Global Print Job Timer instance #include "printcounter.h" #include "../MarlinCore.h" -#include "../HAL/shared/persistent_store_api.h" +#include "../HAL/shared/eeprom_api.h" #if HAS_BUZZER && SERVICE_WARNING_BUZZES > 0 #include "../libs/buzzer.h" diff --git a/Marlin/src/module/printcounter.h b/Marlin/src/module/printcounter.h index 261cdf05..39a237cc 100644 --- a/Marlin/src/module/printcounter.h +++ b/Marlin/src/module/printcounter.h @@ -28,7 +28,7 @@ // Print debug messages with M111 S2 //#define DEBUG_PRINTCOUNTER -#if USE_REAL_EEPROM +#if USE_WIRED_EEPROM // round up address to next page boundary (assuming 32 byte pages) #define STATS_EEPROM_ADDRESS 0x40 #else @@ -57,7 +57,7 @@ class PrintCounter: public Stopwatch { private: typedef Stopwatch super; - #if USE_REAL_EEPROM || defined(CPU_32_BIT) + #if USE_WIRED_EEPROM || defined(CPU_32_BIT) typedef uint32_t eeprom_address_t; #else typedef uint16_t eeprom_address_t; diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index 962c2307..6e3f2baa 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -134,12 +134,10 @@ xyz_pos_t Probe::offset; // Initialized by settings.load() LCD_MESSAGEPGM(MSG_MANUAL_DEPLOY_TOUCHMI); ui.return_to_status(); - KEEPALIVE_STATE(PAUSED_FOR_USER); - wait_for_user = true; // LCD click or M108 will clear this #if ENABLED(HOST_PROMPT_SUPPORT) - host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Deploy TouchMI probe."), CONTINUE_STR); + host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Deploy TouchMI"), CONTINUE_STR); #endif - while (wait_for_user) idle(); + wait_for_user_response(); ui.reset_status(); ui.goto_screen(prev_screen); @@ -297,15 +295,13 @@ FORCE_INLINE void probe_specific_action(const bool deploy) { serialprintPGM(ds_str); SERIAL_EOL(); - KEEPALIVE_STATE(PAUSED_FOR_USER); - wait_for_user = true; #if ENABLED(HOST_PROMPT_SUPPORT) host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Stow Probe"), CONTINUE_STR); #endif #if ENABLED(EXTENSIBLE_UI) ExtUI::onUserConfirmRequired_P(PSTR("Stow Probe")); #endif - while (wait_for_user) idle(); + wait_for_user_response(); ui.reset_status(); } while( diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index f16a3af0..4018c758 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -411,7 +411,7 @@ volatile bool Temperature::raw_temps_ready = false; if (target > GHV(BED_MAXTEMP - 10, temp_range[heater].maxtemp - 15)) { SERIAL_ECHOLNPGM(STR_PID_TEMP_TOO_HIGH); #if ENABLED(EXTENSIBLE_UI) - ExtUI::OnPidTuning(ExtUI::result_t::PID_TEMP_TOO_HIGH); + ExtUI::onPidTuning(ExtUI::result_t::PID_TEMP_TOO_HIGH); #endif return; } @@ -527,7 +527,7 @@ volatile bool Temperature::raw_temps_ready = false; if (current_temp > target + MAX_OVERSHOOT_PID_AUTOTUNE) { SERIAL_ECHOLNPGM(STR_PID_TEMP_TOO_HIGH); #if ENABLED(EXTENSIBLE_UI) - ExtUI::OnPidTuning(ExtUI::result_t::PID_TEMP_TOO_HIGH); + ExtUI::onPidTuning(ExtUI::result_t::PID_TEMP_TOO_HIGH); #endif break; } @@ -572,7 +572,7 @@ volatile bool Temperature::raw_temps_ready = false; #endif if (((ms - t1) + (ms - t2)) > (MAX_CYCLE_TIME_PID_AUTOTUNE * 60L * 1000L)) { #if ENABLED(EXTENSIBLE_UI) - ExtUI::OnPidTuning(ExtUI::result_t::PID_TUNING_TIMEOUT); + ExtUI::onPidTuning(ExtUI::result_t::PID_TUNING_TIMEOUT); #endif SERIAL_ECHOLNPGM(STR_PID_TIMEOUT); break; @@ -623,7 +623,7 @@ volatile bool Temperature::raw_temps_ready = false; printerEventLEDs.onPidTuningDone(color); #endif #if ENABLED(EXTENSIBLE_UI) - ExtUI::OnPidTuning(ExtUI::result_t::PID_DONE); + ExtUI::onPidTuning(ExtUI::result_t::PID_DONE); #endif goto EXIT_M303; @@ -637,7 +637,7 @@ volatile bool Temperature::raw_temps_ready = false; printerEventLEDs.onPidTuningDone(color); #endif #if ENABLED(EXTENSIBLE_UI) - ExtUI::OnPidTuning(ExtUI::result_t::PID_DONE); + ExtUI::onPidTuning(ExtUI::result_t::PID_DONE); #endif EXIT_M303: @@ -830,6 +830,9 @@ void Temperature::min_temp_error(const heater_ind_t heater) { } #if HOTENDS + #if ENABLED(PID_DEBUG) + extern bool PID_Debug_Flag; + #endif float Temperature::get_pid_output_hotend(const uint8_t E_NAME) { const uint8_t ee = HOTEND_INDEX; @@ -911,24 +914,15 @@ void Temperature::min_temp_error(const heater_ind_t heater) { #endif // PID_OPENLOOP #if ENABLED(PID_DEBUG) - if (ee == active_extruder) { + if (ee == active_extruder && PID_Debug_Flag) { SERIAL_ECHO_START(); - SERIAL_ECHOPAIR( - STR_PID_DEBUG, ee, - STR_PID_DEBUG_INPUT, temp_hotend[ee].celsius, - STR_PID_DEBUG_OUTPUT, pid_output - ); + SERIAL_ECHOPAIR(STR_PID_DEBUG, ee, STR_PID_DEBUG_INPUT, temp_hotend[ee].celsius, STR_PID_DEBUG_OUTPUT, pid_output); #if DISABLED(PID_OPENLOOP) - { - SERIAL_ECHOPAIR( - STR_PID_DEBUG_PTERM, work_pid[ee].Kp, - STR_PID_DEBUG_ITERM, work_pid[ee].Ki, - STR_PID_DEBUG_DTERM, work_pid[ee].Kd + SERIAL_ECHOPAIR( STR_PID_DEBUG_PTERM, work_pid[ee].Kp, STR_PID_DEBUG_ITERM, work_pid[ee].Ki, STR_PID_DEBUG_DTERM, work_pid[ee].Kd #if ENABLED(PID_EXTRUSION_SCALING) , STR_PID_DEBUG_CTERM, work_pid[ee].Kc #endif ); - } #endif SERIAL_EOL(); } diff --git a/Marlin/src/module/tool_change.cpp b/Marlin/src/module/tool_change.cpp index 0d916699..2471581c 100644 --- a/Marlin/src/module/tool_change.cpp +++ b/Marlin/src/module/tool_change.cpp @@ -856,7 +856,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { } else { #if ENABLED(ADVANCED_PAUSE_FEATURE) - do_pause_e_move(-toolchange_settings.swap_length, MMM_TO_MMS(toolchange_settings.retract_speed)); + unscaled_e_move(-toolchange_settings.swap_length, MMM_TO_MMS(toolchange_settings.retract_speed)); #else current_position.e -= toolchange_settings.swap_length / planner.e_factor[old_tool]; planner.buffer_line(current_position, MMM_TO_MMS(toolchange_settings.retract_speed), old_tool); @@ -991,8 +991,8 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { #if ENABLED(TOOLCHANGE_FILAMENT_SWAP) if (should_swap && !too_cold) { #if ENABLED(ADVANCED_PAUSE_FEATURE) - do_pause_e_move(toolchange_settings.swap_length, MMM_TO_MMS(toolchange_settings.prime_speed)); - do_pause_e_move(toolchange_settings.extra_prime, ADVANCED_PAUSE_PURGE_FEEDRATE); + unscaled_e_move(toolchange_settings.swap_length, MMM_TO_MMS(toolchange_settings.prime_speed)); + unscaled_e_move(toolchange_settings.extra_prime, ADVANCED_PAUSE_PURGE_FEEDRATE); #else current_position.e += toolchange_settings.swap_length / planner.e_factor[new_tool]; planner.buffer_line(current_position, MMM_TO_MMS(toolchange_settings.prime_speed), new_tool); diff --git a/Marlin/src/pins/mega/pins_INTAMSYS40.h b/Marlin/src/pins/mega/pins_INTAMSYS40.h new file mode 100644 index 00000000..c688823d --- /dev/null +++ b/Marlin/src/pins/mega/pins_INTAMSYS40.h @@ -0,0 +1,152 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +/** + * Intamsys Funmat HT V4.0 Mainboard + * 4988 Drivers Tested + * 2208 version exists and may or may not work + */ + +#ifndef __AVR_ATmega2560__ + #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" +#endif + +#define BOARD_INFO_NAME "Intamsys 4.0" + +// +// Servos +// +#define SERVO0_PIN 12 // Uses High Temp Present Jumper Pin + +// +// Limit Switches +// +#define X_STOP_PIN 22 +#define Y_STOP_PIN 26 +#define Z_MIN_PIN 29 +#define Z_MAX_PIN 69 + +#ifndef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN 69 +#endif + +#define FIL_RUNOUT_PIN 10 + +// +// Steppers +// +#define X_STEP_PIN 25 +#define X_DIR_PIN 23 +#define X_ENABLE_PIN 27 // 44 + +#define Y_STEP_PIN 32 // 33 +#define Y_DIR_PIN 33 // 31, 32 +#define Y_ENABLE_PIN 31 // 32 + +#define Z_STEP_PIN 35 // 35 +#define Z_DIR_PIN 36 +#define Z_ENABLE_PIN 34 // 34 + +#define E0_STEP_PIN 42 +#define E0_DIR_PIN 43 +#define E0_ENABLE_PIN 37 + +#define E1_STEP_PIN 49 +#define E1_DIR_PIN 47 +#define E1_ENABLE_PIN 48 + +#define MOTOR_CURRENT_PWM_X_PIN 11 +#define MOTOR_CURRENT_PWM_Y_PIN 44 +#define MOTOR_CURRENT_PWM_Z_PIN 45 +#define MOTOR_CURRENT_PWM_E_PIN 46 + +// Motor current PWM conversion, PWM value = MotorCurrentSetting * 255 / range +#ifndef MOTOR_CURRENT_PWM_RANGE + #define MOTOR_CURRENT_PWM_RANGE 2000 +#endif +#define DEFAULT_PWM_MOTOR_CURRENT { 1300, 1300, 1250 } + +// +// Temperature Sensors +// +#define TEMP_0_PIN 8 // Analog Input D62 +#define TEMP_BED_PIN 10 // Analog Input D64 + +#define TEMP_CHAMBER_PIN 9 // Analog Input D63 + +// +// Heaters / Fans +// +#define HEATER_0_PIN 2 // PWM +#define HEATER_BED_PIN 4 // PWM +#define HEATER_CHAMBER_PIN 3 // PWM +#define FAN_PIN 7 // PWM + +// +// Misc. Functions +// +#define SDSS 53 +#define SD_DETECT_PIN 39 + +#if ENABLED(CASE_LIGHT_ENABLE) + #define CASE_LIGHT_PIN 8 +#endif + +#if ENABLED(PSU_CONTROL) + #define PS_ON_PIN 38 // UPS Module +#endif + +// +// LCD Controller +// + +#define BEEPER_PIN 18 + +#if HAS_SPI_LCD + #define LCD_PINS_RS 20 + #define LCD_PINS_ENABLE 30 + #define LCD_PINS_D4 14 + #define LCD_PINS_D5 21 + #define LCD_PINS_D6 5 + #define LCD_PINS_D7 6 + #define BTN_EN1 40 + #define BTN_EN2 41 + #define BTN_ENC 19 +#endif + +///////////////////// SPARE HEADERS ////////////// + +/** + * + * J25 + * 1 D54 + * 2 D55 + * 3 D56 + * 4 D57 + * 5 D58 + * 6 D59 + * 7 D60 + * 8 D61 + +Hotend High Temp Connected : D12 +*/ diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index b43ba1cb..5de75a1f 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -258,6 +258,8 @@ #include "mega/pins_PICA.h" // ATmega2560 env:mega2560 #elif MB(PICA_REVB) #include "mega/pins_PICAOLD.h" // ATmega2560 env:mega2560 +#elif MB(INTAMSYS40) + #include "mega/pins_INTAMSYS40.h" // ATmega2560 env:mega2560 // // ATmega1281, ATmega2561 diff --git a/Marlin/src/pins/rambo/pins_RAMBO.h b/Marlin/src/pins/rambo/pins_RAMBO.h index 0a443cc1..dec72b8e 100644 --- a/Marlin/src/pins/rambo/pins_RAMBO.h +++ b/Marlin/src/pins/rambo/pins_RAMBO.h @@ -72,6 +72,10 @@ #define Z_MIN_PROBE_PIN 30 #endif +#ifndef FIL_RUNOUT_PIN + #define FIL_RUNOUT_PIN 5 +#endif + // // Steppers // @@ -153,6 +157,13 @@ #define SPINDLE_LASER_ENA_PIN 31 // Pullup! #define SPINDLE_DIR_PIN 32 +// +// SPI for Max6675 or Max31855 Thermocouple +// +#ifndef MAX6675_SS_PIN + #define MAX6675_SS_PIN 32 // SPINDLE_DIR_PIN / STAT_LED_BLUE_PIN +#endif + // // M7/M8/M9 - Coolant Control // diff --git a/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h b/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h index 8fa36865..5176c699 100644 --- a/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h +++ b/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h @@ -21,6 +21,15 @@ */ #pragma once +/** + * Override default LCD timing for Formbot T-Rex 2+ machines. + * The long LCD cables and the routing near electrically noisy stepper motors + * requires a slightly longer setup and hold time on the signals. + */ +#define BOARD_ST7920_DELAY_1 DELAY_NS(200) +#define BOARD_ST7920_DELAY_2 DELAY_NS(200) +#define BOARD_ST7920_DELAY_3 DELAY_NS(200) + /** * Formbot pin assignments */ diff --git a/Marlin/src/pins/ramps/pins_RAMPS.h b/Marlin/src/pins/ramps/pins_RAMPS.h index 05093277..ffe7f7bb 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS.h +++ b/Marlin/src/pins/ramps/pins_RAMPS.h @@ -169,11 +169,11 @@ #define TEMP_BED_PIN 14 // Analog Input #endif +// // SPI for Max6675 or Max31855 Thermocouple -#if DISABLED(SDSUPPORT) - #define MAX6675_SS_PIN 66 // Don't use 53 if using Display/SD card -#else - #define MAX6675_SS_PIN 66 // Don't use 49 (SD_DETECT_PIN) +// +#ifndef MAX6675_SS_PIN + #define MAX6675_SS_PIN 66 // Don't use 53 if using Display/SD card (SDSS) or 49 (SD_DETECT_PIN) #endif // diff --git a/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h b/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h index dcf5ff5a..f32f006e 100644 --- a/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h +++ b/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h @@ -47,43 +47,43 @@ #endif // Labeled pins -#define TRIGORILLA_HEATER_BED_PIN 8 -#define TRIGORILLA_HEATER_0_PIN 10 -#define TRIGORILLA_HEATER_1_PIN 45 // Anycubic Kossel: Unused +#define TG_HEATER_BED_PIN 8 +#define TG_HEATER_0_PIN 10 +#define TG_HEATER_1_PIN 45 // Anycubic Kossel: Unused -#define TRIGORILLA_FAN0_PIN 9 // Anycubic Kossel: Usually the part cooling fan -#define TRIGORILLA_FAN1_PIN 7 // Anycubic Kossel: Unused -#define TRIGORILLA_FAN2_PIN 44 // Anycubic Kossel: Hotend fan +#define TG_FAN0_PIN 9 // Anycubic Kossel: Usually the part cooling fan +#define TG_FAN1_PIN 7 // Anycubic Kossel: Unused +#define TG_FAN2_PIN 44 // Anycubic Kossel: Hotend fan // Remap MOSFET pins to common usages: -#define RAMPS_D10_PIN TRIGORILLA_HEATER_0_PIN // HEATER_0_PIN is always RAMPS_D10_PIN in pins_RAMPS.h +#define RAMPS_D10_PIN TG_HEATER_0_PIN // HEATER_0_PIN is always RAMPS_D10_PIN in pins_RAMPS.h #if HOTENDS > 1 // EEF and EEB - #define RAMPS_D9_PIN TRIGORILLA_HEATER_1_PIN + #define RAMPS_D9_PIN TG_HEATER_1_PIN #if !TEMP_SENSOR_BED // EEF - #define RAMPS_D8_PIN TRIGORILLA_FAN0_PIN + #define RAMPS_D8_PIN TG_FAN0_PIN #else // EEB - #define RAMPS_D8_PINTRIGORILLA_HEATER_BED_PIN - #define FAN_PIN TRIGORILLA_FAN0_PIN // Override pin 4 in pins_RAMPS.h + #define RAMPS_D8_PIN TG_HEATER_BED_PIN + #define FAN_PIN TG_FAN0_PIN // Override pin 4 in pins_RAMPS.h #endif #elif TEMP_SENSOR_BED // EFB (Anycubic Kossel default) - #define RAMPS_D9_PIN TRIGORILLA_FAN0_PIN - #define RAMPS_D8_PINTRIGORILLA_HEATER_BED_PIN + #define RAMPS_D9_PIN TG_FAN0_PIN + #define RAMPS_D8_PIN TG_HEATER_BED_PIN #else // EFF - #define RAMPS_D9_PIN TRIGORILLA_FAN1_PIN - #define RAMPS_D8_PIN TRIGORILLA_FAN0_PIN + #define RAMPS_D9_PIN TG_FAN1_PIN + #define RAMPS_D8_PIN TG_FAN0_PIN #endif #if HOTENDS > 1 || TEMP_SENSOR_BED // EEF, EEB, EFB - #define FAN1_PIN TRIGORILLA_FAN1_PIN + #define FAN1_PIN TG_FAN1_PIN #endif -#define FAN2_PIN TRIGORILLA_FAN2_PIN -#define ORIG_E0_AUTO_FAN_PINTRIGORILLA_FAN2_PIN // Used in Anycubic Kossel example config +#define FAN2_PIN TG_FAN2_PIN +#define ORIG_E0_AUTO_FAN_PIN TG_FAN2_PIN // Used in Anycubic Kossel example config #include "pins_RAMPS.h" diff --git a/Marlin/src/pins/samd/pins_RAMPS_144.h b/Marlin/src/pins/samd/pins_RAMPS_144.h index b7d5172e..f02a8b86 100644 --- a/Marlin/src/pins/samd/pins_RAMPS_144.h +++ b/Marlin/src/pins/samd/pins_RAMPS_144.h @@ -44,8 +44,9 @@ // // EEPROM // -#define E2END 0x7FFF // 32Kb (24lc256) +//#define QSPI_EEPROM // Use AGCM4 onboard QSPI EEPROM (Uses 4K of RAM) #define I2C_EEPROM // EEPROM on I2C-0 +#define E2END 0x7FFF // 32K (24lc256) // // Limit Switches diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h index 2f2881ee..a8c6d30e 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h @@ -178,14 +178,14 @@ //#define E4_HARDWARE_SERIAL Serial1 // Unused servo pins may be repurposed with SoftwareSerialM - //#define X_SERIAL_TX_PIN PF8 // SERVO3_PIN - //#define Y_SERIAL_TX_PIN PF9 // SERVO2_PIN - //#define Z_SERIAL_TX_PIN PA1 // SERVO1_PIN - //#define E0_SERIAL_TX_PIN PC3 // SERVO0_PIN - //#define X_SERIAL_RX_PIN X_SERIAL_TX_PIN - //#define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN - //#define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN - //#define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN + //#define X_SERIAL_TX_PIN PF8 // SERVO3_PIN + //#define Y_SERIAL_TX_PIN PF9 // SERVO2_PIN + //#define Z_SERIAL_TX_PIN PA1 // SERVO1_PIN + //#define E0_SERIAL_TX_PIN PC3 // SERVO0_PIN + //#define X_SERIAL_RX_PIN X_SERIAL_TX_PIN + //#define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN + //#define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN + //#define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN // Reduce baud rate for software serial reliability #if HAS_TMC_SW_SERIAL diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index aadd355a..80e94b88 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -49,7 +49,6 @@ // public: card_flags_t CardReader::flag; -uint8_t CardReader::sdprinting_done_state; char CardReader::filename[FILENAME_LENGTH], CardReader::longFilename[LONG_FILENAME_LENGTH]; int8_t CardReader::autostart_index; @@ -1089,7 +1088,7 @@ void CardReader::fileHasFinished() { presort(); #endif - sdprinting_done_state = 1; + marlin_state = MF_SD_COMPLETE; } } diff --git a/Marlin/src/sd/cardreader.h b/Marlin/src/sd/cardreader.h index 749ece01..955a8b69 100644 --- a/Marlin/src/sd/cardreader.h +++ b/Marlin/src/sd/cardreader.h @@ -49,7 +49,6 @@ typedef struct { class CardReader { public: - static uint8_t sdprinting_done_state; static card_flags_t flag; // Flags (above) static char filename[FILENAME_LENGTH], // DOS 8.3 filename of the selected item longFilename[LONG_FILENAME_LENGTH]; // Long name of the selected item diff --git a/bin/SKR_Mini_E3_v1.2_256K_BLTouch_v3.1.bin b/bin/SKR_Mini_E3_v1.2_256K_BLTouch_v3.1.bin index 91aa46109677e544140b2370b55666a6f4409016..8bc26214841e98d2cd97117cecd50155a2a7bf38 100644 GIT binary patch delta 37086 zcmZ^L3tUu1`~R8U1(usEau2r)(#;$z4hpSf^FV}L(t&q>{U3m`;4>Sa{xPNhU%b%to4R zqQ5cBn7}7EgY*g`N2`s&#&Y9oqfZ#(Qx$R!2%*KCdWD=>Sb0d3^ z4F|VGMkJCdYVX}E{?XY=wOjbLQC&y)U>D(=CATAm-&dc)zfWDgb&x1c%zl+TM(eUy zGVu=X^A-WOOMSD+Q#9)SC&?7L{(dVU;r+TZ;sO17FmFb`AI7L3RjMn8RSqNC%3%?8 zni8!sj(=Fx8dbVjUi4{=isX>uSpKe$(<_pLiaDw^Zq>)}4}c<$A143bkAKC1hHIL< zIKJQE%aNS+09~ImkY(^qP8YI|UeD>pB3=65PipDN{%;1U(1+A;A@5PC{}T+iaKHeC z>b-;e1|%v-{lQa%<|@LwNSSuEmgC=$v=wQ_F8qDeJY+7T{cy;nlv$qZmaTWxm4WeP zx34|S>8o9Y#PL%++Cr}OjDyqu=m6n>yqD!d_A8bRvln4v{O?z$pPvHW{3zcjz5Sl;F0^oB~Uv9dt}=vF{) zH;0VqG~BvKDN!eXD(5o%N!qmAmi2tLTe@l{d)axaqtis5I(Hl`c7p0SNuV< zvCo2XdC()zq0E}Pkdg@ghC7t6_UfyMp;I%*kCoKmaG%8K0!*QNjAz{gtVlb_1CF2?oRz#h?F(YkUr{%DP;$pE15F$v}Sc;}vc?XIN}Tcd4JbUrC&$ zA9!|`HaIzLklort*&L+nWAX`yyntlJ+ku@eq*HXAL+6juV(^|Xg zol+b_o}i11`;&3hUL4c6%F`-jt*#LGNnSIWVwcEZ!FH>GHAOC(VtN}@kZu5|im9hK zK@sGkU59tG4(vds0+r!0by00>!<{h$)}gh5u_izgK!@?+=KQl>7KqtRLDzKkSW;c5`LF^x7nVCS!G=t#!tqa zr_Yx3B1BFp&=Vy|{t=HU)k%x!jS_A6Y1b=qq5o>q>R6!<)1=b$h{G<{Vg@_wI6*S} zH9E0$?4v6>;3DAupr3wJY*3>Ug~3I`F%kWV_5LvCc1@ki*t@6yncmvogS^63cLe{9 z>#jp<^a>Z?He8MRzSNYlwiqT_U(`Rg=p#CZQ6?pR*srBx&DBR|j` zBSu^IcsM)PeY|lTYWOa~N3iI#Idm(7cN>WXIF^46;aX$5kx5|#gQpf7O$fh;@Gj$d zY!${EBMQeEHx^>%1pHrVBF)bgu*oKA(< zTW&5bt9g7e!+hxG>|;xGa>;HukBiuDvApP|@)+_Yb(SXu{wNJI$ARzHR5vmv`5=As#jKi7U`SmMzh74@3vU;AsW=9Ip3WX=Cd=rdk-C0!o$=<_il0PP z#Tk*)Flo$_(!qP0Q)Scu6JgFYvb?5A8adCgP911Q(Xdft$>;RZQArcucO9?qglX!% zp;1j5480HxjT=}F3hY594ZlX@FlDjs--(~nNc4UteWixqDc*79G<=Spb+M4s_JPb# zVt&rJ&gZ9;s<3+_vfNhEOQRxE-*IvETuRT1uCjDCxU}|oIrOY6^GLh&*U-4psY&Bp zCVQ5VO&Fs=wM}lj5w0}M>U@4DzJ*R6Z4d9k7LiQ7Jt#TLI2QvlnI=6D6*g3!&)7op z2u46RTJV6*+CzpF*tNQGfOT@V&v>flpyYJpD5Sk1!x%604#clI%Xm(GplFJ;O2*7; zYMmjqIwNGFXv?E@9=$4#M^{vA-Z+dHS-X8KtvbT#SnKSNs_e+Cylr|l==vf1%WQ7R zEU+7NeGxm}G5xBWO~x3$(9PM{_A~>9cv-Gsft|r~+Tdw`KS#62WRN{{>X@kFwPIik z3B2HFpTNVx(MbCq>eCbO$~Vkd-n%8+d<{A2xh^nOCsT#xYqMw!C5|fJO@d zU6}Xf2VV`)h`(cdoJY4jSRCLL9KI`#Jo?vzpT$4pWs_69eVlHk$s<^N&p|MC&gV?g z{9p9zvDsmh+weiUMZo9N&~e@4hk7^4X~yej0M^Yn9cdOhXClpev}{~!)q7B3(DY z-u0#;&EKK{X$%rAAAeu!mX1UbAgJ-O4HD^dx%Mb#RX(57#h8Nm@9FmO8Ck2*qub}q zml1x($Z6k#|18|oa7~DJ9mZ*M;O|4cnvw}`Dgr;GZ%wE)Jm(pVp%%mc;K`N!uiV;- zhwM3M&n2E5^LSuRc>2kH1I?Y7MBby5C-#f~(X-!Cj%`i0k4wAJ^t~g&thK~j7@y^I z|3pLKTG7wgr;^j9flp7+oN5XwX5mEd37jUL29`&Qu^q%`D9||!M>Ztc5IqU^ST|0a z`65l6)HCz}v1esY0~^sP{0KUB(wfk9Ue5lNk@e>oekZ*-sek`tt{A?r$R&?A$MCDg zYNK-FYL>0YIw?DSMf1nKG5kZWQN=ZY&+?|(M`Ff`;V06mllzmkbo1o0M|*g=w1TFr zG8-C_b=1J-Or-nT*SbXZ#6lj5dJxEjT@ zc(}Ajo9-{pLwFp*Q=9r@x{l$uN|`dA!NxY-C*w^Bk8I*}to>e=ddT=b9yT#=txl6E zo|TuO7(N%2gPKx`8RgTGzBm9rV0LX;q6}MPZ6i$bm=3ZP2$GYci~Zq;fGl!EWHBqm zL!e>}8|^t@564UygDttHSOq@@RG}roGOSdlVkhnxUU0Kh_QhKC;+o7CmFk#7&4&ZH z83i0ynU8P|Cx^!t(DI5P@&TP#u^{SiXMnL-F4bS@g5E6ZuMXD#qet9OiN)c zqkj_=VQmz9+bC9pLZB~99hOn&d&J?>z6H0_@qqDX2bX%@!IqRVG+-v2svoDt0{RJD z{!mID?rU{R3(cG^wql_#H7teJ~N zpNUoLd_?ZFpUUu6>mQa!QIvCPu^+If!Qr7&6KY@U;?fp3`Gk+$G5qhYFsWKnXkT;j z<^0Dji?|rxj&*be5;P#eB#el02p_^q_cb;ynhmGK!UL@8I;;&byhF^#Aq^u5v|HQ8 z*?BQthFPiKw8=?##ZB^b7o@unGt*1XF#bo8(|UzvKBCp|f76<2sWH!qDx(nvo8ijD zA+Vo2L7qaMqz%*J`*m)kq0V>ruu!=Jb zxjk=RC_m6krAPYcszl``%#@;H6Pp@3tqTUTd02Fjji>_beOfj>J-6OT^ntIPy3S>X z?Q+$2+Nt5+5JNT-W7opvpnOQWTpPM>XZ=WH(8g$fwNL%WDs{i%#|wvwX`ELmpmo!` zD+WsRm+9R`-Eo#5*<;DXjxUB+N;yX^h|g4OjXz;eh4yoH9Z^x=)r`Gd9^3uJ@WVwS z?;E4}fxgU&K9&e9oUtC3HW!$kn9X|m=z}v7!w*2DBiAX_3*euE`X7jU1@fm&PQC-Xj-j~drmWtd~uQ0(A z%J1_KZ75$yPdz$6e4@0%$i224V}aALW@x6RmZXAIZ@%$_s76=4EN0p{y?R%^sLGv+ zGks4FmodMIyKhz#mzr8Jy&{yK?Ve=5AXe9Ou}rjRjB!TpWkO^4<8;3z%39|eWv(%H zv3w`0sx`)ZqvGWl{uP{L&x`76wv&(Mc`vrsBcu7to+SQfS3V#PuirWj5;sd+a)CLT ze^aW)09g%8rmVDUT|zcU(fnf`<>r8O)JeE#J{eR53k`&abbXO-g%mu&sKDsT1Mq2( zPxkoj_Fw0}D`00RZ-?4qi<4D=({|z$#b`T$-$m?&e&!Xfc@>C7h@sf=hw@fuIeOY- zNbw)HGFfZxQW**{ZJAj_R?**Prdw4QA>s>cl!!x~^5?W{`MfR1x8_wsZP(rBpO|>I z5PYxtVzD2s#BSJn)F<2&+5R81uwOL)txs*o{?X4L(^CS}Ows(8Sf;NvE6oLBx4g@a zN@x{EVi`V+=`9C5Jy;*Z&T=UM<|}l~tcZv|-K3AIC*PdY;6k%AiYwGUDLcg2tiNHk0;DvF74z)=3$ks%ctKQI%>|)?8!1|ygd~g zE4Of0jX{Bss%F2IOwymteQoDi7C%wj7gP)A-nsGFRc$F#bq2sDb);nai&Uhu$api#P>FMJ zGH8ZV*WB*$CXuV{CPtxqIbAW3!*F-Bd9;|SiRO!F?z~~7FMW32kb%UloyuBwvnS2& z6?S^{pnT6=G1ViOyq7FG@Zaav&P)V!tD6`T5r5ZPF|!Nem#J@Fd_)&H_dnWB=aI0bOpmK<{OgN$~2teTWAgfL2+983a2!#k?n+1 zia6~`aBJ5JD4-c=FAY1l5&nG_NgRAuYt{{qw{#h*YG!+4f;HvsMlLmh_F9lMaDsay z&S%@#FH24 zI}3URkN%Krya)xPM|hrISWp(W&dK(G@%Em&M3gz5<}OT)d_q2dokeY#Rzm}L=!f)) zg}u{WMiuVe*nN&T6XquP1RAM;2Bw!%HPEJo^OCL}_BRFbN?9rE5&k-?Zm0yQhO1Vx zBhOEC@}jKnweFsk2DIZwY*RM6(s5$WX-MXGxNkeUo6}@TwQin8u`WxVFcT41SMRkb z*QLudTeR5Us9JXsG7JYsv(B%LE(o#6>U5+3IyV0)iAZZ7`&4%cRb_d;jl4&}XJsjY z+rAikVBnnemB+LCFZ0F9eZ?)TZ2YS>lz-Q!!1l)_c)bsI4QiT}IBDpl{4}FmcuU+m zG_c7dBs&EMi@!#FkLM1*g!6$W&n^7f;1Q^#Ge)7u*Gmy-hbDJK2{E$sQ#0#r9qL?- zNfhSEN6Zz-m+7cNK<#&!KKDeTmMmy(wO`l$)9Dm|1;T~$nT_=GCo+Q_-aNUz-2zX2 zPxOl$_0h#zPRDwHODI8D)fP6=vcRXhHr#IdugRdh>?2*rz7Yg$B?ea0{ZFVicpKxvofkUiXQ>Z<_OxW z%0No!#HxX$C$&{&liT#`s%c~f?X@H;)O9q7_xmWAFKr0szo2uMrH@1*o$u0kDghQ8X)>K^`ZPr)Ng5e)H+$S$Qhn!LeUF?bVG5%huUK4qt+BC zZdS`{xz-rP*Zb1!DVXM?_}y4cY|ULu{u%T`beP?Q0d3mZA-Y)b_)dgi2E;ouA~1KKRfsdZOg<2ncrDAD_@$-Zvwpn zerII-z2!UdfAY(EIIagX|6TSYH#B*LFV#G zI~SqHf0g$2|Khpqzj^+T(iX|3eY!25A~~O_?fKBtD6QqcI1m4C&NQ^ztmx&X6RLYh z3NF9I=(E2zhnaN7t)dBP?hr5CTAf06(=V#$l22)NP4~Y0oc_ie6-KQ`SmUn15T4}W zbW!}H@^F686N*V;yekyz13P7hm~)Jq#z*ll)0b+76y5IeA5Tt*&$xrXo$xG!Gfc)jng!y|~^za4~6azf3Mybn9rKOK9_VabwX7dTddzpIA( zdv|pyLX9=$=eoe(UXyw*52z+C z!OHQ^)cBnn38Ja{eL}MIq+_&9^nhWPVr8O4Nl!4I?zL}0$fRxwF2E@2u z!M`L{I2Hgh8nvDW--v<^sF{yYVNE4y`t0`#;l2@$#{roHehcA`saXU}ck6zRf8U+& zcmkkNHH!gC1Z0gT$B}odS7$nu<7d|#ytC2z(9fqpQC`#i+-CS`$Y?2iCXw8lwFt%4 ztVdc7X}|V#ahw384>I})eptkmvSs{3Yq`)pLM#tvL_KcOakT{_E<&JFh}!@ijr`4&GUdPy~v%-fF%58B&b! zp1+!RD?=`JDBw204)cV!cP=u0CNR#j{mqi7{z&B4!@5KEJ!^7G#TCpK;w|%cBH;8r_KQ8 z1NX42UaPR$TX>c5$KCn(KkXij{~z1~@&B7U2mfkMU;LMOdgFhsrx*TT^7O?2PER`i zr+B+v^$8D)dW2VcwfJAwu?v zugd?w;os%Fh<}ZAofl)QqKn{_x_;_?F}7{ z1vhFXxVf?zLq-2gj(-s95})96=i0w8&gpsqH=arS=RSYquZ}OUBgY)!X<&QE6)<}0 zM(3@(-@3)gmf)pqv$!z3O5swD)>l+ExP|r3K+`RUTX?~#Hr;@RhE4hv{^-r<(S>l# zY+xT2wU6O`loz)Lu%Ng_F0BlkY?YHs8+O(sa86%Z(K!bHxVEsC>pAp%a;aOG=45v( zvQTC;m+F$R3i~{**Da;Gt|m$NO}<=V1b)qN=Ah&_OSDN4KJ_sg19Sik(ixC?pU%im zh|~XJh*NSf`2E<%FG!~bzaw<@s_x__wXcdI57J|+GI9?&{fy6xT!pe{+3(Nz`!{tp zrx{0!DVj+Bd5@p*g80~hG~-0kAMxd$=;GzrmJSfL_Nd}=gbXxmbxe=b*jI~X!TkOs zI({X%H93MxM;dpIkK`Zr>>Oz_2J>(D91xshAziq-n+it^AANmww}f)%ph|X|8_c)( zNMB{f`DXCR3+88m&ro_{b(D1*^d)1PRmPrXvJYh{H<;5|*|PE%+AH^gr!Ft_NA|^(UVkKza}d*#OF&R=LhMppo98TVU5l@ z6ztn~hU|&7Qz*_(ePAILRpNq;+&_E80lIMH)4nYqfZdmbGhaKt_3ku~ z^)dNak=j%hjp8HNU65L1d1^p3n(4}#eqA^tvegbZZEIgop!i!w>HA87b7_%XbL># zpeX?jmll22m$tLfr~SA##2h7==vk;A-etv*LiJ!P?`S zCN`isgV5Bv5M)TV9M3>O$i~5vwsF8zOsi?&%PYwiy8h)a$N)N)Ua>BA`I-GpaTe5A zR-mvGekrWj*yOSiDc^(R>&nb!B?*>i4~)}xv-GmS_EpjzVK=N1yvwIpH(vXQWiFsU zN*7_4qXm@rDc31?DR#Pr4BVmOZUPeh(i_Bg@fD%upGoYtb`UB$Fr}U(M_hCZFS^cR zj$7mU4gVhlJqgu5D*4iGqS}Y)g$+^GW4MP=VV++N?7(Kl77p64NPYrhdClE0??>?a ze8iZF;#azqZCG4aq-8fJ$=El6O$2r-%=)xQnJeWTiN*0Tf`8c;2Mt&paHH9IykmZj zHr<5{ArmZ&FsxWDBw?l)#2-OD8a!+jV0Gyty^7=8ZbxWwgCnH)D@U;DG!{d4LC01I zHq2uVjm+5xDSiOQ+T#fP_IU}o!>}TThI6Nn>6e1|bq%mPMSN>pd{qP6D4ERk)+>>? zDxGODqMV|%%~DiSgwWq?-_=p#p(t^sTw=~Jw@nc>7{&HKJWl&PR8Wsv-bFLr!79$B zjY1FmT+wkb zDd)!e`FsRP0BwmBZHmP7X_By6D2N2aSx-_wa~wBfco?b57MsgN`!Phw^xjOI%p$H` zoVXADjNOTT3;eHebKx9tSfJ%aTB74^>&a01hpixKnbXgdjy3Z+C)19Mb!v?{4J5^d z#tVBK-JX_i%+>`+oc?!t#~Er@{h{_dA#&yO?92+i$<6Mhme6e*`;v9^$Bo^|aq8Px zOt#bFO*XQLUfL89uuar~a}{-MDh?dxzR&ov19wcc^tE1!u8-4Yuk}#>eN+J@zw0PH z@LEq@K!*tty8#J7OLl5g^aVlp?-X`W&uj6DkjH74%{eh%-(mY_Rha_=4H0MZpaj); zS?~OW&fKgseC5fm+8m%b?G?6reuqu*i}LpDWN#R_z%um|{8i|cpQDn;Y2D`T5o_el zK!iO4nT&Uo10^z(qsitHq2|;HZ;IQvhE6rH2(F3VMkb6@Db|*u-yn{im3`+ zr6er!<-i1Fc*o|$uQ^Ok+X?50W9lfc#0Vujdmb{p9s&2~oZPW5vOIqc$Ot zXII{8SU9uwnPh5t8_nO6p1Ky$-E0fFq7!cKxs1)tBz3!^tMOB8{eN`yz>rSltLRHx z63A4#cT0DxOWG)}@QlMSk)(zElu?#p!o@^&E=u|ol*a~B0RNn4C5A;h^s$NjgRa>6 zG;?gF>|{tOR+?B$P^pkfpgUED6}Z&(k}%lS!$@?@{`xcbW=9fih|dOmbUIO{sP@L% zKcl1H=xa4VPML7bP;(l5w(zko%Z#nhBEAQXSqd|=WIMv_66FK7#D2rhjy$1McZSpOdm1$SyGQ(oM_9*|q5s_B?Twfj*j{2Z4g3~1H7YXf-C(N^>wTfMZuvLi7p*j?jV51Pu z51@3b-a5jiLX7bU=a<#vxr}Ue-MUvwDoL&y6+li0^Vgkv6t>Ula;!ctVgHbKFb-?Z zY`aU?fR(k|S(mU5E34l*m$26TajmK=jK@;K%{pVOMZ^E)8;w+txpP4Mv^!KTa|p^i z&8^|*YorHoXROIX-9Kc^Q)$t*R9I)v-j+l(bj`N$*2Q>*!Ip@8J4_jrL3nTyCU=h6 z;w?w6oufUBN+YxTNyO`p>y9+L!WbyWCW^m0x)=lG@EGx&qk1Iaa#8twxFWb>xKcPx z-Kqm>{-~(fMb?p>K4FWm6RcwuI|KO3k|dN^-HKhoXygaj*zQ;!0x;@&$ro|Vs?ZPP z{kT(&{R8WhnPA#JjY`6*dNpr3tma2y*BoK)S{2EwRoZ5+@GchAu4kEKwz;-KG7H@y z=7UcE@(6yjD=e3*eRk;1Mn9w49HTWR)P(XAy#xa@l>ZA4C35mY_#M>wR=jnI*n#%s_vM<*(WZzLzVney}}+pDDKAAYs03NCV}U(6ovTFQA$y{bBuY!Bvt57WsW8 zRbuSfP{`?d*Tve9l1}`He=VnK$m<1pT4suLc0gk?OQ~m%CPFZ*nB3ZBrorjLC4{)P z*5|`NDebKHr7$@uU1^Y0i0heJU(d8gUy9Bc%2;tQ_9!{x!i1XicFeGAk{U!|@*v=J zq5S9^x%A7<9a2VKG{ zP`}?n-MK^yYM5^8n3;*%`@Sr>$Hb}Fq1NDO2p%{LUo|wcQDclX2Jl`dyMbdC!e2D7 z)_D=lej0WRTqBd=9*A!wx=RHm?@SAy3|u6J(s=CFI%6n}p^v{){7{OdL5VYvzlQgP zshTn%MnnPlMIlXIlS@dD{AOZnE3 zgv;a04yEZ=oD?oP=F?~29T|`;hM2-(JaGQqnj5u;;dlh>kC-vu zq0-B>br4!-{_QsS%dnX#s?Ge~H1n?#p z5N!eR`(9NW@mQJo^$y})AcjphXnTW}g7yt>01EAgcAV&0XI2@zR2{3`Jv6wMUu^~J-8Ub}NsqofVu$jksk>Q8wn>PAmzew5Q_#_L3E`aAQ3-K-?pbp38TUvro7 zPmSyhyPnRt0A_H1`p52?k;`$fU5_R0He4{mo6wi;gYQP1-SVDB{7tw~fX#wq@AnSM zqE{fdqhh0++XUpc)5W-Mp$+d92PYyIPR?Z!4c{}C45Ksm%=kIb>agWb*6@2M*p^tjmVXHR8{L0z5jzzrD{=g;keeC zT$`KwLu2JIuCWD0NUmyaICk;w6TBbsC{krzys2>MI`P5Gx7CJvqE}~Diz70_VbdH9 zLBCCZtQ|&H(4>P={=#x-%vKy6aIjE;Cr;M7q(EkX6^v&J57QlWIx>=;sEa2adZn(6 z1kk=8WW=m>uBvAvyfc)MT-u!Gbeuvv^SkJh4~9VTS^t5aoTukMFj$YdV$D6Ou=o~e zQa)|TQYiHQsr7>@Ov8WZ>TK?nOlW7FQXgvKHsD2{D+~}u`zT;)(Cl<64#2!izsd0@ z>d3>f&dTbx0VQS~RgHQtMfez;4KAsU(+8HsB~PmeGzS*z>B>XlaalN9>nl`PVYx<@ zzKO}kpVMAGXg_37;3?q2U+UKq5>00x8J6Eo+AOZsofWIYRg&UXprx}aXzFJ1sqnL6 zB~d2d5u$;A3i!%@;a>-Sos9RVe;>&vOKJC`j}qg-mySNFR5g8wETqP-hytD9%TE%? z7<%QCMb`EPR~y6m?M}bqaDJ!6Mk;oBB1W-GTd8R{as2pT)+rdxdMBp~=YIz7s7qUo z=frLBXJz;|fd3$;X@@V7c`n1M5)RYOaQ>K_ifcS|@?ZN)zfCp%Rr z%)@fR?J|aIP9V?GAv0T~nJ^hbfZ$P6a}KTXD013&L5s|`!7bOwM%-6la3sLDII zD6t=Il_aw&4CgOMTkAv8pme}Ek_`}Pcgs%mx2NH)MF}4TD;%VynEGF}7(1r7n zqEGnVhkY&=QP;}KE{&`AmpS>1iuVez_Qe|g_(Bi8_<3aiT_O|YKGaLY-^7!~^K#PT zL)#Otkt*r~kXXZC^tC3|>R9r#bp7Ws{c7aY&&jEeA@x}~_0q!j)YICs*5GpKpR6a* z3!g`YPL$JD$Z5Ax^2J10H%|VdCjTm4Lup_`TgI2=GfCWVs!{E-LRM`xR{u`iZ$$>Voi0%!vdZatXigeyrW3b_Y`RaoqsGQeuhjju`Tc5w!B9o?}>EVv3N!5 zK>E?K9;AU@Kepemcmh$Mr(2F^htKU#)Obg3>H-5{pRl&^JiT;$Ao-CdoJh~@?Tst7)|0g_AxRJqnB#yI3;x;CnPk<4!&Zy9eLW-o&AF41^8mgw*JKZm=!+ZtHzWSbi~)M4tqsD8@FBpsrVP6K0mjB9Wf)dDt;vdG{Cw#8)lfp8!3P2SQG3HlohBDJc12pv6HXMq|By~PSxBPjwv+wwS%9-A z;{#_L3FIGvdzku8j>YTfv8Tq97pVQzWY}tjeG~5&;?nSuwAVM2NfLbl@l%q9KTY?3 zlSF*<)HiX#A3%+%;ok%FAZ__({($e1;TL^5?RB_IFi0*({7E<~+ySgP0{lDZgL@F> z5%z-|*xYJbL0|iJ9+W15O;cdmJF_W1*n#;@!=H0%U<>IH_{tV`7zcvxA zk{RkZ$Av#GQ_XTFqW4b+?R>hVxz}J;3}zGEUX;ry%KCe<8}uCE+KYA-aNTD_&FrVY zLO5z5z1l32yY#|;;>dOC{LhlOJ-8zLt*I;e%zk$aT9PxIYdYvq@>}Ve@8ZeJbjNq8 z=|_=tGu$e;_H0WFiTWVoJK)l*hyzkUUK{{ZOFbo}s_|&`r0SD%EvHqVDnx&i8Op za0`YJroBN=5`_6Q^~ceQ{=?|fA5+4f5QCv)=~5L8!y!R1(7itCdk^sxT8>tVIyA>75@RCz*8iPebs%gZF-lOI1Q2@>>(veTwOdWnuh&sE!WN>pvAlJn7{0U$iI)M~4kp8XM3SU(z9G;<8g^x`m)y zD&qSM>s0yyF!S#Z&D32_Z@J~ZZdwLvJRVK!BTM>Ky5>xJc$u88(9@$hjL%2vV*16I zMg6U)dV5GHoY9%&>^?C@54)hAl5|&J2TCv#E`8D+6(Un2+gsC@sbqA zE4)lBkLX9?`zAdgmSrxjES4d+pWT-Z!Ss~*yuB|4o&6&>6jk#3nb-Hl1D8l&`XwHk zrT2b`D^<#Lr(vw~w%4zX>YIIkUrk5(QrpVOCV`m{(K~~Pnu#(4ZWvrXU~Cd#^<}gF zX&QbZA}+(FJTO^Qxyo)!ivsH8E3n)utsv-V?uD4Rs5WfgtsDAwY!I-4bnb;1g-4># zU3ig9q)``(qwdGi^m-FxqmtjIYz5hKbkW7WQQ^ScxCg`7Po)hPv!ZTbTDj50n75{3 ztOrx&rR=_60rS^AmcelUut^Pp@1#zVf#P14FW!h&c0OK+l%V8H{Z-MqW&B4 z8u)#lRpLblQHQ`k0sm*fH^J}z?Dngd2)RWaznaNOn*H0bxSg0F{%9&dTPVGQa3LSVkYsd^__$1om zBr+^OxV>->AY3$*sAJ)?_J}Gc>d!$l7qpk*SJpjuK*6KkFZT=HCl(ZkwkWtRIPCm& zIU)NsabR2g6;aW%b8|LIX|T^Wa>@7OTE#5{`7(}TM&mTer3zuGVOuCJA6 z9DCD!H6i;~UssuD9KP(K=&5dIAK74KBgrvx*+zN8QMNe#8((A_-3hw)YPMlE__Dm8 zfiJ+Vf$M~PUxNQP9Lu{k--|TZ(Jy$J@4mM5OK7QMd~k^`sx3Z@+8x7E|3n(b?`0_5 zW59={w*mGh+-|tRfYs83YjcT~uDMoBT=ev{g19r7qW)}3K-(|#wJthWnm$0Qo}yXT z&AORweApN(M|k{LqSnEm`5?9+4-oZay5)NJC^nY|K2OvefeBx!RBwlWhn~4Ug}g%h z|2`dOzBhkQ2n;|@r<)Ye!+i03G5O_S*dL1sNuewLOdYrr3D`XVQ>DL;Fw2fHbB-tK zXfV8r@DjM&a4X?h)$Tlr;Vq1yzx_ES@N-NPKY;ZNYW{0J9z`AbD?V;1V6QcqP%)3E zKI}jhT%d z)&io=9YxeHj3erKfU&X^RiK;0SD=hHFm<5RyjwwIl_8=&QD8 znL_w)=#-YpWF>8ADeEx`IWoB?!Dsc2hra>wJS-d65Klv#eH^EM1-<`PCFx9e+$tr1 z&^xzAlTT>z-(_)|F!nDu=^^A2U+ZLbzUdj*`C@bT_r%Q6OX&a+r3CSU2;1i{CP3b990$v=o!&z2}Kol+)fHT z+HoFJ@N?*Qw^PFzA11VC50G{EAOL@f2Hxq{%j)ZcOV~VU#-H*n$3wnO*w<$c4+poW z@Uk_OU*J2^!i7~Ehy0ucoQBT7(<^S2FTt$ZQ;36Rf?OJv6nhX~n&KsT=uW?g8|Ye% zO+{kL){h)oC^Z$lo|3!SajcF+Rt-JW$m*$(!{Zt;Uhj^M;qcpQX76j_Du`~)0e`3l zJm|m&@0OATN`xWMdF2ZR;-GVdk>n%VC}fd$Xp5llUgjIIt@%1f6z_4ABrEkT!ew!6 zvBK!LGZyBYWp{lG{B}zC9Kt~H*|5c)pCNw^Tbyg?CTjYv7*8bnhd3;JuqPgvV;F^3 zn!2FHmeK-eR$nHwop7w|tjw%kYT-6QH_5IJe!v!*wc!cCSUbJ}{{-FT?1yq*az@2y z-96-vc(!R4xKDLeAM6g^Q8ZMFA%QeiGLZdrq?B)c(ftl|b?kLwH8`A}L1b>{nGeT4 z=|lmqLJsUxZlstEgFhQ;fNPC23&_h2FLcBeh@WfN)Dc%A{(ZxVM~GUeV>c!qAyu5o zEZFm|)Xqz|OT%5=$w1oQm4NStjCBnO4{?8s^1dQ*X^y61l-NXfxC$bEb-e@VY(OvL zfqfs7TX>IpKwa;83UDY}+IssPTI!C$)@!=Ep#KV&(Xj;OW@Tsf`yKUY@AXWwyB;R$ z)$rNg>L~mZ!-;w<{4?|tc>F<~?gjWZ*=)~v#TQ=s5b6%agfEJA@~Rb&c<2FNA=yPI zd&l65DF?j^`WH!-f900E>Yv;K5xx)ZCzRx8CP{=_rQsIv!8>0z2?Of{vXSoh6+v}) z$2W%5zG5Z|1}<^_-&~`>W$-;*ryvZy!!Ragx6tzyfn>)Fb#6Czse-E1)IGx|DRX4N;O|@sVPN1J=cu zRDMJ9dYHh*$p>~ktg~%Xl9=I-A#bKNXZu*z8(9y%30amS?1Rs4Ynbe3&LwK5AE^X= zE{`J-;&q5K{S=c@)I6I)MFz(o@-hHDv}z;D4fb%0iTWGB z*hf6pVyWMYco$TgebD1on16hN_zZ+k!(R@XCAR(n1bko7ql~MRQRwtzW3#v~}t-|xi zP`e~twF%+mS%0RjADL-e-kHoJ>9&^6WF>LimPC-VBiNhQ2T``UaGJWX5+^<)7?`|4 zd|mUsxQ@GtX9z5|2eGY)9hGBq!oL?Q$W5Wn10#PQm#jc9VAm7sM{RFKl3&PbWQzJ*LKoYxI5O2gWVKQqzuLAhj`ZmNB);6ntYFyA zi&@0v0S9FoTI4O!k9{4);uB`e>NzD$Ci5D*178igF}Cn7BmuJw)4*~3uSXdJr!BV& zW*`*03rWH)i|w^8gne_;78Fk&BE`0u@iO?(^YKLRvo&i;#Gws3^06YLFFs{K@Zm0k z{b?_WAUxQoKsX&=3L$)suZvugTf$%7Tf!z=O$vEIv(yW-lKNW$FAX={5>83B#8lGF zYWL!#rZgoFDOT)k5q9GQ8L%hp>u0Woak%~mMw86oZ^%@t1E?PBoOsef^3DOp{v+tdzq(XL69&yV@h}EWUt4Jpq6^P)E0XIIxD5jn0&vmX zB4paEJxDq^X4};RD^Q^AR1eaB*q<(al`44!GUe!+;&#$Yfc7x9Li3I7&>sK|ZBYld z!g~N-Y;0wH!d7Y^V=~^jhuN$SX7nED^bY7M+qVW174!5x$VnZ@g*KOgq=rs${plz# zZp~u6Eu$xiiz@*=X)A9)OC)J8Tb^x7PxQV%_plq-!7knQ0+6W*uHHuORhA->v@(r! zv3PIPqH7x@*mj~PF=*~ce>g&t6Wj8>A=y+JBqjZ<^p}H;Sk?#w+D7g!jNU#Ny;``- zXc!gXw{0UcNWYoyNdptOS9=?sU0ZY8E*+`zGvx7!%U!bHWx2j8qCO83csEI%tgrf_ zxK*-;V+SU*2y127C;x&im-JPSwAKD-NA(ulS~5sX+-xBK5lz<)(M+-F?t^GX--CXq zBdy6+b{~n#$OW>!8@%3u>a=z3MY_g)2mJpk?J?WPUZ~8Gf1&?r=l!-CpviXIre4@TySNTobwk(vH+Um1N|ClHKC&$^gz}~3P7+YU>{;}vpY0ukc^d_^grETs_rUd@e zxB6$3C82M*LQO4#)s<#!5uUO&W|OG6`#TKl*oOuDOuP_V&n(P-vHg`z;;dD!Xrvh9 z+G3AlUr1=PVbsD3zeNa>lg8sikQyZW8&3;cggn=)_TYOcgYY1Z7bMvhnOX0#kI1l0 z&K-tbM`IJZ{=L?F8P^3oM#N=ZfV#c~2CeUoGwmpC5u#o1BD)Cr`>m~S8-sM)!Q@-{ zg&s4a+=|#iF$9UUt~WsIk=Wy;cG``=)_2gpg4h<@`97q3=^GuuRRAs*Td;vxZGIl_ zFj$@MWnl$=We4?Bh|LzWs|@ul%O9j=$nv0VWM2|tHG4?%64;IUgswh@{6tzjVzFt# ztQMi0%RcJ~5GK1?W<3r+(Ump(G5B5nmC;nNF6qc<3SyZeNuDip{M*YoZj>@Dfw)U2 z#u-TMk}47V6|pIZ-L^^x5Iu|NBt-v`c*MR(Yyx6e|0R@RU>)0$QIYAU;P#Q^(Q-zO zaz>9x3uc!i-B*%*b{YIHrIy(v;D7orK7GOGw){GbHH0-AjD7;6BAL-3U3thRTs3IeN@V8y=w;S+{?xt>MME%<2Z(2HE-1dJip zBNxDLw<%qWFuP3M0H0lw*1|sm_a)p9aBLg)H+=RK!ph!3ux|jl0Z71+u^ZfcIQHo$ zKftRHJ_#4F77u#B>@>nZ!TpI9;R^g4aC^*qO>tE%!ne*n<~_1xg8o&Vov6;Bj_SON z>S%o}g2MCm2(BBxsmM+*pBTCBtg}4h>~Gu(dF*x;8{dTgu5%;)$J_jJNOy9|mXSmB zx+5a{=4bn0Sq|nmJ3i=X1@rH03vx)RITNgwBJqRHCFZ53Y-fz7MJRVxnU}PMhdURW zt4wDmx8Mo$y+daP7#`|iI1LOp+b-phC@bfjRXW>r-O_>wwX=%T&_%|gi&&7wWao@x z3*wt$<2fDiG0uBSI06h;b}%%9;cR>dagyAc_jv}@Peh7Zk@fif7}2N1@#gWS1WUT5 zMaaU}6UPFc;T&roXf8&gkHr2+r1Uxf3rF?+3$);sEo2wuEo~t34u+FuWt7 z1_|%TvG(=~2A*`_)xclD6qJS{m!m(k>s5lT#;#cJeWHUtZq)_>!TKM&zKujU6OL); z`osSo{(pdD8oNP=4}oKPf>QWFKk5gE!#|8Z{vdodSTg6q;Z4wV#MwZ227_WA!q34m z^$GiO_Pt+sePOKw`GezZg3+OZqiqWY z5?#MqDE7O`!z1Qj5(`IyVmZMyBrT5G6tI10ot^xFCWkAfrkU zd_=&AVvE!Npx_sW77)yYS}69bR4S?7=cOtg?7#k6-K$sETD#7<=ML{q@4h>p+x}<$ z7)+gEvKpq>YcD#lh)vF$5p4HbEzf80#POFHVXHH>cl**`$k4xk1i>CdUPa*9{0JQJ zH^%3x-JuU|2t|Z58$xnIvrL_Nt4zoUhn~R)f|?E!1ZLgT2Q=xg;mz^>$f2)J@@xXH zxqXH-ybm=0%<^I_wC~C1`%}38+`3M9h${E>r=@-3>v#zm`}WHMt%Mo=4#oz|i3Z=U zaWf{OkG?F9S*HRSKqip2UQQf9ZT-vZ(-7E8vS`BP#qz^ts7k7Ux_Y1``u+POa>>w7~dGgPJ4r(uJ=V<7iP)+57M zS!e4x(1;I201euQnRJf`_zp>Y)(@gJ3%6$%r@E z>h)euvc7JQ>2=zE1jUR4&KE2;5g^19EsaCuUM|nL~fNmJ{`GZ6J;; ze~DcQWSrwy9hW^}r{67tr!fGlV|2jFx+9_30S8q)_5fU45LTK1^?iwB5^~I&;J2R~ z7u|u_2^lpPvM0nwQvz)?AM!uY!?aO77;uOkjB=YCfzUIS!5SXT0XY2Kc$>}PK?EJE zWwkAEKEYJZ5xp(XWKlG|E&q{4V~fs0!aKg4fJiPtBKm&aHYesj)zQ7dVvo-m?I;?{ znhR81yV1$6I-bO5fiM*J=o39Hy&4x($3kp%u^`dHSyExY3Gr*7b6eees z7g|>s@z3&_66R3}^r>%D9XH%7?P4oaPQU8-7;6iej?ar({jln|yM6+uKgWaX1pSsA zUYxrVB%Bv9ZYnZF=kYiUn{a;EAG51Sm|JYe!sQ^&YOXA)QN3K2)Lhdu8-~ZBGmb4FO!S+*Z3bvP`)0Kq zsv{MLugHkrm$=la2X1uW$b3*gzAT~8Y9EX_mV^Rw%#@Z^GX?%)I(5$B(8h zbWZ*{nvT<4xpxe$wLFSrj@PyHv9yfD*DiVFFZ62oAml$kBcyJBnbrQQK1xm-M+3rR zz2cv+v6{sl?(=qY+aemVuqJsV~8R60QYweqR7P7K@SYJmf$F{Quihw1{c z`E(rKvn?(*@2>NQc@WIc8RqSLz;TLtnzwQuLvwxv;H{g4ons_7Os7LMR`#2Lsrm=x zf*Eufi-$RnU|KU#E_;Obicf20`%H))o|`mRUtetC( zZb~^;PU*@mPdcvTf#(|7L;l+Xv$h}I9&1Xu{VluXK?*d;oM#u`)XBwjD3=5NWDX_M zD*5{y>{eJLqvv9gZkp`DWSqoOX*<-ZC3BI%DRM89NO=iF)H$W!Ji1%_=#)L@QBTZP z&Yg$#l0$MYljr64^C&5{g{xlQR{!wZN_z`dTX-r0nv0MNcxv1ESk-w;TR)%P6r%fc zTK|Rg8iA2NEyD6cnDk#v%WPkGlsxM9z$~7ZS8kb=?MK7UcOUZF(Vc_d`O;#&slP9G zFGg)YEdRckdPN_@Zu-IYKDf9g8Q+kA`XFe&E0J+aFp0WV4p@SjorUuLB~*GJcc=Ih zPI;jyig#R7^Fl!1hH8P}5y9XL#emJadzJdArr8wk?)jnPaHBlzbS{dS`z_o-h?t{2 z^e8gYT!S+Q@|nlzRaz&z6w+?$EiZtGiU#e`rC2nK&4VxQmhS=Ob=oVS+zoE?ynN$v zdZbmWhOeAs(zZA!+2ZmxXLd2iPaR{e(Su~lGHM+@8DHtucpN8TDb@o&(C%GEL#bzX zo>nlT%zABX_Rd+A`c6Yb65k18vv-1dOMNmbaxK2lVfJwQP5ni;JpTl3vW$KK-4vPs zBuN@0X*p`0DpQtIlIsdJl= zUB30byN!vDL1KFtQ#_4{kA}I+9aBDG@H^TVGIQ5980DGnf+BiP5H>E{B~PxP$jrs= zAF%GjdHoTh(!4K!7KL^LG8!(jJ^KFgwcuMLs*UDde~*F zT$BD5-Lw5@WO3w4KJFWb5$LRUVuwc-Qu+f&LsRIx$O0T-ONcChvOv$33eL=)uJ0-W zhezauuZdgJVn}51r3%j46j`;B;(BonFjjUEo6Be)t3cgoGv^{EU&H(vj^3-s1w6R1 z+NtCT>%@m^^#9;jC0dSIMekX5Bc9W==%?{ETaJOxmD#H)E`S3ztmNF))OGY<3}pyB z<=8Q+TJLGR2#o__oYX_c4f5KjVHvp^SE6uB(`erZYFumdZeII7wwADODQi|!e7_%z zc}%`6!|Zq(hbZ`RL=~51R6^TqZ)jY&sh_VER$~;IS*`!oQ2Xp_WXH&%Yv|rK<7*E* zZh^zxT0XGG<7Cc_fk^$(7v$S(sDH%O6XxxEvXnnw8f;CsY`m#oc4~fWDT`X~blU9q z!|RJqb=!TQZ#(_B-3xkD&U}V)0-kk_wGV-DjXe1br46XTjW+}B84%2J{@`@%65D!$ zpAJRGJwT^8Uu;S+-~Cpjzu;yG*Q>5b@S`$i9oB~T$^3QH&aVpD9JN6{w~pGTC2zoh z4(I{&1-=c<&YT~yvd>`f*?`HEnK>GCGB5*}Ex%t!Gb0-6g0{0RPJX~cc)(S+yzg0> zLMEv_OW8%=Hl&WY2eJ4^!$5l<&2i|U5n5qc&= z%y1tva-#8er(ihRZI~MqYsGYbg&yYhX0=%mnFE;o$jCG!nzv6jZ@IDycyob@J2y^X zQz_K%*i41hx)ZK(ipN^5ho0omVlia@?y?rL#_BM~?6 zxB!*NBcIxY-b#Wj+eAHLRTuPYn%+w`mn(*~35jT^t=8SOQr%2b!hfjcT=~lQ{}S>K zjh1x5UCWJ(es8!I7UQo-E2d47hW@E3i41SG14UaQafC!XGb=g|f z>;ds z70}zncWFJ^5K~sICqNUxzgOU*GzXMVB8Q`$0a;(+^T(S?IP^JyWs{=vmc}9ABf%#D z8JpyP9HgD}liYlW<_B|R7Q^}kB7<-IVLH?)-qYJY6us#VceE9QAUWRDR1CoPd7Hd( zn5Grg7%#+N=;lvA4qR{cdRVjLA^Fyj#Fe(mj)Uo9b9-Af0-fXyl$XmY^~@%F?ike0 z3WlFtLmdy_&~ne4EDL~aczySZ0?hrKj;M63hK377pKm(hyeyQLU#EYBp7XXvU2XRu z+{3c`4RnmH@`pE2dJ(ej4N4pQjIm(AtxX#^nO9e(e^(!$m2I!muh*;lart3=)E(1n z;fQWQQxg{oKe=-Ln=~+BKemH&#uv)6H>pFY@1lu(dwWE6oBa7rYFG4hQ#xBgxZE%` zwg*w!;gBr#+J|L_!nClNJ?m7e(p}#6g6A$P@wW3(Z9m96)mK&U#{1^gh_hoS;^aJD zl)&4yB1UYQh)dxT3aa#O^c`&mla;XB-S z!>|}PGx3GdReH3%TuO1{R$ywN11#3M^KA)*iCI*qEU40-a;N1*jj};*;i>$l?tUaB z!Nv+j<5#Rwzr{=37+KAzsL~&Bw}gF$9Cnm!J;xzarUJg6Nj`YatXgE?MWkgk`28rz z){u7t`T>JC%AH4{k1eddpRoar-ExNe+-Ac4>JC!8MY*=`xX;=YG0xLD#we8|7KFr) zk&nHF9gEM(9dA+2gpFLtceqaQt`@Vx)JokSx48!9#7<$od0YjS)$#ubT$Nu~U52bGs|_Sq4M}6Mcf~z)mHK7l z)sHLfiaF#;DAM)y5G@zNy-Kofpu5M?X@;_yAVbRU<%eZ~S^N#E(titiho{&1wcvOj zmRAucdRP8&jOKUw*k!Yaj^LVTD1UFt1J0u<#=}i1KS4iW0L+8shU0i=f7M<;PTvcR zbk?1~9@P=@zzK}e>Kf#zGRmWWlW)F5WwPKMj7f%T;6sVt*UC>)k_cb!wk_RNc;@#^ z;+R$Fk81j9jBF@Tvz60Hft8By&(JjNco_ITMx1Nqg!d^&STeNN-lw00r5KIoDs97u zG(%vB^@FnF z9Cd1arWV_s^18utwZR$3J_cXccW9kHrhzTZ?lKIm=KVlWvCv)CUBNU59uj+%-evmD zRcux$kwdRxMr4_sdkw?me7WHo#ZUgC>YRlR3~FIlTQk@qVRu?vj2sjm%Yzg209K%c~T5g6|eByCxkk8`G1c{f>-t- z?0pg40p1sZY1)zivCM1>l8QQg8>T3LD4;Kp3}hh1slc-`JVew{p$rZcHMC2s4HfH@ zmLpdQwG}WK*tb%s6F|qU(q4=d4Je_V+KbU*5EZR`MyR2BKsGCG(B+aTJ2yf@uF(uDiyQ~8d`uWFGHmx zFaokSK{d$sX)~wwo14!0;T~uKrbK(XaVT#XG~AgS-aj@#Hvg{PVO9b1BY2auJ+(~(L$jsGXDYbsR+)OJtv9eNUJdx6Gnq~77bq5>0-HHl8B>X zZT%$i7{%Xy?Z4VYsME)inQHT3TM9e9t=S$DhlGgPr~Pe;=ud$|FAFsr7503lH*N|>^f@i(ffP8)8Ey8pDzATXuVdI zCl2|GpPh0`f#~CRqSjPy-KTw3Ag-B%Cm}$_5vJOQOT-^RV!2aJxhA5t^G}I$A%Up} zQFi+jwfjEp)eYiNQ4~Omy0<~xf!>z?F8i~a|08oN^`A#TzOhLx^y`b5ns#d)H>0Ll zIO=)YgIh(YB2o{^dD}%xp&pcf-7bDZaV~vHj8g-S!NW!1x^`)g_&|wgeiy)UkLTB- zO`s*fdEmNse7{Hv2sqbdzELW^6#*~7yw$M(_?XZ|tQGvdKMCm5h%6Pj>wf78eB|)6 z+#|oy#5D`s&(O}CKrM;B0G{vs@)@rEo9L;u zUOF1xZs0Od3*fAsV@H{(yi}%rA|~T7%!W_IFbmg~Q`+~Rh>!e)dO&;af_Ot==DtfJ zglL5}<0}zoCa1RI8`0Gdr;AFjhz&GJPQE6h<@l@Onz-haeXoi3;*wD#lIeZ9_L@kc zQtkLP)M)g=F8nCcajTc~yDr)fy8O0DEe#~~^CTSH!cpSA>qxzE5qeNA<6uh_4jab_ zb!=B)oKSzp8iw;Ymab2sMY0zROIu)4ue8->T^B9=10A!_;YNO?&z8^Bh(6&%F*N7J zw`|Y|&fUJ=(&tUm1*ZVH^p+lxl@GN?_RCpriifgc(NmoTh$2U zvB`8Bd3|IL@)r%kzl1jQH`H@^t4=Jmj7&>SO_LA1#b=Z*yVi@=B0WtGuNQaw4J=q_ zwRV@w>&4TWxj~eO@Ew?_c@@|Pya60PzE{~ql&V7tjxqmwwAWtrSG3@ubW^v~ZmC^T)4Qan zX%9v#OFb#%y~;DPb)0!mb!4pv?U7{$)ZFhI`}Xga0ht>uvfm4s3h6Asn38P zrsF|5oF_mz9F~>HszhaeFn3;Gfv@Ah>vBd1WqT2K3l&7nM}1{B70h^id_tPhJeUJu zei&E`KD-%S19K3}i-4`*TY&BXwS)TX^1?t`e^qKg>tLnr=hJudy4{ACzI<+b9e2Qix1ZdyAlC&tMuU zSJ^gjzybOw%aS3pG@~p_g)FccWm#XyI59p7)-(b#&S4)V@M9q3gieu9CMoTP&ViBR z>!a*^u{S6mW&2f-@nd`xtf>StE{GC&HAxv}+XExV)JNILVaPbE3@TSth`6Ft5OIh; z%EfvXvgSDjk?AwY*v=O-4*F}zxN-DR&Oq)vajbn5tm&rLuaC0K*(fXWF)TBgQA0T= zeUxQkkZ}Zkl#?9;S#!$n61_4XWmzg@oFzWWvPx8!n}7f>Q0+_(7;Xbx94vH#=dM|! z1JoV#4&7dRc4I=1(Pw5iW*%%Yz_WeSpUg2Zw*fd|>^=xDS~AQ=_;|jlGYqMKF9O}c zXL!vl>kB>;@I`0{_$+{ngY9#{j|aFOv70>ba{#tu6o6k0aFMe43Gl@LyS4Ej4=VX1 z#g=Sd1{m7rp$6!7IupNWD-Q3+}o*!`vcAc9Q z01rsGx9xNP-fpPrJ_|?ua2Cd(?wo5DU=|#I1~b2`9N^dBziVcH1^jium%d8yH=Efz zz~63Wc7k^UKKG_QXdQexYNP;}r2@Vb1c46&_@&@T#(;0*wP!b#h_Ej}4%7;}M1Xll zGWgB_`(>np?+&nEMg}|R+e|PW^)nM@UkrzU&tiM|b7!SpkuRerK{SQM2!owY2R{bz zJvRy&m*=%-H#~5f9nUgVOTFYZnB20JdcC zsB1sWzN*V3vF7GuusZ>8NwWJyl)_n zo4P2|)d2nujsZ?d>Zx?i9s;)PGogMCT>jjPzX>$}H~@18pbB>U$vg~pWKRME|0X}_sf^O1dMU>g^O*Y-^*;fI C?|Qlb delta 37028 zcmZ^L30zcF`~N+|Hf%ENAObTW3L*ibi3%rl0luFs_Nyr!%6Pp|vMYYidC=_DT$*;RMW$A_eOxwcBlqe=zhDOn2M`}qc! zn9XPM-GtjtuECSPQp+W@LB6(h6Iy7nZ>rA`=kL~T!a-W#+p}PzL)}W$_pAf?EaX`% zdGkShtk5d?C8~IiR`dS+D1IF;i@CCAA(!^=<~+U_csFb+q-5{|5H6>Ce08HZdl2u9 z*c(p21j1J%mn>!=Paa@vAHeRbl<+&MSnVclM zk%OHHd@4_N`fchdJnZz_~Rwn$-0~h;b0%hTUoHF05$iF07@FJ~~L0#$~-hy3zWq=b3ni z^nI6r+QoiZq&p3Ncp1r}8y_|S65PKhLmt?_7xSj~|7Gm{=^pCJVU@#(wsKf#y{1IV zM+*;2THaF^C44Vyc~wF{ag^|_%q6N4{E9iM<+mk93(3HU7GjitKm4oqH(uA|MGO81 zuY_^h@pNPMAXdN+*+S67}`>Pd*1M^;0n8=&Qydn8YooD4g#bUqb50CEWEd6WW0uE%V zYq`Y2zqC(mQ^=&y{Gp-b2pv1LDEC`Om_AA{IlPj+nxljt9b95+rIxR3)Bw5&(0eTb zBfAXuZmlYK@BXt{EstgJQNjy=dp2|3ql5$W^iTtYpHz@aVrf~y?Z9JKhQuu`o6L$XqrgIbnjM@wz&X=s6+d&_i<=Oe3t8HG)-kYlDQ|Zk8G(c+)=$ zqgge)i-vS%E$C_ZS<)s_sdp$z3^A_H3!PFq49Sldjb>Q2MdMAaf5#Lg%t(gl2|=~pQOqwjM$2V(dDbap{R zn)-l}P+^TTP>6DayVNc%oRDf)Bah0?>3sBoLbFtQZ(k)RjCQEOl?DUt`6N#JBxoE$ zexeT-7JtSytpTjEKF8q2$5h3ql2cy7Cys%JLBnH=VaCw9fyKT?|Az}NcjZ#Mo#6zB zt-qmvNwl#)igDOpvvFEKi>a4Ki=VEqUKW?R0m+E5_~|nBZgDalFf5adrn865AkWdC zhv`(Uv*};M;!LcSnjYq~>iPh|$L%4^lsT;|PLxB1Y3*nN38yXb=CqR_64qq>>)qm5dG_$xC85Sd;lh&z0=F=< zA_Rq$-n*DNL+=pvN@$us(dZVZyOWGw_m?hy0(Cu1bBiO%bULnh0MXNp#gYAtt~Oa{ zb%jVTaT_49of3ojTTH1;VmXl5*mf*G-9TUspy!HXRdy$J7WXivb|xhuDahTYBtY{8Fv;lMviPTy(Cx!}W}e*Oq5ciR zxeRv?&KvzE67FU6nNQ#+!)3zFgIf*v8nq423jWaf2CB)W-fGtIp5T2Q%`wE}Tt+%U zm49vGn$9AeUGHBKh+h4p{C77>;e88qG`h_8s^rR;d z?yiKp((sa=DN`hsvbOo@{dtG@o6-plmSjvnkF=+FDJjS4w377jR)u<2J9WPVM&C+z zmc)BsUg)8|{S^J7L>qj>@w!rlo6TAstHKT{m!yR5aIp4EwXg}^Pl3Nc2aOmvV__#; z0^A$;V-HJ>`!P@tz=u7i?eV& z%lYxB?<|B5@tIi1qlBpp-lGibc9ifq!nJ$~&tx*5!IO%4J;I|A-pQZC4x^k8Ega8p zDvT1A+6N$IvAvA|ZhO-9%2!jEW?=^z^8B-!1lGhG@`zg_5$!to3#;P*Q_Z4e$~` zX=+RVVph$87+~k66B~*Z;mrjtPmaMyQbU=645j8WUH?p5j3KJxl;l})TH-WJ8hz|3 zpxx8v$!m}jYRKSOSv~C84S0T?K^ zFs&C@{PY^3RAS2t8w_29#3qvHrN?wG%#rR}vm3ug&$>{^X+7t8sK3Xgns!6T?>@p4 zn?9n*%|O2x9hx-L!8LH*dslQ*q%+>3wZtf)Vn@cI4(XRt+vueDZVtUAlV{UMB(SzC zZ5QH5##AiicM*q*D5Kqn%m|}t&RtUJ8ZJR z3ez^L{vws5E2_3^8b)~5ZmaBT4{ zEqXpuP&+v@+XJV8i4{r(3oH!obhN>f0e_l?j!h$P(fqOD#m`ET& z+4IwNL2R}}`i<#K_XXq`B|Qrw^45D{pD2{N#qso=v6&jSCSpZLqxk?&cF_xC-|!hM z{Ri7>4PE|dv5zc{BKdi>F^VivjC>=a`euX|qa635GH&|B(lYxEI6!HAxSlb6+?$j<<+|yBMaa{TXQ6E-^312{-9^aL$5xCy4^hkb^q}wC)BSW=NZ(Iyk5B4W+YT$z^#JS*cM|g4l~R%C zwvA?#Ka})RXQogfEO2vaQB9=pmD4tEW~Sc??ibmb`i%T8^@z(BT>TZlhQ>~aC-Z5}g#IyGT>Gq}uo=mcx#U~TC#i zC8tXU9l^~dA8!sQX5mY&V>pH6BUM0)v27LwLuWA_*_dQw^n18PJvi-^m#BL}@4zUj zcV%`X8`9l{5ZZs@`oKrroaI}db?8W84*hZBfC1|r5rR$T63Pvc!U(CF_t>5)QidrjQi!MdlLnAcblIfR8Mj4Hu`b%hKsQUpifN1xR4@!VX2(AzFHDX2C@3Y%T0 z8hn&K+(j5fGanz5P>U*m0e1oJFs7ti@E=_G9P{XhkH2VIWX~?H2AjRX+KlFhi}Mif zhVYc;0hq5Ng{k%oC7r>>H9w@J2OwP5%;{MBJ!T~q7{{|vAKOZ*jBu!6-->XE`B<#c|b7QMLU%1hWM9cVe|!%Z*XxXOHlvpFR^ zu7GA#_>rY_P{o4q12!MNSmA1(Q)|&Hp~>`%iumBIwtO^dIeKCjc?!h-I&G~;88gbc z;ZQ!BK2k6^SMU{wGDhh66r?V)MF>}1Of7&0bhi1A%aOwO(oADvEyI5j7(cgTENI6V z0gOX*?v!C^OXR6mS^F;B4(lWQZ&ohpoRzI9@$+$jhx6>uX|aNS0hb>_FHY%a`rQ7M zfzw4*JY|SAo|L$1R)$@guL$TZ2WOdEGFNF8L7Jnq)qV$CMR(N9#j4N5dPSP5blNov zeC@_3lu>kAno{hA)Xkvq_y|2}U+dtKpJ|rG&zzCMUPq9<+OE>R=@3Qi@ZSCW1yOg593h31* zCdFTqHY?MepY9>dOeR~9utnmuZt*#pXf-&%PI)pZa=7Hl^I&YcBLnA&{?1rs3dyBg zpNxsl#26ilG?b9M5lqKAHA-p{ZFw@%#QFs53myHS0)l-S?!ghl1YHQ2YBLiOCzT3I z%OVADo9AYa4O)y_QEr2{q*Wy=`9PtktTTFGEUvTHjHt9sF|zuvwCgP?$_RbVuC>fG zdLn&^eH5KBby)8;_H7nU>o4@RV;d^?N>fX@RWyBCO3rc{N%Vd5_zf;AXs4sL%MOk3 zgcPua@ZAbm05idUr8aQGj)pScZ&QRYLRSB=R^5O2(ZZopGUpcO)7Pi-AX zJ-Ei}(#k|(IR-V>UEOskPi|v2--R5ME}o%_TI@knWslI4@P#bTv*eYWQfLdzH{g;YIq2G2FC79&M=MyBdF%JgYT)KCgN; zQYe?ymUEK2nr-DHgiqYqTbD%$J6!R?+m3udcDcPaaFBSAol7V%L>5^_&b z-?c3vP?7hKz zr_YW+VKMX%Q*5jP97J(Nj<7J1T#(bz&)nj5w+gY-av-++fkJ_86nfesimd`9ACG@MADW-!MA-k1PBIQ2o&1u>4xkHI>%d3RC@4VYPF78Yr=w6efupzC) zcDUfMEZ&yb0RXeGSA;-iwFMhUFK+WN?N@vds4c+e~eLZ^%E!mCVq1hS6R=ROktpA69!)e2;L^6S%o7KNx zu6)W8ft4Ua$dLD2!VTRjf(@t8?^0Z$n8+CXSr=PJFi>1U#Sy|{G|rQ>cy_Mp(tP^D z?17;lIN5$StFG-t8LfAUgXyocM|AlSg`bCGlf$0bw9lNOStAtG7)ug1R!;Gn66@G| zYV|fTM}f?4Clw2v6ZE4wJ;{gk$2s|g(BQeDWDHH3o7HcFa$JqE6zOt-wWyPlXNy;B z1{uKSzV-txiyy1)2dpXdrMWR##`c^^x>UeQI&(60MiTOkSJDmOp%Mq-1mFy$XXf^d z36Qwj9#S~ESEC~ma_HiWFpQCsG!cR?jh#1)c+qL|at9r8Xs58&-Qr5N;K=Px1m=8a z#S|CRE*FhD(BJFU&Wrh=1s=nAsKa9rXOXm{32Z^gr5<=V2&)I}MyaC^oRt zLmdpqgc%OMV^7JpW6^Zl{C++a?!J`~(6w!!KY~0=Z_h6aP6ytK7d_Oe@Q1>Up=Fi1 zrd;J*a0n%2qkbVM;g?TY19luy0?-a=3J#b0BUA^zz&K+67RNNMiIv{Hh|`V(wGOqw z$50J)aKjF6M400saYN2%4La!Gx(@YhVS8eNHRb&#E-97!~fV&##qfhloegai^aM^kd zaVE@}@Cg)D-yLRZs-uVL{-@@}|8mea?=Y3+YZ7Z2U(FEx3p02 z4Grc4G?{J@(kv(#QCO00T(@6q9KeSQ|B+8fo*U*FRU0xfVTKEr5LZ|4F?wuB!ORve z{3Z|JJvUr1h6^W=qS@fpj`ss%Vbv+T_XdXb4Uy@qi@wxZP*qmu`zU)fe8x)&+_-13 z2S(a4x_EKsfO&G1(pQ|~Gfg*Z1BF?#3fmtCj`mM<^J{)GZsO31`N_Ofd{x>u)VJ9s zjM&A=n|=2$A_cGH`qhb4xc+iO9;=-Pc5vsbt+*sdP#g- zIb*IwxlBnFfK%)JCOZA;IBg5qVy*VZhQB-APk^0<3l#2sM&Exr!~a)zp3>e<@d7>n zbpPm~pIxZsbgTzB#K8!Awuc|4>Cfm!C%MrRQJ;%)CT2N?Aj_uE-_M3@pC$Y9b7ojv z;!hImbOd7BgKpji$gp%51I7E5QCu49|G zPFc&fX!PZBvZXtw`EX$#787$zx01gHeXcGBLhseCtj*O$fyP%#tZh;-=t7a+wLRT{ zVdN0&Tp{2|BL(9>Q2Fp2x9O2(y3}GNo#`prG{qF0sg2o<502QepjZr-LxZ1< zj_KJ>uUw($uh26p^d6^0&+1Zr|BK!qhyO2n8$r+7zDzu((EHBG_)Avk#nB_6cT7ot zkiT93C%xe1(cM03r&pxVTd&Z&?q>D<-AVc7+SGObMR4~2NpR!xB;rR8EYHOuOk7@s z4wLg-ipjUVi1E50i0h`KUeas2fbCZmZF0vt>jTI=Wq$8q-V@lr9O{_gJLYmDM4Me7 zUgE|7-BHSw_2Q(GJH}G3l+(~r4!!zZXwv8ZMfu(Trc7f^(WdR~R31~PtnQ#9_WCbw zU;Hnc^ZuLW|KPSr;dX9&IYml2WgX?vdQ)i9`2V6j@V_b3n~0~DzWlg1I5ZV zB6VoK>lrrF~+9$ZVoz&8^C6-vm`a<^p|>q$>wfNx+&X1F5r60%{`PS zoTwo}A7}GLP9XAMR+lKb?^=oAlAz{E*o__RpVp5JK?!#2N1*r&=wGVg?tV~Rg3#_7 z{n=>vFV)1I4THbDCh%-9{HJR?QC{sSPWa7r+!~U)rv=wQ(ot&!(iYTwerJxUCKAE< zHBqVCS_tkr4_V`sYyoFu;LicdjGAr;&8mq_eFYdlyFa$-5I5HNoQ+rD+SHYRUv|H3 z?S=TX8bhk--m-l}_)>n|IvbEVHK}JGN&Tuhr3C9yKvGb|7Wh6jpCQGu zmoXS_JqAd8&3Ay@+3OZ_9Rb#JfFyz55Ab7ZOrPJ0sQDSe=$f-Yx&S0Er~O*p{f%HF zs>b*1C8Pz{)ZKs4WV+X~R~CPe{y^#*NDZjTyOS0|hnnskK`yoHJm3z%!)uDp*4;mj z(BbMRgpMNQtoAvZcPCxJ-V4@hq@&mJ?raR9B||x(wYu*9F_3?EFA<)X4ui}u$ns~k zKQjM>(3R@EJ0B=nH=>~bNV|Yx2mE)y?ug62uk9BT^xt?s@P zm`AHWzw;F!9ta;nt^o;*?F!_|bS?!oqiJ9>D{TtW4p&@kN_h4fO_EHHXiq4^0? ztV&7&QV!cDU2}`?xF5Slg!i4}@NaQGa*ddT{mwE(_Blu5|0kyb{}-Kl{3pAL@ITEp z6#td3T>O9M8jSx_t^xS(=YIH_EIuV=Aw1cgf&U738vfV2d*Q#?om5%bNQ5Xk@fy2% z*P`fOT(S5+=jw|8ORh-3&GxWsCJ>i{L8@Nra!n;<86LqfXmDWRwtT##wS*UsLa0C8 zzAm!YMeJFnQh(vlA)P=$t=Z}~qKw~B9wy9l?I_dp{=#nA3c>xffL>bH!_y`9m1w{V zJz^)?23NAHQhz~~Nk5OYb1iJY>@PeGIwNW63*n|c&_#@E@#K3O$X@U?D%Fs}c;mu^ z2v-Ue*}M{lC6c8lRK;OJqnzE4WVrk&m-=;+S1VV9^ihw(#X*@GCLEMCb+Jllr+nQ) z`g-*KsfBE2+P?#`YBPafCwpvG!QUtQ3#krn0(MtwAx+M^Lv>TNzCxjtcjr?Uy5JO_ zmI5K}5%^aN!{ub%QLS=)mFFvD9`xET;CRdKIjY)}HP91p%V&xk)l(koU(iSHEucfz z4i6;@ z(|&h^g>6k=R62NDRdg8NqWCXo+ijqZXKe3trdLXhq{mU~@Y;V{O^N5NdWeOw>$B)@ zQTYpD2bscQl-4Qwx-%^4hA3kc?sGYvPS}c5$QZy~u4W64;zo9#qB8N}e29%0`U+ao zr@5#%X`a^meha5dsf;peh3oF#mD=Jk;Rgqt%aacfM0*)XY;(mJeE2A%U?DoSuoGIp zsFBelaH&|`r;;S}stmJ4VBgfOFtzGEOLt2s!Z9&iYM0*};&(XvYlXw^pP__pv2y9A zi!B5A0QA1|&a>9YhHPFfXk5$!Z4FLoY%|!Y3}~ODUPO)A+~tp2d!ZJ|mJOJDLM=Fe z3e%vUPz%CgCK*jVtLs{q#^Mw=y13e}YYA*K9JqpIT`&d`KhdbyI@RJcE+bH?>48^b zlcu>wAv_Q0Tyn%2IeAButo^(;zz{WdD2P4k8jsY;)b>hDY8;CHtskd71$P3jt+;`% zO~5E{t*T`WkmagEY%tB;5MDC3vGm@GMSob?`S_ldRlO#ruoSZ=VVReu&ISzP#tL+)R3pz zsa4EuWbv7UTH&ONX}zymJEWNh_CxC*Lor8T6Va#HDQkEDJreM-pYZN@NRjcr?nLyU24H$GI74)H37a4pyC zVa(vY(SdK-vM#VD*??T%v?QZXgbEd=J}nNBxO4_x$!24BV;uIC?u zeJ`+$$hnNxycTZqbZ8H;+sshmqO96buAOR}Yjlb>`vus*XaW62_SoRDQ?Ir%oK`J4UA zTCNW+(Gy6b$4+(&qcTA=zXx|9o>&Lw1AS17YAd^V3ls7X%WLU@bsBZN>qhFSp z?#54ex)HXZ&?c^FkI$n)Z^W4595anP80hNQZY(M(LMZ$ntPBM!D->3^)Vb~2ogv^S z>fm_o3CtKXj31&sB4PEzC67k0zGm-_`^YdHc9Ja*;}Shg*ur))E!SY#;1EBuU(@x0 z|DK)wKWgVpN#&@DWIKp)d(57qWPQoT)@7FUIh*m&H661TS&xjYw?1!Y{{!t@5*tcq zZ4&bBvFmW_940J4zIfa@hY3&EHZ{x_LP;!ep~2OM=^WxL=uM@9FhF8HB}rddkMdtw zOL>}Xj>=&&+yI#|Wipc+voq^h3USH!6}xDB2kEtNISdaDE3>jXe@mB}H^RI+Xj4J_ zHk+3|1&iel8&hU1v1$42M$+AZEzEi3SVk9Y%2M65(GNGpkuCJdrhepi>e$qi?4^mD zi^)1Vce6Rh1hp8%y5U!d*5|h`ioAY;5=_#8+?zE1&0^m)=R^GG)-J*{y5P-p)t`&# zyKnYVdo`+{E)Q&^C*JI>OX;-6VRs1uXg+Pb%FGX1beq^fbz5RoXBW{STe2gs$OkQ7 zRb>qFO$|Mr2X*3K&{)~U%k-r!I{*Eytg0X8`s+#NU*bSTjgn>YS71I0EQ9906-(CBNpD4_zbMZpLbHQQ+tNak-m`Y&zl4S0uhw1|igC=GFZqdPt|y5(R;#m+ z0mo{eoH#kpW`&_X=nSJRTYH)=+BYfdIfJB0Bst(zT4|adO8)AcO1tI_G)insS3yC%G znO!bxx6$J25@49b_xIx}KT) z#`t)j^f8>Nim_;fSq{56wN2Hm^${F&>pQXj-pYjpc141f9(l(QoGS+#P+KULU{$UU z5<;nN+cUn4u?tY=vCIGM+frh$HLx{-sr%V%&*rX^;DBK94HmMgbz7pT#Nmk;%M&a- z+kmGeO{^|$`;7RKgsRa#mzf-W-&DGc+!M&&^57qsY z5uZ#qZ%-nR(x&b4qzgU2z1*}IFBI5RoNvKG;o*nJ7(q&-&6Ms~b1WR~#e49~wk1xe zkZxF$Eh^quiIq#2tX+8@B|JttYppILTq`PnAI=8nVuE;@*|4qMuNFR)R6EHAvO^ZP z%3WXrs@mZrT(aB6H72KOr$1WoWi}Q&7Y-kcn{wr{iLD!67@v1+>irr;V|@jLJ7zVz zSlgf$rXN%bqYh@*hZ?$7g$Zg;ZHrsngoUfy877%Cj%|?4ZfAg@&gMNT6t*NmIb7}P zp*xzqc(ox?%g5FP3gvEsffOkGfky<{c>%%)bi{ixrrCC{xc&-}y$)|ayJ0lQ?Zlv9 z=d=J}?LpZ8Il~PRr63IDnH)qlsab2Q;4SG+zXI#{oK*;H9$A#K} zk}h}*@SwcZkk_Yt5QQ0wG(iZTC2gPy!5g9AdFDEI3`D z(D#tKK2RBM;U^f`5XX3=Uv`8FKij$5h1eM{)Os7DAe{y!57Ds_U=j0vwCN5rx~+4F zUjn|70%Lac#!0@$0!<5$-K7!N6?wy!n>{pGf zy^f+IoW$)t*Tkf{8v^x0uMC4z*C%0+P4MtM+1;@D+3p5kI`f0lU^DQ;FyJUQQy~~| zuh3&36hHpBU4vT808eZO>Dioyrr2xuz_=+u8KuaR*X$6-*}ZGWB0kKH9*{hsxqJH{ zHXyw}XbuBSHi!%C9fO!jD8o)GKkQM^&5=`yX9_m1HUtU-)t(~knG^Y^aM_m3cM(!; z2drK_nyifccd#PH5vco*)_8$9u2?YpkplF=LIKVE=r#$ax*etD zN4j7~nrW|_z=k?hcuQiB#tw|QQd^F$@)EOI$K1>|0SP z^yFj=gxR zQ$)?7v`?ibrL^%V?L!Bnx`hVsF81$+QrvD9UqGkr9!H93FYs26etDj-#{Vl5w{6}c>HO= zY@0Tv^e=f~!pt{^2DV%_PBA7djV?S^n}uExEW9IKHbxa*fYDE7Bd&mrR{`rq`|p39 zOrpp4Pb2+kmL)BCi{!D1slu*%Xh&Hz|<(|Lx*ZV zI8NMb{S*8OaE$l&QCB_qW_37>@IweMgEP=$2NI*xagI%_@Wd+HR?}6$sPyKvo9es{ zrm8%dZ3g|lA-8Vfrv^g8Xw#u#uqgI998dCSPyA=lVTZFw6I&nPsX#Yzz@ zG$IvNMaac99smCO9N_d&3ZAB9-YaP<{w6rV<_Tshl#JVH*;k=~1_d%ofo!A;z6v!B zQXn`)gLsXSn``1=6|1ff7Sa@&Pov23ZF|jHFX7l>mZDWsW+G*QlJYrHMk^_yHgA*} zrO+!!`V=L-8tHQmGlp4iV)FrxHxtrGNQnp9$WAikFxS*3EoK83ES$4%YY4z89bI3s zii33Q#s(%|EnvyW>xaBp=TXEmTK09M=@{^Wg%C-``v~^-Ikdiw(mwn625*Iur=;3d zfaQt3b{y(bq010l5wK%B+(E|TM-mg=Zd6kv+{A0Va|)%SLpx}#vsX0ufR;x1U2dbL z)iG+PT`CjEsr0Rw2_7V9QV6b62p$2!GYY|_g&hQ^v@@p>{?$&9k$cSjznCjmXg#jb zdZ&{)ZGL5afT3#@oql9E*+(r$YD`z~{6_-?c&SjD&t& zF~E5{-y8753eMX|3x-+cR;hP}cZ>)1+fr}iI2FbAoNAznXLN}STP;wqK(E3Mt)d%E zYsYij4Ox5w-ezT+aGEm7p3J1aX2C$BPP-xJ`{3Dm93KeuSLLK)_V$&LItyFRHWs%$ zz+yf235><%attur82tvAZHyWpV07C9j3%#DQH{c;Zi*a;jQ>)K*yV2Hc0xP1+rjNF zTJ}whX=5jAV2kfw9ET#YUV^PPoop37z}94249vnAW6vpA3p-f~dw`{q2U#+zXpkYW zn8|LclBc|#8(*39RD@RwcFJuJ2oJLR)!imLHXd6B(vYLQh?V9X-RE_`oTyjR)}vX$ z(F2GYuebGGVP1>5s%bUtcWe+jNf#VT$;og>8lpyS#u3Zpw%~t}D;#$&Sk|QRmN4A6 z1mlf&hDFD#w6L+Vs}c`Xq*kU@J!$EJH^Terug3dV3a8 zlVTNCn)jP(5HIeGztyxE@h3auuQgc^U)~vivFRk@!F@aOuWGu1_}I?)vrWFh{h%|x zs3`^UR>Ujo+2hzOI_SGp@;#mLT~fqFG?<5h=^CPVTpm`);C-d>pglI$jQaiq{X5 zbQ7@-UWPtng5mfL)idX%i5m&!ba+e0X)s-BV3x7+he>!fe({GGukY*{;b%&Ij3+Lt z`!U-86R0OO!cIUfwCKnA1J|zfP#?jHeFN?ydl!dzI$Rdqeynf1;BSXSb|d^g!WM)% z?&whG3VQ3ud1Nx3)I6D_)5hi)f2d(W`Zt?KxI`~EPr~Ay-!iV>7tnQGY9?9_p%z~P z@Ss{4ZLg|UQJo`S6%cFNBo{KY^z@Fywe9XVhU&#ygnk5doz6rQMm0Q%Q($KYaz5!OS|4@Ge&UGnP~)m5JU@N4&=mnDDL?su*7 zhtZBGPNU>he99{5o7g*-Z_rnAl#Fhzx3F93+}^^P!zu&OMHxk0K^C7{412t$Q@P|* zDxZo@BF?rRJGs5bR-(slM$-quM1j)<342@`_Ez$ALH{K-F7ZgKig0w;a1Xu_ZSgfU zd{*@K{Pw(DXWm35Zzb|p(F3Pr{oey-Uq#BV(etNMf=4LnLtVX!gM?gQ4WrS&EgX=w z>hE?uike)37;4a~k0Jag!sk%4FAzVG1WChOmgDS&8Imlg(j&jEBo<(1bf9s&m3x%CD2K$0CCd{HbD9((Dv2t`dod?s8e zTr6B3Tu1j}f|ijl6fh6r4SM@rVk{PSl(l_tF*<9Mi*GM&^WMb}(bF{j_tKP+3dVbT zVbAZ!I@4fVhT*sruuVnNVckz?wlPSM>_GxYKl(j>KraRR{k`2m?=vS9YRX%dxAw+> zUNiEVip=_)$zVphMSNV)ky%40}*#2%wm@?!H0s|p4I2Q7b>HW=xJwCQ4T zpV|kSFuatgKSDeW{&o11;C~K(G5nX|7r{TX>b-%N2odO@%Lei-eg5(=_WIy*Bwngp zFOOwUEU%=I@pSf;XnzAHl-zp*_jw8l^pz`_xm{O#sCz=L)gUFpb@UuH;H~*Y{XJkz zwqKx_Di#LrCis>0Yxb*H8(!(}zgsFO4s2C%U2&MozZ&bmNgC81r*tObtEBYyxQTAO zs`H;Gb#IT)q>V^_Op0%hkEK_yPDo#hvYD~;+wdFU*1_$Ey8!nV9OLmN_-#DE3h`Qh z|9f&9&1m5^wOot!zaV#0XhsWX=xM~im&4lQ-%w)BN{vT;Rz^1bU2wT@U&0l@eFVqK zXruo-oowyz|E&B_d;VwWc5Au+a5=m^UPQgF4@=sHJdED27;)dV=QqF~1NS)G9k}Uq z!S%T$j-J0>Ol&meMgjSi&b<*yzN4#e7<92~{+7Nc!d~Nu`Xq9NKZ*^TQTer?X6gnPdDG186RL{icU5$oZ72R#A|A9dkjazhYv~o zH}Ekz-j2^%1dbTTFTw8t=bA;-H!F$yMj25L7*Es*fHBTnC!?#w{}p)?W8Ow_?yU84hk~-?U0KNKD#BA#jllf z5-dAPs|~C7;}*o?FZ@8q2sEWDW{z*rAl;phE4BEdS+U@GMI{6x<(FnIajgW~EMNz< z4kFj7p*5HEpzB-XeGkgjmP~zs@I9?-okUjC;5((gyq|AtrJqqUtM8BSUqh?qVPUwA z_*ul+hh?r#rZ3#7g!#VX&IodY7T+C%{;~CLDQtmm-i>72zk3sMfx_NY310ZNdl|6lz> z|3vp{YA%wxZ~M%ug{o8~=;+wLvZ7fXiK2jdyouFQrG&>frP1wwjS1ajU~gBVD~N9W zes3r%T;eF|FODGbv|P-^1Axt9DkOPCEF+)ONGX$iM2n@wo@MgL?JYMrqT0n#lHifp zDr#)widDSVjwo0YLXo$?YlmH&MX9tpb&2aY*f4Y0!dyp(@RQnB`b*9JY%95v2zN0$ zbMJNA=MLJs;Klgfo&Ro#B)SL=B3AEH69v$g~UcPEfT?Nv{DJ9qLO+czYU2ads z_GG6$-?YK`0Tcx6O<-TpteK7h1^VmYzYfQ~h%^lFD!|x>*GMrN3V$}HA+0UWUQk_W z9MBn8A%3>8s59&=B6BSJPY_x1)d0O(cVoN zg6Eo70{*alE$;v0fxUz_It$8HJ9z67)P&WB)%b1HtYdUAd5?X9sB_@6Jyj+A#lwl( zAO1^lFm9?>Lvw!7trj-h*cr_!-lS!&1>_U@m8+b5Lu1`p$<78Myo_L;prNCD|@F7^P5#%%T=!?Gfz zG%F`;RgN=G@en?&60K+hoFcxRrL@Yg%|BdwQ2xp0U{4bI@Oxlz6e?Z^pIs|4!357G zYNn~_4u-GZhW>gEQBOgfDdd>I8t0lH^CUxJ8sz3{oRHUE=;J6froGS~%yph*5P8{r z+mj?kGeL}<-`2T5Mz}-3x#l!4U`3i|dXb`_hvYM;LOo7gHz0u~bE6k24NsMK1Gomj z3(aN2M;Di(KRL`gZ&F5nGB5NdV`6qlTBUwxnwJ1G$+gXrI=pvrZ{Te)U-TxE%Z#W6 ztJO&OYo^nf=?E`}zXCXE z=8Zn&9nxsdRFkaupIxNy<=VH0POQDw;*ro7?dXek9F0lnGHNl=yb_v{KB%YL+b$(&ur2dtxa9|Zn3z~%z>5`0eh3%iI~T#91jml(y`%M&I=tIWfK$QYlg_L6Hb zn>B9_BBA6hbA1r%`KI|y5Q&Cm5YtB6#g%4P5SgM0Iqa8s&-w^<5f{MW{c`g>4Jje- znh$Bnd*qaPaxe)G+9rGBh5CLAThwgg59XD@7~W5rTY^bx`f!;HuI5<^*>t7WCO%`o zZDo4YaD2?F3v707LvhQgJ@HsE&|(*_n@dB;YHxNU;Yv6E7DDEcvF74X@;upZZV4r4 zMzULwN5RZoI8A*}iA_w9eG^`j-qM_qHgLDa+b$N{jo3ECt}C%Q!6&2&a$CIUlEuaN zdW#BOo!vj|pN_W(twS#l5|54jERB{ z=4W$x6!|L92Zo>7c{cGrl>I7mN;H}4`)w1u@392hQq9vns7WzA!p^0I7Q63Q{gMI_G)e*U%*y}_tpE`1gW2I@bQh-Q(wKMlAgQK&g&;|Q?ieHn zy44A+yq4m?KU7?+*rz@ILwmfJf;~0iJB4Xg_G^Xi@?y|~2{ zmUvz|`syA=MM-X}!4cQy>pmPKwhDegd%Zq&nef?L;@^Y+|MB;jT|G(kgl$TRkKyAU ztPqu4MF7Vr@0>dHw4fWNfQwch145$=GAx zWp+knPCHAtoGccQkfY?ZI@?+it%4$$X~c275^ojHn75~pnE2yPq6iF$gf;pRC9`J& zv-xcmKQo_6A&Eh|6`(4it)qQl4(vrDqo+9E#0O4R;gdq|UhVj96w}`Cz|l-yxLR1x93g44v1cgBUss%pde3y5Ol!RYF57_u8OXAKZnvVvYT^ z7fB&^%~((pNk4N^DjA@Pa+)hrNmx{%GqI`{zfvF`9L?uDvZ$Qq7gI?Txo`d;m5h!2 z){$7{nb3wbtGENH$sF99gr|M-K;o3n#GMa7Cw4;LHjn8|l6tOp{AnFk+{WE%$4Q>_ zNUREIr*G&)t}?&Vn?#a1W;p|1h51L6mNWJNx<0KM(!orzqYux$!D3;gjc}fW#ryC+ zt=-xo{mr^GlB&@;{;&ol#I={-)nT5PM!Ki?IBr_m7-oXL1;@tnPPo1p&sw-mfE|R} zVTQd)|KMNkgJQWi`tY`HZKeHaZcQW6c~98Y35iulirZv$Fltb2t9Vd>een<2UVCEI z)b<)5?yT{9cJsF0B!ZaDQywCbs`d6aG7&SGH$FtdCoDpijz-wtnPuh!(6>6Fj{~Y| zC%>r^ItI|Nb|{ldhwO%#Njk|d?SbTuR(LSE>jT6dgm=M5Zyi$xtxBx&{vSkT^Tu>^ z>$@;{)c%iTtN9C-d((Kz?*Q#+2-e*?;1~~m$biUq z|7Q_s(mtqAjrk>b-ru7mon2@CtPhz*CYW)BH`({^{pHQYMa(Q^Ri!qtB10U{p~%~IlCT`c zt+LnyJ487%o4+eQ?;;6H6j(QzVY=+kjC@AFU=~E~u*`beglvyHT4ybW|Cl3l_9FO? z{-f9_D5$El*vW`Zlt{vCh2&i~BYDD}Ve}Pl;EsJda`$&sB6bO}$%th*_9J!%v5APK zI0VE_Aodty2`I<(cm0NebYW*fMTjM%pfO58O-e!A>Q5xW< ze-Mrbse7F-Gh_9)#Zxj#=&KN(uMi$(&m7rDpJ{9r>+K7S@t|d~Ta0n=_xyuWASnH) zP%^Qu;|Ef8AjQ7U0X2-9>s{2+D)zDuy}&hf!7R=OKoa~8YuHqT*%hoFKD%0-4u3w} zQn(l3*skp(_z!-dXFuXCaKFJNu5bG;)1KKLCUtK_s^Jd72_Uu({)=#bV!7B1|6RD< zhCTY|s#ZK7-fh^eNQVDMeRiNe#!kt6i0YKct>O^Z`y<&057}Ym3!dxA`pW0F0sJ<| zXG_KcxQe|l1@So4n;w$nlIa_9Fup9H~g+*~>* zJXJH0pQ|*%1Q+9Vux-|e+4>vCR&l#+R&g@A%s6xzBTC$Cn_g@*0k8#jsM7%0XnT<3 zktm?9vj77MFuS>gi3;h5T!R}XAjd6<4S_!}-hFN5hH`zZF~!&_&b7@njstwAZJc3{ zels9b|3SGwD6eU!Z1TewU~h}F+$3RyLYgRCUy_D{K$A4wFkD|J=^+yjTd`qid)Orn zGbFW##eaxd2h!!8Oviz8j?$+;l^zB?voz2!usz?IwtS}cFMx+4V@_vA4KnJK*6L_K zf25~%rmK-243?9@@+kCgcKKS5F2*ikAAI}6`ut~rv+l@tjz{5Nfn#dBn+(?PNlv>4 z0jA3n;NOK~2Y-U^UHSc*IOGW8bI{rS5NCr&o(lqaY!r<+8yKrFND>ep2*(s6>_gWN zev369@L}c=gNPwhlp`(4sKs45+|m>NZTZ30?heQn#y$H)>`<^Z367av%!NO} zJZ&&Ziz#XR1mpE(06d{w3T;sSEh;TG?dCm$N%}ym?KP=e2tEm=@=drYUO=ojVp=73 z+IB*^pn6UEGlZr61eGf@p_j#8%zm z6_B1nWaz25O3&ds% z>uj((n?aZ;zOk^hpmqpx93dpBd3u__Qj;@TztFZ7Q@*9)7=+$2AsIDj*)&{H@0dVH zzj}JbNM^U%)6PtvSX%ZxVL5nW8aBn#Fd_}3($FbgTDIt%!CF{PIp`YRcLZRE^0!!u zz%&y8GK?sOo|uR9^#B=3ME5Ukr6nQj&4aC!zxfLF_GLT`3 zlHv%^mL`!Q0LpOa5r53wjj@|T{g4ThB-=i7lU2sHQs@agoU)a*nXEr66iYH$ zq&2zT&k~b0(qDd+-tr;wiRG)jGx5_qp534r8Y2! zkVZa+zyN?p?cjm=HjMenwsG!cnAj#=AI)Va)`RY;^QTfV`B7%Do}DsGrYN_Fh@q@~ zw}10oEbR_6=w<}}&QnqvJkn(8or^tAp1|SbO9Qi>gfaR=$WP#dM&|8hTZov8fIQkQ zwhU#-O{%GLUhHSOuez11Ls=NJ>fODu&q9VN{xI7+4%%sv3TZT?RWK+)d)tS53KM#j z6`Gc5xwd$v*x76??47TdZMR*^Eqo(Ux@y^m&u~Jj?ZQ&B4lKj6@&t@`jt3VH^OF=` zqzgwYXmK@nF{`HfGm;yNt>7&^1`Ma-dR%-n<~;|>wo*jO*UH)~NviF`rF4dXY~y&$ zbg+RZ+uSbQW^9!Mcdw3b!i9jV!B#^Y&UD6Jc5TZT2UbSIB_ zbu*FR11w=SK$l++EBEo_^V9mJgNIlW$_x#qsm1z%7OSWW>u+0w>&6^VtiNSVlLsFST~YIiGw5AyX-45 zWE4BX<_PyF_J&^}&hz+LSv8t1W?Ww<y#@?N$Gb zMdYNODw>RCDQvJv8;d?`gvcMua{T9&+*bpf;>uVykX4GPacr3(qHYUb-M@&PvBv4<>Uo}<~&)Aro8;kjAq;n}9cFdyVF-)M#w#749@sMYZUUZ^MWN%p;5 zsR^#VVDShh;MGl27WkBQ8P5u2-p(bqXR}vXxrm*D*_#a_e+t{jQk51{*(%=gy0Z!P zueL0{uU6CrV5RFAJad0>lKfMh0rEh|Uup7XabY@(VmeVZo$Y69#D*LU$qR8Vhh1e? z#m?t25RxsveU5#|4NkFW25XDqr)@Ks+3>7me8xTXhWK&@8r|vQ{tOmtNOq({r-;a0 z7BkJHHJG!CO%{LKdrqBpFi8rGsaLDvk2R&cW>mqr9QD5F)7J?f!j7KUEZuu%ORH=X zrf`46vSVsVWY;HTNZ1HI!hTQP?r4XEUJ{#f+2V1uWu885z9tTBpI-%>M!9_p{BD2z zq?Ok0;{7}9vsjY_FHiGbwU=i0AvE=_nvY3^wJ39zaaSEDP$5^L!J_<@hgk@AON7s4 zQ<@aJbh#6s_cPs9KNi-R7(*0d-%K_{n+}-C3RoX8Z5E5;@hS#9Omj4-8$NnT@%U%fe0Mm`It!;{AF$-I&3gGKYmzLJQ_#66c6=XAV2SdF2}A z-Fa*`PFq_e`p?HC#FJw3d^`vB;@W(qc~8{MN4>rx;$LJvBRVz#u0{DnIK7np*nuuw~w zrB>x`k+6gn`RU$41s124Fv0X`Ih>2#@94Rt3VlNGKQWV&3GEn|^MQ?y~7 zhAWD|6-{_-m?sn-7i-TpJ;_06@=X@TS6NJxgRY-2Aw@qHHM7^r(Bw z`hmZI3^d5w%Z5V!X`S-it869XJ=_8daayqzqR9%@y2VuI^@@O@O|!yQMy+g;9=`PZ z3MzxAMcN7$MU{Ti3fA0YMsZ%jyYxIZ+sj9&P!ezkmM)i@o|#&!wy}$%73@2|r;$tx zCI2-%U4FUXWwGOR7Gud}Y!S2QCAGz!=*qgtK%$k2iA5;ptc0%v>OlVBmF zTKz*K_dYOyTBA<#y7w_Rhx@=s?#4?Axq90>*gZjK5eDP6SgAJAHh$CT6WDXm;L>5e ztU1-&d*>QZx`DXIT30W%T0Nv0Que*{^kVBuHZHozv2T$dJg#-nMmYMa&=QS@C|<`p z5&Q=0-!!IFzj;@N?%|d}rfz=gYt;ycGU*ML!6JXOn=MZx=nr;z(^H_o*bSS;f!-5k zZ?Y`oS^H>9I>gf=d=*O?P^+4-7_1i*yX`;OZQJ>#9^kjzds|XKx7gonH2RW+g7}k* zG*mCTq98sH%U5Am_qI5-inaFNisC=JR{Xq*J&|-Bd^u1B*nn#xnW=M{F7Km)cLS1? znySO)gaeU4Ymu^=&1l-e6}XwKTT%j(kU)@Ie7c%t<2@I$hGkk?coK*8MJ~cUX_h{q zn;zW=GP2PDnqywGrvc`81mEULgw9pZHxX^HpW+*fcmkSTk9 z%qUZ*$LBj7nl-_XyobX3TybX&>ozbBxo_N)lcbZWOGh@9QlQr=q;|EoG_5v*9|QeC z;1qBMIJZtb^A;Nx8uuu210pxN#OH4@bYtp8#@nnz>pfbzufnS4MK7Fw7(F^PseO7t zo8r2^KNylxp>7oG-e%zuyPX3y+n`i>{SnCtH7)@t>t*K|0&&25SlUN+lJg@`)q$QKJ12^IE*! zwu}AiSaH};2Sp}zEb=DWS>(UNVkymc-eK*muWR;88sZvjjzs*Ev_~hZc&zrAshULY z4MxmD;p4K_xu!Q4Sq7|7ztQA|I80_4nkT(+m@tB04Xb~&(m;=VCLV8mmm&)=-iftk zIP;+NnT(zpJt5#VZb=JOw z@nG@!ddx)H#5e0%O3&L)Q*gCf@6D~jXIlJNght9p5w?M) zw89Y^wv*Dy1bvwf&edusXEny9tJMUj$lk!R!!U0?_*JZ4Uxrs z#1z9qdrLS!C9ZwM;)mthLozBVf->nGs|EEfORLq%Fg@_M3LH{qlhGZiR!7^789(5Q zN9#sRz$~B?%av&rV>=ar*QN;QwG@qT@6}bQE$d@4GA&gq-f!Cvu$CcP9u1m>z{gVY zEiv#}rKV$)E*RQbjqV1`=Txb+-ZxSJ-cOb4MQ0rB8B(GC5w-kjU^FmP^ebjFyGCIk zh3d(+$0DJ6A|6FT^<=Sg0CZQx{}1p4`La5&@2 zGshOT&0ux9xmEapC*?L9VTL}92I3!$(}qLSTbp2@vIs>QF_<2wGh%Zpkh-fm+~LyxQ)sK2-@+k@5{%NjH_^hA;< z{(@!kPkJi#U$CFKU-u&P?UbrBEQhmEV&qx2iTVW9XIWz0_)^+S&~n&o2Lrb*vzT&2 zumWJCrCdGjh$|)oUZ&h~^#?KF9BUtW*MUV(xyf)mtZ~}zkU{0@Ic3>7meyRK0Ba7) zzx~8kGgCH>X!Il-sphnye()4t=7h9r?w^EWet;>~P(K2MrqfuXND= z9+7sNwFp{*hKihOF!PLC7!b+1&3YO)q8uW|b2(f2@HTsq8M#Nop?KwLy%Ku|%WVBG z!u@QKV)>aZV*Jum;)@D)lx-ACDp^z{g(Vvy1Sz9nNC{-3yF_s%yTq`_vPg zY==Iq^&~ET3q%6MZx#9XSQ&FDo$q59$#?~UCvLz23nI_P);!V7K|_OwomCYrwIzq0 z+g!_S1(Lo|E9#x`9E@5g~$;3Qz%pe%a8j_Uo2w(8{VO7Gv;9>!f8lv^rW z#Cge9Ws(ysf`Sgr;_{s5xtuu@P?puPox0}75#l^>5;zT<1+ILc^zpF2@ZcQ0~o0S6DB_lsMVR}K74W}UW#%WoI{&oSkH5oU-t ztys{ymr>|1^MUeyFqDDipb@Y9$BcaK4V3ToM}7x`_hq1oa>2+K>&++M)yXY4VGIH| zyAfp$TnB1##pOV%$P4CmtdqzI;WccmGCGv6(lvj$oXcf^VFkx7YA!R-y5-6*;k+Jq zXshx|1Ruz(NpEsl`IiPnd3it3`)_dhD&TYb&*;Cx&pxlew?P;FH^MZEYot8*p9Em$!1#OuI%U^`F?*nm9>8_uJ6@GH8rdQgJN@~`=kT=CXKo)A7v>x}U%UAAO9 z4TFE7C%TJs6L}QtuH2c(Ut(;p_~RsqdzFQg_4iG z_~(vAb8ehyK8uR-EMzz!HJXxtd!@q|c{G^%&WKJmBB{1@EAOI!FD**JXHH!8S6vM8 zqX5!-Jol~XpsB!8phyYY$K#F0!bftyL;M;y4uhPbxtou0mACp1nR4IZu)`5v%yHoS z!V-MY@cX2XNG{>G{K!2>i7Z9ch**Yjl4Ku1`Q5u07XvI+79Qt^xj*Sj_9@9_oXb9; z&zHQ1F48=bwt8a^9bV23EW#oKT!Y%00M z6EIeP^A_*O{z{~U()Kpj!zz_%U(UPnbMazQId3y?v?9rC0+_rop2_)dGI{ta>`nQO z$w60{ysnDLJEFMk=mPwK%NxdW^i!lV`*HdB`<8+sNpo>pd28j1a^Bn!ui^^xN`V2=-4F%J=^j(MaCjElpPNZNF9Dn=J2ey!yb z{Ufrud}plk)Lq`xFD0%W+Ril`o+N1(N`Lw;)Brri|0R^Izi_Lu)9}R6Nu!b^B4d(z zB_>M4yFu#NQ%avRJI7QoFK_nzyxB8M&*ja^2@p{({(>lS@vm93$aeEcp4?q5cJnU& z!>7zMCHE2s-264ATRmUL!}1Gs@;u-r;1%GtBj4+a7)w^3=eor@h575gVa;!vVf5f7 zNlpSN^YpuER(>|=YT5UavZ*B zprxRjKy!erKnUr8hFB%({~+v)|EGkN5v_Ig`v29{GRY%J+F!$U&mGAhmGIROT>b3-5%N?Z0en~^`XuB)$S(lHz&8OM4{8DRx#fZ1?)7&NG)a=IQaP9)ILrZl^*ZYD zDTbre3zXcZ0~ua^JZLiH)u5EQEqJmhF&_mh?S+n>;)9?DP(q1UchXCtlFsh3!kDAR zG*GIV7vX^-^ik4Xht97NC0#jm0gWi>Y|v4LeH5%Deb`XKKFXldLr106Oa?;%xwu)u zTV$FbQpSCh?o0x76sM1pdoOP=AB9RvhmP)uM#Y0lJ}729RFrKWC2!f#QMqM{bqTuG z)&htWqmR=4ErhOdkwGObg^t{OIiqM-Lq{)3AElC{78B*#N5M+lyX9H0!5``Lex&qKZl(1nqIYFS^0ti_M?r5g~+ z0bd3x!Pk0a(%HcO3ivW)2k!#tc96Tg6P1Yop8Q0EHv!~EXbV08pj%3EBKYnA`L)s? zbsgygMUEu*g5#5bPfi7&?hQch8Q_OCavueLY$Nya;C=U>>cYf-kh6c6ty+T9e^+R7 zF63DNB}Sm;Ikl0Ar%V;V?FQZzz6?@Fg<9o4|MTHq2vFjrJCBQdxlw#BT<}uJO(ghW z;z9>qPwU=B?jM6c2>9av47{&IwfsOn4*2qO68vd^9tukHJot-Vck;6Z_0Sg|#rYlF zt^mXnuJ6Q@%MB24{4!#$FZIPYumZ2yJ z)YqB_wXf<@|EsZ_3%6MSy?@F76;$&=$iAw(6ntZO1>}_g6+Hdcf-eH-O+;Ds{zPCU zH!3$e>!!;_`ZVf+0x`UYu4|?pw`R(DF24vYyWqv2xm*l>G;jg>bpU-uvw<=5d(U53 zkTW@N_H*>bk|?^Df$`!@4_(K01z;Z{m=RI@V|01Y#Q{|pMDw1y5lU`P-9eq+K29h9 EJIEa7oB#j- diff --git a/bin/SKR_Mini_E3_v1.2_256K_Manual_Bed_Level.bin b/bin/SKR_Mini_E3_v1.2_256K_Manual_Bed_Level.bin index fa69e380ba635be178768f49f6f5d80c0865a2ea..d68d5b05fd37028f8571c79c84341f06c2fd7120 100644 GIT binary patch delta 23143 zcmch<3s_WD`!~GT9tJii0RaI4nE?rKBtbmkAwggO(Zn;FD4wAt$F#)M22wLqOWW$! z%+lW2 z`fJm)nFyK5f99(m5#R{YdL#TjvtK;XR%?s3PASdlm74{P4ehkEWIMm29My{A=jOcm zTaFulyI>^s!Ii-b(=}@~AM4jQDp52$@ zL%f*FTYIXBijU0@$Qr&bV@A^vP-64-dZLWWmqw= zX#u1Un**NgFx2~ARnE>wOEQ`#rXeqrA@^!xx<-hr`NF|PWCg!*u!hX#4-dW@c=aUV zJ|&DQD~d4Ld_z_aIm44|O^>x>6dYH_h-z!YO)iTRFyh}|%^OW+LE;u?kZ5%}R2{@C zb{g72{EB}nI|})IK6`K!^_o}FPi9pDZ|)vS5;~Tz&I+BX%SV~BM?*(FWCA<1k$*U3 zp#HF>tHCL~>U2sfr_JP)7CKu^fm$zZCoNakQQT)?#3wC2NIKEtQwW?I*_fhbx<@vu zv;pGG)-<%fL(XbsDjcvB872i`;s*zr#^(|lm9B13ky0C76{jKRy~Hl|{zU_ZMwf?` zht~El^ey+#{i8F(@5xc7##;Io^&J*f-WTb_S~j#YDnEn1o1)oI-K)SUopV5v7H#lT zr-NI@U(HD;zw@EFv&k>~;#@W9#c#`v)6*j7^kGz7oxfP;P>6LFM&*b3Kh@o=NgV7kBWG6UEr_|!;ywAUPt1+wcT{V2LGby@-DfWsvN^( z1`hPrXhy^S;*^@44^2!$l1`&DqknvZ_*DS&Fh;Kmu5(I@Ezbh z;1=LT4syKO^LdZ4(k_G=DXzwO$1dX*ItnKRWPZgcBriu90cn z$?wRI4ZZE8nba6kv<)}=Whn}*(jRjkNE+GDWShxUHPJQ<|oV7@Cysa$9>i&H$(0X{qbL$8&vQ?65w(EPGM}| zc}GWad+XmOmDVBsSQ|04i0#eDZ9c)^7oV=JL?O*~(&sl*`}&y$w-nR9BKM3LFl^(6 zVd{*2vMk4-QkOt>&E|>Y)$A9aq8$ZWN94Mrwo|ktz#rsWhQ$U2yKSk|xrld=j~Je+ zx!+1-=NL4oe~0u=n=P)n04}pw8G+7DsjyMb&mA5?Ch;qWr%w5*Rk0QER6PxhCZJKJ z9;A*y>}fXNd&KuQlc#-!Apal8_G!=V0F9A0(tC7UxG%yt%HbIZ_byOk2p2~N5Lgsh-boy4RmznYfXcHek=5Pxn+6k#~{1HpDxY}aY{jLnxT*$ z;G;(7^t^_=dh&e-^vyg*We2_jI1lKhWmMIGw;}f(tKcqmwr+E2Zxz%E_p&yE{UV)@kZ7s!{qPszrf^{_Jo_KPt}6^wJGF&@~H&U*+y z37FHHQT+mZeJua4lK7AgP%<@X{~z9d<9nkU>NgY9kNh{$hk7VJxhlb$x*&}(rB`k zPb^LHT>|6%AX~Ltbj;Az>OF&yqFJR5fO}eG9Y%8+ zW2i4QmbLz1>W2xHI(Qda5jWmFK4OgQ4Dh%t^_G}T#8JF)`g#(?7tZM6pNW~lj0R+v zbo{azBZ8hV3vy@duI>W6=lH8L5<|Pnsa-^l=olOf`2jv^W=2#fQfc28a>3K$b>?Tz zTpD+>!Mngu3^LQ@f?fKlfom`$ESRZQ(4|HRPiCDZ)%>|xu~^PNnw3D*QxTo2Y)1S0 z1(=$mbsRcb!OcV1B0jTxZ00Cir0g2I^whyS`vS#jHddXCDd#Qwv>3mp>0KrbnUqcW zC!E`d_%_+4pY4)~@_qR4%clk?ZCP?L>{5q=e6NZ=QT-aO>|@llWHzZMXfHS2onKa= zj*YgbYgLGR&XKN7#*9g|-hjtw)@t~}6&Yywk1EcRj{J$I1(as`GrP%lK5)+1PA|xV zJ)?P{39)kg)I%_z1~l+hb2jx*$wASE!Rkl|>)U1pMRSolw4hZAc83?i)i!B2Kd7>A z?Dr_YrxK}8Xvh8pvPQs{{QAn#DL;bhR~I!*sr`3jDN%PqWw~YnI$npuUN#^2Z0eYW za;w$28yTJK)d%}Ew6Dy+VDERp&;MX|f^2uJY$Mt*LAFb5{OiwlAKmwV7`}So|GnXf zvf*&I;fb>0!+hY})X|dM2HR(N$Nz!dJlXD9*#;dVs3U6lwR2Ou8~=yhssCHM{EfL? zNiy%RTfy4L^Ka^sgZjEHmZ*bZ@elsEE;=#(KP-Ade)20%-}F==;pfc@4WA(QZiU;% z1lh(OK7C$v;$QAnnrjT8Ha7pGji{j0?pbG|92*laVt@5NV$b-;*rDNh$bn7T>b8+5 z+sNn1bJ2;e+05f_nuD}|u#x?oo}A(jKi8Lp^6Pb>e8Bv_^}Wnyj73<|t4M;buIWjo z7SnrHhVFC`kCA1#=82{;mz|B6L={EcutKMvh?M7Mzq=MO&v9cW~a2?{Dr9#!e-YTx<9QZ0@Tc!NX`4rL|ktB z$kaunr_ll~MI&GuR7z`NK$X?RYIvwXBFml z5f56kP0v9xu!g&&15T)!hmf8Kxnu2RnlHzC9+DKQYuA{v?x%L-hcKePsHXOjpdbIs zaj2x#biK3&m_tHU!0|{Zwq_A1Rn3ct?2ioYvj&>BLSm~{URnKW_Xki?~ad zfX&sHp?n6)J8eJTsC~2^)%38s_R%KjABX;a`w2*`kdm78OSO-F1ofag^itOS9&)Kn z&=vGq53T?oL)h=Yrx5oOSUl$V3~_&k^m4V&rLkG}KR^`y!*>wmG;c?c1wlVmXWf4! z%isLmDGju2fP5fIUA@G)ranX2eS&$$Do}VPpvG5_AuL0e)z&TeSNh*GW1$c z>gK)BEJp?=e@?__Y-KmH?we%!$B20gl>XsJggms2zTuFrJBn`*(c3y4-%#sNd^=k6 z@eQ%&;@iubjc<+9%@ugVdDZ;~TSmWSZG)!qT$pY8rPoYMDZ4)i965;}Eu_68$9 zW_4aicd**<{l(gfZ(rNr*B#Q!jtBBr#8+QpxdU{^@+TEpO!y9RUc+~w^(wx%oWCMk zfBQwyBW>sL{mypwIuRxNkJp`2sQL7DyHsjF37sEXk3%x2^*ekkTfddRhwy!~wE_AE ztY3kCtJR3F!S)5dH_Zlo6N6emzs?p#R-r;#cVA~3`72f3QhUl{r)%k&q75uCW8pz3 z;Arfm{lWEhCTkh7$SxnI@O>BcCO`3&i(*r6TbP7$ZJ^mZjS(a51V=3?_CbcD+Bq@5 zVILbO&ailEe>WY~79cjq8y97(4>&r|dB8E^;fv2@RIygY=!7y|gH77w@GZD+vPqxt zQ7=a8BT5up3Lp#6uWpRWF8yd_l1E@6^b2tQMJ$M{&g8sHRDNh*?mnjbkjwGIF&jGQ zrp{H4;p#Y~lrQhoqYcB=G1#C!uzSLl%~3^u@loZSP`V%GSQ=pV}XiIJZGRH3x$y_{%RQMU)_$skh7{n663M?nP59%UdJI+okS&^x{VBX($lx!2faR!pgukfYufp-BQrl$m8$MFIYeJYf%Dii2 zf!1G~WHaH+_n8s}|NY`5@(q7?anf|rI#5S&itI1$!5&+Ydbyb{1^vbTu=2b0o{3T2 zMI5>)6zhCcEB5+}Q{e3J&0Z)I`5bvJ))b}CyfdMq#hFs*qt${A6ZcwFhNQxN$nOq* z(UMsG+m_(k*urG+Yb`eoq?e-mkIiHYqw*JL+t@7xc)Crog$15s^Aqnn87yQt@eNzn zeO^67#fcx>SHST1R#qO`3B`)5u1f#?D4`}d%VL8 zvpqXE0L)fY$Xvi$UcGcM(eP83PU!KAOelYuS}GSCL4}iZKhG`5N;vLubf~Ygui$wqq+P>Lsd(swuBKX`0#nQ8S}X z(M6W4#FtvT>p}`c#V;IT;umHwoHWOpJ0M=Qfv7n##G=wNY788$4SMV`v0D^3eWem- zv|dL;{=-CYe#nXAEw@dyK{L#YxlO?DBcn=~NH(m)I1y^VIjnf6p2n^EiiQW*(F_hW z2OI2Co|)NqWFP77eZhu}JZ%}#a7fcv1<=r#%c0Q=8hanTtmpr#>GW8Xxfr5&h?wL~ z7oEww8l9>``vQt0#|}XRKXVB}L(P1*mpf~W$i-xwfJ_3E0BEW<=`ZJIgH4j0%l8$7 zGdZikiTvD`!;2n$HR9pR3tCJVGj%w4X1F>f&Xx(zik;F_d1vY;?r!87=$SBey$y%) zX@;0~uAgY3uD9U``1H$3`VYpYs!E5VURr0y2Q=$XR z8)mFYRX5uFcmcT&t(ypIOPqUAs6g`wF)KS%9PKPPV3)kXRfBulnS8(|Ii2k8Y_nG& z3+;EUURP)yrgnES$$vC=!umB-EYpWK+oaBx(4sJ${D;B8FVQm-)ob;Ba(}tY?^qW4 zxDqk0HM4tz8}!{;n&`yDXrv~39%z*ow%#|%`)w4S_Kx2t^1m;8g)HVPmLDaNe2*2^ z)jye)MaqJxa+~yv>@B)c+`XS^q#gGzO2hKKUs+Gy;lF<+C$7Y-EJ#5YE;G~JLb_R{ z?bkrMS}`zkPf^X3l^J9@U%E1mOyQTV>`fN%wJVcISN`J4LgM5TUlpSBY)tYQGqdiT znW^^q<#3+zN2|2hsYX^u@#kJG^nGA{TzkmW0auYJt9p=de!?n^Ph$g%^N{cP)vHp~ zSLH)r&oNR!fh7IXcFgVzt@-?gRnbJrKU$R;G10c)@NHGv0AEe$g)D6_7L1`tXDgrg zn%e&bOGedJANH&RM>+Fei&plUgt?So|60=E@v^;8Lny2zIB1NLwluw)gXLM!zksAm z(nDFEfr}72SNh1ZKY8i3*nADF75BuYN1YFbxegnGxYHD){RV4|bEa-;m9~p`hJR*FENS3Ztx1|P9zDuqVW*8G z2b@nGky?P0q3S`%={P%sqcR_HuWco2Dy2}RjTQGfBkPlkB6TvzlHE?CjjSi}iSSaO zHBpwm>*VUK(hxpqZ8W*WYu0A!yP|ER0O%3(Bw*STX=D5VbP+ri1E4oIRgkGc)3d6_ zfa#46t(V2nquz|kz*vMEofd~vnrY`6xH?WWv<^&WFVH)K+je>;dkbHy^rMZQNcoFj z)Q_E{@Z~1JNGX6nxHeKb55&v-g|*q_iQ4Gb3kg}z&wQhfJi$k=yBG2q0u6vVKs}&= zk6k|?$?86=@KY<%C^lF)^fg+5?a=Uy>{e+FuU{WQrt!l138XiFZ~aPgk6-j=Lezw| z;}SZ3QVU{zFlH=eZQYv*M0prSnrbie%Lx11B!1e)V)9pQ?Z%B>kKZpvG0>EO> zzJPZCOTfqEGpan$L4a=nzm(R#@YWDTlmuFVvotCng1LVbbm@&>FyFjwd|)s_sB{vf zfwjHgi6bP6AN%gR%5Vfc#kamY-dCnN5N;zsVf(+iEqwj!^MN+>oR`* z4!v@Jxq|z?HvGLJg>M!VW}qU+)K+|;VZG=XAph5g18dKGw26@A{4=}bFe0qRcSh|e zyOmxz6f}Hxf{=~;(miox3%_m8e6poBWUoR&Qfk9%{Rx@MtH0PoYWU_ac9O&V^K}|B zn%_~kN7;}^xGntHFEc`-W)lwg+6A4pQMhJZ)3}A-^5t*(M{$J9R1=OAvdHQCjZrGX zT?M%Kw;R(zTif^zjfJ4Y+w|8oR)XK%#xHNI0e`2BU(&b({GfP`y#|f=zlj}Pw`md-^aCw;N zo(0Ur$u0rk9gqfiAMV@*ydKuJgWdsp2WW;lHl($@_Tz&c*g-V@1vE#GjdIu+(oS#S zD}?db6sUX;;RZryF=#{WqpwXQr4r;YKqkOr=2jZvW`HjNY?)5DdntrlU#mQvz~;5j zF+Gd+g356OV~Lq{5Ii$5M%w|hTaXv zjsg7J@F`szF^nZQ&Fpk)_<6@t!)7#2ML4~qDFFP6dz#A?{JvwoaBFNjcDVDYUWB8< zBM79oEOZ4PVQlW_sNlaj-iK7xwjOU}^CTog`(-Gy;tQZv9|*IL0JMno8tP#$oRcF9 zZz6mIAQq4Xpjpp`6EkYHzX>&TMnR&G<{$(Oj z=RtnxR{0M2>f?ml3|v>cqG<$4?Dvd<>+phtn*_WNkPmnk@F`#-fMx&(ea)w1FC!Aw z{2RCeA$H(uU;>!QU;ojXI2jbx_!u`70%#i77dQkE16T#O31+7OKXNA-Qck$PrIWQM&ik^xA4dRmOhf2Ltj?bREN zB&7tVJVmA1ihYuB5|X98y&L$enS?tEKEL+(&CzV^x_0UdLB9>4TLrphXsFF>Sxo*z zWf_7$ZKraow)ysHw(xg|=p0J>7%lNhEu$)htOjeqbtiMoUM9&fdRJ~e}IVMt?R?X8Cj zR!fuf1k)sGQWIbz4W>LvRe)d8E~!P}kAYtWd`(V@?s4*5+9=NYps6rC_P2 z@p5T=bcPEiwgp}@KPDi5^|0uTZGTNh=$Y~FHl6j7L?xP zdGb(L>`kUBmmnLfg{$6V0NE?V`jFVZo%RcmEkJ3H0^`vcTJf7O%~;b6bj$ga4|~Q7 zyM9*QM&bPUAnouW!aN_?Kw3T|4!J$$L*@bv;>Z-zB5dQR(AdBcvr#k-45)uifmfwdUZmQ|6fJ`_fc*3|IV# zj@%-z_~>%A)`w?zQOozGVuvEZOL)+cglclznYb?va&xYzePpg{e1@D@4|8ueL9GpJVVV2VL-2lyRN}SUC26srGJ92%L7(lr zZ19qGAtyBMul5Jnh<-H}7w(u@>9XXca6OdtnBHKg28i1oU)oc&!SOhP5)YWE+~cN? z+i9&e#}wa}cE}R1_*yylZ@D>x%<*{){{2$Z)w?eUSH;hDu=EzA*)Y4e4Ec6$m!%0++RCj>8nvl1yZpmUf z{aAP2s${N{Fg={)pdo)0P7))o+PHW|cA?9uJ{xD2-IsnA{s<={f z(5Bo~&_|I7WhAvE%!?tRY=BkR8%4rcVilh3Ogbe#vJ8mrsr9)RMwm@5Yqud`Hc?p& zaY_CVNN1A5{>vgXbs?R|H$qNlED;RC%+4fTvl$0~t{y`j`k}k$q@wriNAGzbPz;$4 zP$nGiOa>&*v|!HKG$6J$#$~qXl&|2_=O>?`Wb4$*{DT zNIcbW#n1@zqEV_i3!Zbzr6QrSB+>^GkCV5xIl5wcW|jYgcGr(l$;h)x{%Sz56lTwb6f#i zgpFNDLc~h*KN(meobEy*B6LtE?!vXkc-q%Y!Hz&OK?si{Mat!%7S~+@A57FP@!2xdgp|=pB||2(&V1hU`f{Amm;m34F1E~AM8#ouBLl+x4Pr-5%g%w@lnkU*a_dYWBr*NPvnLsuQ;fW+cz05+NPI^u}^$5Rf zcRi-`Q&XR96(%H-0fWZMYNHK09BgyqFHYBM&)InG`InUcA10634&52}q z(26!;K7{E)>SJVN@YptC4+x1_c>OUlG$^@E8dV@lX9Uw@Bt;+4CiI7JztfZNp=cGf zIoWJ^SLo)p5+0x%T5~5oU?YGo zGLOzvJi+;$OL*cX2)e@U{{p@NpsQf|l$fr5X_a~2gx*1z$Bq4w-KoN>l^=6b>8up)&>SU@iAM)K8p@>w-~!9$N0eURfz4RnP|cii2PQoL}z8(ADe58`xS z*8nyE-WKL*$l9P??nh|!1)?Zr3xVB94|M^;Uzv|vFW{#Dv|>D!ln#E1P}-f04opY+ z5&+!*os13LF**BoN3?2h_`rDiajeYQ3$4bl(#Vgb!x6;WivWh{l>6Ir!dpGb`5?9X zEp=vWK*1fUvrv;kLOa>;5RGnG=#Gf)f@tE7=Y)?lNKbt*tiK0C^a-no%f!`tgYe@e zMjfu@#EXt#LqZX~giR>&+88??Nu{1_WD-dtBW`hcuOli(-01LG#{#c+aO)JnYaPsE zexE2>mV5cG^Zg{(96X2n*k`x*E+T5}exKx+!zv+L!tzW4;k`cb8Md3@xsQE6p$dm= zjJO2P1^a2~@0mF9h{N?8rcZ~ECZ{ym;xFI5(u~sgwZV1XMYv!xtAdrtqKe_fo5Cl( z$Vd_<*n5#E{Vd#3#}Y`rJzWA@arssMVM2X=`nE(%9FA5;U)C}MFY#C%G1D)vJn*erD9IZ5$+)( zSt3ODAsPNd?OxgfgHk0*rNV?hBqhOOd7_XLi4B!w&)Qf0fcRw=vYTPh(hu@SR!%%E ze9(ua2L5PKzV))U5Ov9kCxzeokZ}CoW+a#;wnBW5S|{N9l|`xb+M1iIXyKUgX4T&D z@D!DQDr?S`HTTMzA6TgOwp+*+FYP#UGW_|Lh5CXM$JnTh=3%{CB3P;J8jE6U6pFUa z>QhAVa^w8I*q`V>v}Bf7Biv#M7Oy!{%6+t1;2wax>`CyK zK&@+Kx1b=P*5VeEhULL(qvMP@xq4TNkAi0PH5umQaKwAOxGt{@7u!5O((`alJ2?)fF^0ec-`~O=fR&59;RmR;IqUHbqW; zy0xSpD?)7!_5ukyBKipS{$y)@g!QJOqJp5OQ3pP4PJyAhZZ}RfXKHD0R9Z_6?W4YH zD+8|(u}RilE#Hnd^{4RL05Vqf3|uHSJv2S8#kDNP=}OE9vj7J%5is}@iU*QS$wAXXO_$-o;w7H!~gwwZ|`-u1L z+so*+Fw;n9U3zoYEbPd_s&ZPEK-!Rb#N7=_!0NhKz*@J}KmVK{FOY zUKlPHkR}tMZ#r@GK9c!K+(b=AXZ@)o*hT}5R-t@)xP9}aG9b# zLil)+q?~TEV;!449y=SAFm^o7a6*ko$CEuQDKkDlk$gl*nGib($(9R)C!wmk2?r)2 zz0ShLNd#A67J(}zeZpV1d1-UB{qe)sWK^B6JpeBRCJUoWNkY^tn`?abmd9rjuf$;$ zhu|#XjZ%VNa|qd!NqWMw@|zgXgzt@+Q+Y7Bp&H{jos8*p+0D3dGOC!^g~L-D z(lv((2b6c8H@-fdl#uwZTj?%={-jE+O)2iT0&6BnJr}%q2Z4KW^J7K89k9YkPd9XvXg&P|Ua7;py5g z2-mg??~flj+>u^$hxf-j{M%BWws7C(_ZO^fTdgB`FTxg|M;Y#oV8xNpnEvxz&B z!^*1Ub#>Nl>B9r<-L^znsw2-RD^bjO#ydJPn+^KY@fO+>0>}n0!#&z11<&?X3g!mtp8ll&jT1HD{C?EYQTDcAcQX@doRId--UnYlL|VNoe?wwjuJPd|Iw25O=Bbwp1Z(SxAf_b8Iv| zqgmfH7>_qwqzGYZ6%NQMgn2JwOx#{Y-p_x}x%GdOgtp+O#5?n3+n(N#g>ql8X0@d^ z2u7DXZc930^&(;jdBIAJF`5nT^su{n(UV^0=uz$>jzRlrky>Pq8g@PY3r2D$LlUOzm_)xTj^qx_*%$*`B*sY+TO`TRB0X}@`T2W+UyS~GP1v)T^zM5OzeaD7 z&Nz-d@Ie|)6e9;G9ar`tyACEbpmC#WB_!WE0#ZqHi)3&xU0bBjh3F+1Q*;)hRw0|O z+B3BjAF;MbWe%lkyRJog*5Q}r{m3%QsUm}0B;FArI(^K|=*PmsB^W}pg&j+9nABUS zUxGOeOZO$DcT}>25f3qklD!%g2?_IB@SwXz>H>%n1}`O3L!5T%oxkPp1AB|~hhSJr zD#+)?=$A+XA@3V6=*ff*q1$bWg1gdDTZ48lRvLbohC+nA*U33$9h&c#g8B_IowZgO zUwMNZBte<(v9b_TfJy2pj9iZ;K#FjAJ&AVd8|@%Tc={sjSTU~c!VSt`(4zq}gjAlq zOF9atcrrII#YVXE2#p!asCo;98_3b1K)F58hCUecOT7@gkxbY7%dc;84C&egr06Ac zuJ)=bjD^JN9=2i%qrp9tId`}^9A>^~Yf_=$%G$zdvuu4j5OEgBHW|&}hXeLdnJ;8d zxArpW`Zj1AI^GmlGL1T1kuF8=rX#`oLdYg^E=c9J+e1A7o%N(3Z6a~8S+e=jhV-KJ zp%{#UA1`21!Z5jpXsNUCzai3tez$p!;bIW)bz#0h5`&Jl?c{?XTp)ZTkZj*GcvL}e zpxzhmQJq8XH|rJJ_<|eoPU2<~H{t`gP=((g-;mysIale!3PT{-;tmfk38wDNsMd@;}CYlk%<2XKpk)v?cy}xIN%#0b_-b% z^sPKwxN7c}G*>We!P>o22zd)b-%P9Lm?juzLWIh}rpw1V0kYH=wyq1f`HSdu9z~()dh)=bn15CY zk8dNdh3t1X#T$73=?nAIh2z`MouZA`w~@+sRIh{3~{#o8J)b?!ZCQ(-hSU+jo+2pvz% z9cV#==#08D`{KMg#^F~Ysmq#2{-w@n!F|2A5i$PO=z z%q&-=Wx4ghlnxg@JB#uTGFJXfGKg<6BA)>q7IvQ_Yhz37bh}(@xn+thQfs5jQ{yj| zcP_w5isiaAR2Y4pj16HHWA^~Kf>`~4%Z>Ht$pJ5Az%m6FX;R2;{nDA zx3FakFMbv2Lgzo?7`OdNqP=`eAa~;2t-yHrFHA4`i!)fxr|kb6E=>79kJIQ*Yb)@4 zK+z0#2$$d%TBozz+L`~;XpUQU9pRpgHh}hIV3{%S9$D)5B?@C*l4ep$ZAD+RrD1g{V(qwPEkvPpny$C%fO0^bF}oKV%?4(GE&>z)N{khK*nF?RYS^P`(tK_(HuPsdA!LcM zVj#Or;kyKS3jo!|M}t{^1ql#H4ts*63a4_|l+bnZ(wi+(lriEF{F)%R;ZwmkmyIT$ z8WVHbg>-AaEe|Yq>Ur!Zm>-NY3)sQLcjh6Ms{m9ApB1t@l~)E}3>3x=#qXzV#=Aq= zWhAP;NT}!i~d> zl_l&SUV%$sjY1Q}#?n&uQ2_bNIQnV!atGg%H&6v@a35~WT*NM9^(i-5?&$UZgbBC* zlmGAV|BHMl?jJKCv@VP4e{> z+xVqh*o&<15%7oP@TqUJ5*sxP^z)}!jx7o`u=saMi}qvM!e62=?_Kr}B@JF-oUk1Y zqEjnq`kzW@ZdI?NBmnao<5xS`eXLxZG~>JvSv-BE3TehgpR;`xQCs@p$v&VJ5Y-o_ zD}{`>4X=Znh2sWx3eG)K_ObbLbGc-Eejoe2H|C^4_3R!6@STHf5FtB^_69Z@Pt%Q2 z->^NrS&c(@@&~q)Pp?N+2vMh?ChVD9^BZ<=T9fD>be0~kf48R2U!WSRn=y64%o+VvJ=1!orKV-1 zW~2+#ud$DNXX~C*sd^cOYwSZdq|0~=fPiE`4?rK|HWRy)kPKt=E%s$a^ze*yW_aJe zOzzxgXR371RXn?(;@R1%Srv0;`WfH8%{GznZNYdqxRBw}0kj14Z=12^FZQc|fDGo} zi5v5+>>^ID2w}OJP?nq0f#t3OFott?1F`Y|-3)91UJAGeNTM=;%P7PAUx=&!|1Du1 z=}y*Rxw@CclS5cEiX@T*v&OHz6gTib|Nny*2;*cJ`Q!4(tv*-`xE((dbRs|xm<#xH zHFiZ<$xjjj{S=zO^C0Phb_d|7kmsjJQmfFRXJC~`@p51qV;Arwx9p&>)=x1vkS;+F zBi32KDZ$rYu~kpka|&d^gFUq~6~uDPEgjn74d8vjPXlZR9nube0X_iye83UV{=iMZ zT3}CD1?b3?F1=*nbcWG0lRyL_U@l;eJ8+3BklE`Fn}M)HZn_D$CwMPR$TV|duelQQ zV2JR_*VTKIfqlSJNOQ~jxiQttdQFe#KgF!Np(4%oZn991kWO@%lWjJbedDDZbY#?MbgC0zao(oxfO!bQ0G7qM* zNsv*ucrcZPp~*x7SkNq*9uosb1)x7J{NoefHo7V-w&N_40zc-(q~G*Oagc^PzHL2o2RmJ&~pHu4Cz2G08p3G@M_S@ z0kkbqoeiKj185k9w?S_Q&?=?;F3_I>sBS9#(Cr|dp=coG_ag8MfQR1?`XG%UGzTd{ z^;G2;*ppP`j?x6$Q{}Y!&-@pEz8z2FT>3Bm3ixXPk3G8DrmJ4c(`?*CSP42kXuZpe zP@v0fPlVf05CJrCD$7NCeb~<60_d8-(@sqddZD}=z!N_JbZ|Q#gn^E17ajvzCG)5< z8mTLoWPry>-9dZ2PQ%l{_X1Fw>huFW5I{Q)&15d<0(Uso2}4`;*rWQx5LOJJG=(vs zO91%KCN2Y$z?1=KWC}Atm$&2Bp$*RgPb1TC9q0w^!mB_pX%}7%dO5)3!B;`A0noVA z#yZecU+>9L7F@c)tw5FN4r()a8cvP84SIXK@b^LQ0(cVm6!cy|Fm!4BBcP7~JQ+R- zx(PtTD9~NlnN^C(Z4IAp%^+ywuYkS=pmj_m6w@{V-qY~Spxg5{@C@1strGgjfetXn zhAQ-&ADujx0B)`pK8#j8UZ?|op_b+D09wCrLmkVd0FHyt1NZ{yaaa|84FnWZM8!@x)d!!gwe~u~*@x8>Ha=7oUyc A0RR91 delta 23134 zcmch<3s_Xu{x`nYo*CHO1Ox;GWCldQ5d{$y@d5%H5HFB7G%uK!puAvOVroEI-b>rs z*38mlowPC?C(cMp=*do6T2PvrdeRKh)Y^DCdzkC{S(_Q+{C?+spZE8F-sjKreD?RY z)^}a^+Uqu)I^p~1gzw=ZLbeFSB!X-)E+A9bp#3%`CXf%{S!tuwuW*GSPRbB2tD*xd zwx~FUVYG(>7;WhoMq4a+sS~xF#W!}GbNQ~B=FR+|U!kGS zoE2sTneYq`PQ`Ofa5On8EC}vL&Kh?I2lXI_1w;RS5$`^s;%xFS4O}geQrn0`+H5T` z(%AYKX@X$wuOpd4RH{fm7HU)1q7H`**hk>&Mp`QQR0tWkf;fe(1FN7392AeB>4Wrm z&K-1dV&+&CSCLndN3<1rLA3#+wS1`bgiXtD#yA`fNG8jmo#kyEOsHU!j$ zj*hJ)8ESp6OF!RMNh;sK5G~^?^>bzU*4t3kTh-*P8<6jmcR8R* zjxc!ZQXu6C<=H9ZZ^EwZr_ps(IXY4!#N|X+(F)HV$Y{A*A8EZqC9SY9TBkhC*;N{9 z^OaV%IpxD`s=|oMh&tL>LDEM@x%$({Bvk$MJ#EO$QUh6?)}&uTV>AZ5+b;pz{9WP)kqsu(bDquw&Jz^U)rR_C9Ka z*8db@E$|L-PzcFO4Q#Z%iNqQG?~OWM z4VNo~DR~iot*{d$eX)UQ_)VzEiwe5xq?yzk68ZYugELk6R{00Pkf#rcRWhII(tF3K z@@;as&3;2-5q)}^d1PG z_qn+~6LpgZj1|rmMERX|bd~nB{i{XGJLJC`<$^*sO;YMN*5DnJ!Y@D}Z`;YhpIbV& z&pcF1riE%~$DISm_k?Amb*Tx8F595hl|Xmi=8mIo@{UR5pMbAVJA5bd;~;-5d^0-A zpKT(e8V?iFBr2mD!D#_UfJ=)(Pzt-W4YsyEJS*(mmKSoLLQ6h{R6G}!4Pmf8O z`C*%C7vgFA8yLNBgH|_87mCAZDIpnFzWJ}%z>J@XDF+!WnB z=!%3x2)D|m^VU59U7}zg7w13QOuKG`VX7_{I)5RhD8qlaOXsaih3+?DMNyo8PnRxN z*9*Ev;ZRX}phI>#+hcp{f}s6KXe-L@uSZ_p`5plNb}pmM0gVTufdM?Dtp?tPz6f&6 zMB~EZR|%PGeEdWnOXdl~CWezK!sLms#I1q(0HB$q;xcm>?P>7zO?0~#AYTy3B%S{Y z%9|BoxN}6)UW`ehbg{X)y+?fn_} zp9B9z7?@rMPt$k@)Sb>9q!R>rej20If%cgsd{Pn%o8I|dPNSMYt&6`B7ra3x*3SpPkO-?YG6U16I9bS>#CQixTOHYm`79~ z3#Eu$p~!nOD==L#35IFo$!0+_J>KgJI3En%^FrG6c=ClXefoDOXwr;~pz+Gfnrdu+ ziNjG)wA_p_eqSNRMSvD+m~df6cB<9&w#1<=?eaDyp1Wsj^DXjS#r~|zQxw9yEELWx z4{3uJca@xnH<~xSaAsy|+6&5H6k*84h-{Z*Iy|bIG_A=b9ZfP<386Po`OJ|tghF2{ zjYu8qiW#TVLuXM^cIPDy@rJh#bI3~thM*XPxh+(ct|xZEYu5IlqslvW*U(<(U|7cq zhFKXsG?P`F7eLGG2kOqX4RYXQ!TYJ70^^~c`kac31swtu3Xh)}G5fxf+%Y&DjO4n) z;hH-4Af#&2>U>c>SClY}{yU7JUI?+I?dz7on2plJ_M;b#gEwV-MAsMsxD!vhBV`dO zM-XRkC6k22IsJU*;>!?*5O%p#m_28le_ykxyo`NxJ>d5%;pCjSpkO7nE65QYg9D() zYc?k}d@53*DZ0IHf=r7yOURwOD*AZ6N4~e@Z>FDJyZl8xS8s+bfT>o|nZO?5#@q{} zLNLvXqU(iuu|#(O(P@w!=zl+fQdhK%N6b)hb+DZj!pkP6kFD@TH$Fz~tvZ&nGxo4zTqg`elatoDv2_KZr@_lU0RElAj9mj;=@`2$A z_1BLuI$AQD90OkM;v;zdkU{b&H~R%BrU=6bT^N)HI=%|3 zrb3KiZ8GDs7ow_d@=hUY!JsJrl0O@f)(L&FAEHh?p|=Z*7mQEr4sLL5_-GCPXJ;wV zbwgvde+B4x9Rz z77Gg&CH48>zxgfx-})8)v8X5MF5F%83Y%LZJXew6AMf&5qVtExAA|!H5piAr&7&In z_-Ox{bj=S8YY z&1MWl=FyDSTuWlV8|_JZV^M6yw}riU0Rzhz{jkOf_z+HfIZyA^bfz$(EK(oe=zmqM z*EMRc5`DzwFY}3X(@d_1=-Zn7>xlHOC9UGC8&mb&8$GT@>4O`4>+d(&u@;hAo`f__ zf2)a+@~n4S7|Gjts|qB0E&->hpBFX2Gfv;+q zhg+%(!M#?Kc{Ln#QB9Al!Jsp1{H_Lqmei<`A=4#B`rZCnOIQ7oCa1jBT-(wOw(&J5 z9*nIC1y@`XrhmVQNNa5STYBiLXf)re5ipEJkb;^>aHDIY^xF_bZx>s%kVnB%T%!Y* zU(;K^7H+S%ZD=Wn`~)gMS{6c;j_A*V_DA%jn)%=c)+|7v@d%`IOl(;UO==BybrEQ zLk@YWGr#3IXa?6Tfo9kt2Ky`{T8xk1M4=|uOuBj+wxKmWuf7Pn5GgDJ)gy&oHI?8J zYnCHcRSX=}I(xQkg(|j2b9EDxVMz8>NB5Rp&{?ZLhsGb8-HyPPZ=s2->3a1W(5?u5 z1~vi@3#_V^v(Wj}oP);vi32kP%dKmQhP(O$sJiAVEO%kav)#Y-3pAw0_;_noRn?;# zpD@xC$IV-r4<2_FMxtB5V6962$@usjN>W=Lc-8n=1oxo&#Dn|QnGgCYp?yooMLQ4Lf3}s~a>#9txwnYa-TD-s@z$Am_OedHGtN2%&wT47JSSVn z1#6=HWTqmV;-ZEep^6w&8gGV9UVsd)r_@QrGqegdFER zJZr6Y@RXdl5TV6(6MTv7I-cij*P4msu>S-;&3qBoZ`;l{JLSr@COnt5eXBgb!Sn65 z(|CT+_9dS4EPuyyv$X-w2j=6=Y++cXQ=ZahYJP<8Y(;HpT(HnwsY}XK2Fdn$VIuFB zZbXc)Z65GhgbfC z7Mon>;PQXRrX?L^Ct$8bH%ZO{e+OpbYrPm)r+l?1XzlWKE0Zt|^PtxUTAc~G zSE>HQk(?t;pOM#M#@OW79du2nlx|+r7+o|nkgKfIBMf77kyxO%+T8&(P2q*!G2vz1 zQ0PV_n%)qiXu3l4l|#qVuiDl>9bz-Y2bw6CKW`lee`kctFUFHS0$CA4h6tf6l7`K- zY4{Chrc~8u+;3|R)i)RG1oMY^N}_m)kll1wj$kahXf#x^B-&Ad9Z)ZlZ6PfD1y@su3hz zn7(RCzuPulW$)3w;cXe+8R*#Fi${}wtgNNz^q+3c#G>)Ch2~YUtd~Xbeks{cYI7!# zYeQq3Tj+8x?GvJa+QQ4 z3_~yvvC9AKw1lHuFJ82FDRKVXrP4rGkBKYOU_qL$>8r1@U%}PV()1P{zVv>v6UI|h zRNQ&s4j=(mzz3UB!9Win0Z0ah1EYZ_fpVY<*aEx@d>>AJRCt&*LUW zmsk;2rj<6d^{LPn1W6|x!O{t{8k@n1=3=-QYK|!MDW{W&@t;CO07XD5)4}~<^&nAbt_${ z!$z-E`WX!yP)p0&(;Q&1%SmSD$f+ZwkH=-3d=opk0htk~@uQ#RYwesIWG+LHNI|TL z>P5^&;Jp!?N$7UPnXtdXsXcMTw=ittNUcqN;4CrNWUEv7siwQ$iS%b+8)X_$0?_nq z@{i6P2=cRY&5S4k^6$*|@wnnq3&U`=8f+{Ry#_P40%dvY zEp2V!>X#tzgKKH*{mx`VWT*BUX`$_BliwDqUXHJN&D^KL4^4B*4mi~qdXk)+6wyZb zfI1HKS=pvlHfNpk(-?%7nQx=QZ?(8@Ng2-kV>bDB zNY#*@a3(-%ak2-p%xXUtq1Rf~*J&OK`Z$?{n@zNpgQU``kS3eVT7n9LvAZ9Ps+~u- zKeQX_yp=cdE1`IGP~ZCwCgIm6_HaObRqwlvba~0>$IO~SO@4TpP5!%5TXeO#^(fOohlW8Y%_yPym96AeVcDzM z(V1pVej)~md^272gqyYe;Cj;2ib1U|R8lDTt&JvmLeknavQC)2HlFwj8`l<) z7U9BLF(S#vB%C)hTP~s(dj51WSM$A9p6%2jt3!mf>k7QCnEUc4TDnL!LlC@K z?KDPaN17f@0m`S;C!eIq@>xZnYVc8Xo{H}8!Ur3o@|M6`QGdG1^2A{3M^{;;x(chD z<`|3}T;C3VnkIiGZWoker=ryxyj>~C@)p5oV;1>97_)J9)D){HUuw+awNX*hR&)^# zCrEVkA<5Cw72({*#JFVC?1%L8xVnql z_l5LL@iRx@jdFX~Xd?-}my*UM5^`i7qg@O>1Na^Am|>js)<{)& zEaLP7sD32o3Qr&`J)|2d7PtuXyiG^rC-9a=)_jID=M zDw1V+4ji0l;%pYFr-dt$AgWD7O5hcwr630Ehi{Vg>x{b|DCAUwZ2AC9BZ zO$~Lz^1uCD6{02F6dmD60gIfz*N_gGbjWWv6hn^akhe9ILr&|EH#KaAe5ONQ)36t^ zUyR$|%7&AWr+3Ip8*V^80J)-;o@u5E7fr?8TH^_)Dx@!77>`9rsZ;*CA)s6se)JzK zS1x$e4P?8Q8;93*RShwetGHZzxE2C)vD=#jxdfO7yoc&M4{Ct7J>buQKM9^;PLGT$ zH*PrIg&juYUq*Ly`zV8tg`L6;eU&h7pI=b@A;Jwsm=C}=883X^LK1g^tpw%*ZZ}>j zgxdmn4Ny0maDlxEXD~LOh-Gs-=a}wKCnLz6M4GETna3eBLnHYi(0L)s3CKC%{lK3B zuK_&`I#w9-MHRU!ockg^gk6poK9z9)Lb!WCE0833otjA=3+1Qc(05)xmE=bcM(CMJ z9_nd~aOTtqTq*GSGPY}69n;VV-JLX|bnoEt!tgJj@*~fvI3qxhSn7m>UuKgt#?~+6 z+4PxEx(itVV-V!6sMAs4Bf!sspC-s}qfY6BhhZ!^$!4c>vQT_FDR^Z=4eZouJ`jfk z46kQ|H%<>ACBj#yPjYiFM%NdZu$0JKz#;ez&* z_28*XS_)c%Fq_j!-E1|^{kDaKtDjYI-@Af5044p#+~(0#xX z;4R=1@G3wvuuQnz^j(w}BpNaXbUTm;d<-N3TZJ#bx5jM%M?*Y~w)+A+jhhBK49Ev+ zfg)q`4>O5QHUH0M`3>s(BMEm7)SgAS&6$Lgg}E2nyGrv5gzJyc9|6OF^}^l@Gl|Mb zeq6+6jD&)I2ugvm;AuV3z?(5<9HurP2zU+90W?P`W$1hIapOmqyx6pyI1V}*`EnuQ=7GKq^b+p;^pVnye}I$)OEc(tB>A)Pz!g24cn>1Y zRUIgGUJGi5OuNYf;O~&>6^?U8`?ZTC@i9c2F&b2}K*ha}Jotjvf(C(pN%I8Q1pCil z5S#Jj^$gOT2E-_b5pPBV4a_QhNkh;AW4B)}5fW+q}QxMK{zyMp{%kV7zE>J+5SXt?(sThL{pilg69`i{{OpXC|tdIW2Pyc0A4 zHkzrn62jHsCGtl2s7q*7$crJLIemIKP5pi0%pb@6Xd=U&Y_Fv)#;sB``@~p8pbiFr z(gf&{bvN)j;CKbz6bz{SktjX7ZbeClL4FB5J;wgqVii{m`D^fVL2n^$&_W~o@Dmaq z?($20#(}>-hj5vowZ=1#R4h-Eb5|x!k|wnrE|THOoz!~BD?25%6Y^=u2S9&Sk`lVg zF(gh%lP{7bMn7`{J7q2Wy6cP9QF*6yR(denHz3ooY7=PZL5J4sQ_#(NnsDdA(>e@8 z-M$1}IdqGSan@84{xZZ>5NWBFfTv$|+5|5Ni)|)y&6sF^n$^@r(P_zc=OS`!yN0YK zJGO5oS4gH zaZ3%o_zk#btjPwtf_&1GJ+HJ-9}uJCss0%ylscwZ2{l`hd}GEc(lkZt&#Mox z`!|~dO3#@is~^b4t{Cm{M>%o|)iDueI^I)Y_fyXgu)tBps>L6=k|6znPA(qENiL~9 zYA;3V8I!6c7A*z_kx&vOCI;cwsz%JkExqXv?bIWQQ6UEp55hRQnL?=H(ckbi~j z9Y;0l1MQkC_H$-+H5qpB$Tfpn2@5@;alf@c#Io|%A{EycA67amF^gXYk$$rex{_$m z(_ih0d_WAgtfXUR>eyXPZ*>Z_*&JE)K;Eio)G{n>ooj0(T~@Lkhst$8yCYURoGssp4;b^K9K(* zei1^(`M+aR>NbW~B8sA}8wsk~Y@3hmIW0Cf|KgT~8`be@H_ltSMam4F6ATz3DtJL-uZ+c%pDa$Ra8|JGzBuH@Srzu30Z%p_YyV>c4z zKSD9FF|^1JwL&uQvhvMW=(yuFHV`J)~ zm~9zRo~<1Ekl8Bk2qg*Rb@5~9b0|qCpNi38Bqa2JHMX)hzgi+HM#$pbQQi>? z!$>&UD$Wff6GP`Aj5?-0Ol5&P%#&gh93&NWGA`;c=62FP)1e(A28ENj_;~BRmKg=@ znbTP>@T6C4rLW8Xl#al`;>>Uos^O?7u{e?hu{MjiC7cAatroFwchW7c*^&{}pZ9DH zCd`}d-mXH!yh(MDq+Roacq5!7vY%VT!#zkhazu>njv2yUF}FKO(XX@IbG;`CDQu1C&w`m7)og+y1QN-5r&1uT9j3k>H3M zu(GZy+SXzH5!&E(FJFrfBS;o|psl@}yTvh)B-Cds?kQVmWvq#<^iYCnUPcVk&b|Ov ztFY`dZDMIS>86{!wH>gr=>%oROrx7qpkuVveos(jNSG@uMg* zoivDEJ;->?b{OWj8`g`@_aL#M%gq1D!F=&h4-y($ir~amxVA`l|C%UXgOL=7k9&|p z&0#dc2{AXC9P|3KO}w<^_3(s$yPlxQZzf9j(VdS4IN0uW+%lloqNt-cKdZpka=w_TBf~OII@@mvdh7PUw7}w9hgZw;PW}V= zg2jE5MDNM&fc2w}u-hR`7We8%y#JOCMe-=n@xTmVAwWMY8$ml?$Jz$D7Wf?S#N>_M zjT?qZT>$twz`MXw#9IJbL4j9n)nXOPy(-S_iK^+_k-7Jfxu3*cJ;@aEiukxEiPbH! z(EE_?{mUxYf3~}CNYXmnD5l4ejA6M-uEB82QzDJ=~(C&24mV2Ep-*=)0==ydnYRFydv=#mWJ*^?S>^=xe=aWZ4&jWOJ ze+`uG?>_@dXZ+VeZvu3V*}7OYob$dIJN!c^iqH%e(5|?PM<>Dbb}^m&(k63X6Ag#W zU5!JK-D2@zJX!2Nx1$W*p$rt063DQS5sGp)3g(%wqStP-CHb~kl|aJNqFqT)_tbUA zMP^so=#A9w2$Kesq0G6UBgAtFB*`Dt2?h>Rl zR{XLzSrJJ0;ogRL6gUB#7K`;{v;Pj)y)=3$QIb={`+Cw(w-ojxOH|xy(6s<<7 zK1;+G`;$xlfy%Ya2t#_5Z~lGRTbz|jg1Y74T#v3;=z@qYf@tEsmxvouN&l*$@cu0v z(Oa$bTx}hnP`Kf6^dvRU^cyEJB$Geez{HdI5FT?Z4^C=xFm)b0gS&+PI>Jd`I|2+* zh4i?W(WVg zks(rs-TR|#bMSPCn^=K~C4%}RM&Lg5`iKT1QmqZw1stZ4q!B+quz1scQbUhtmx_xA zkPvc9TswdiSJA^;x+Sy{U=u2EiaPXCkHWA?oHPd~+);(&q^e?i8qG>ja&X{$gWv8d&=~w$w2(IF-(#A@ZE`+1r_jUrQyxy4KpCZ;v}fvFvj? zyUTS}4_XgeO<^{k74nH)ynyTqvduB#E(R%kTnDa#}g* zvOV)i^+V#FUcl~vL(5?3A3}dltQkm>sv0etw_fH8@C!CHm!*bR-_22L@GG&noXO@m zW(u?omSQ|#v=!j_g_UZKS~R?RS5A)VF2_tZYY$IG%~Ab_O31lN$WN4z`z*9J-?5OL zYJQSA0rk7XLhFXZPphbojX|DXcd52pY2XbO)vj<9^);(!A*C;y#tp*Urs_RQdRaB> zW=nwdizBhjlh1_I3h9bN!_#xq`?ku2!3~w#8l@R-xun>IWJ^BJ3Y@gsvYMxLu-ekz zj8EevCQ~|Bouzm>Ynj4(@+I)|74k#<)wLx;L!0z(ZKO(3Ewtiz%7GfNdGZ9Vrdrrt zFY_fMaTX4z>=sTMrZ|1Sx){HgLyxg!@v1E}qq|Wo9KwKmt&QD@f`HqI!%Aw)hSz$> zd2>Sb{=1$kn$>kSc2`9Af(uiW3{{~Pt5z#Hc@96(Y42uUNN7nDjUHx6!E*ufkF(#l zV&s`7J=ax=DQ)AVnymJ6Jn7Q;Ai*pLqw_>KKO0lW#MAPQwN>Zl@d*u{?X}rPy^d78 z4r&V+E?q;pQMyT3aP)jZiHb?2n-6w4(`5G*=abYk2P zth`r?uM8p4X&249avGc77~!OE%^rAPXf-dkGIeQuqLTb9Ye^lZihMQ}39%KpmM2~w zLU!eaSZ^E3%L!gRT7hNeL^xXDs>Ye-be_JRDr9@zJk(lcJBfqr!9udaR&YcesZ-6tN*By%-mk4jhuhGt=@ z_@3#>Eb!^06I7}-I^}C--Sr)aZo{{YerLbNFrEY1J*3mwQ2Vfs zjb99DbdM<0v>=Bp=EyJN&!fp|vPYafh7^!k@!%M8fP8D3JeD-E5EF~ZMr?i57LzE# zIvnEpCrGK!Iftrj+A|vM@A7GJ#CQxVMzMT6$-@WFFrF+Xlf>8wB#vZ@1rxAuk}8%@ zz-lH&+&BSsm?_?vfC$?}pNUYe7Lz6-$P#f3C9}l^l#CZQPsCn#hFDKYtazUiA2DhY z>Bl~_iDM^`f#jn2$|N#~924s)c~^WqiNtHh+w5|=sGE$1O{SPO89O*3ruQe4LoC^3 znmCnwK*%Q1{v?tu5u>M}sk)21rXf9V@z^w?XCJkRx2KVTA!}@EKARtc-^nJR>AdW| zxZzMLrcNiZI81LJl|7VEnZ#(YRmH(PQd~5h7?7xL21$vXp{poJ~qd%qMMhkwAaIrQ;Lxf0O^( zmXQCu9N)&o1n`0UeYuBIygi3((|oWDQ*5zjE)mIoF?=2xv`EaJN8+)a@$5WQ>3MPE zJfiEh%yC~nW>)EN`$S&sQ0Zbp7tkAai&^AvrHwwFHu3v;Somj()_Eie^XbH=>DHTR z=hGO)p{*?=BZxtKTt;Sk{rJ3!`v&-nIK7-?q~t1#jrQDzQSL^257-BGvJb(p9q!97y6i)6A^)D-tHbWqlu)LY-mtX)h_DNmA$R0I zL|p|5kNw4#Ugn9Y4lAowX49GX?LHnCJV)yFTTHoM5k1PT?cFiwgFfC3o;jVT|HzM_`LwbWM+Nd~q379_Ua8Ksix- z|9O&{bp|PPE)c_<$gCdMmAMSP(iUhNhLN(Ah5#=^KLMqk3zP#3#PAoeAj|6T?U{d9 zzArxi0;!MQXr?u>(SW|bcjYUJ zL>;&PIx_&t9aC<(&{vV((!DJkJMO~JA5U@6Xk9+ESY_Uo>%?m>Vrd^ZnQqZ@2B&<~ z$<^Z*`Z}iauFN^;ua}(KyK*#s3a;j>q5IvTt)#yg3dp=Go0ThjYWz2XEqvE8eak!^ zzxl#l+3Ij6T(9tK(wFVR-MN2V35=axfn~yVM?#mTEDU{jWywL}?#eBWyK=LGewM!y zm#o11dR}~e1xXw96@IgRS3c!9_0SV(oS+mrIPSQ91le^kNxlu+wQHdF1{-VAk$p{UomIrEy)m4!xU4o9%5Tv3GJMETj&-fwE z9OY6EqaX1o;}F$(K{vH+Kug7-dcMBvZD}pjP=RyN19-dXNYE&@ZYLN016+Rl=`!%L z9v3gZNur~Y75C!}DTOJc@X`kK&1VvW@l6fnX=Me8B*p)Gn|t#u67gOV$BQJ+|7geh z-5<(1;#!epc`>LndhFCFHqkJLU3c2c`I!7$s2$A?5Vk#EVbDN=jw1Q!HC zv)*M7DDa2$awj{zGWVN2vLj(nB>cO$WCvzG{}Q+FAlY$ThmC{nQwM%-pj?$AmH6(U zZ#)Km7wtR9EB;31Ye9$J5ePa{+`1DJ^POVrP7Hk$t?td40N98)<}H$%_7Qy40q*^X zli+D3Pe*zCfH#8o#f8+x;5PukGTr}K*Ukjp#=0Yiin_N+Y={S3xs!bl$pu5Ui&Nevi8C!qo9b~vl-{C` zM2)p7n)Vv)hdTaE*13H4(*?ulIi-%MUDFiky3Th?zOKZYt!(D_Dq1i2x**Hm)>C@$EyoD>AUT{BNJg^(DQ=aL|-Q*e@9oANj|8vs+Ncs_0 zD#KmvQ|1BH_$i7L6Sf+r;XU!>9Qz@wvtM`#f3Q4o6{zKBjYA&HXS4{^FlDRAyAo?FBJ2AOAaG0dT4W&bHcG&1w z4*Tw|;k9M{_|F(S_-1*(Jd_EPp0C50k|3CLHBy%lgA8Dx7jzKD${yXv#8> zy&~-NYct=qNSY7Z|(>HFtA~(c0SD zuA$FJ2Yp@~nh=2Alg5}gNn*Q-MSxUSHTJe(+ z$1S{pu9<@F+Y-2;@WQK)njTApsq1y3vJgQAHK5QE`KSSRfeq195Hwmw=9rXwF z7lC8IKHznr3YZOyGbM$xPkZ?Jf^P(Tk(X(vy;1B;l^;$2Fw#l}8clvWHdY--b+n() zhi)D4u_-H#HL0Q|fG+{)doT@@z7tx|!;nvyLK4~6RbC%cJ21y|un(K63O@zgSzsk} zmB3P<45&7>^<(|j;q#FfJunE!0k#0!fI^dQ02{&j%>=&;SPHB$6%1ta)P5hsA5D|y z^Mq;l5cVTN_L~ZZva3~I`w?yr@UiK_2-ZhM28%aFvfq#~;=yb-F{oOZdb5S9Qbsz3 zUjziyUlQ+Rvk~NyNt44aBV@F=Di`8t)6QJ>BbHQ{a`V{{#Osw4EVmxmEN(7f_i31+ zbat3F3cs?tXZmgwyPAaewkGq5^PO^xGa-tR3ali?DGzu4Q|@7Ub~O7~Mb4RK6|oyAps&L9< z$%+4fcD;fACp4$ipJAAy^it9OGW!rM*SeY=&w2T7#=jx~hMLA~V!u#DQQi!fRPS{D zQFRaeZ6HAjleC46_wv$$ZoLUPstGrMuWn6OXW8d5}_5R2_Rr z1$yo{>rco@)3tgwLQRTHZ711&9&Cg|?E5v_P0T#azDSOX$4;{{87Ugiu(2dfym*F9 z#GWJhn$?p)NBcu~sHa!L6WHBDZ9OaE ztC$hE3Zfcf4QN+TK^*e~yEf1-jBq8GpFMrv~aGr z;<@sLOUoBNt({jsf3CNfdXrrueteUiK>Ca1S2mpOKR}H9mF?>>X4Z4s{)0_Lzp{_m zuFTxYD()Fz5%2=A$~3WsT}4QL(+{`VmsO_4_t@|7>kKjLcQ%OBnSqIbbvp2jN4qRAImj??gj#(&!akkRs#L| ze-L-x|33+vmaA1xb@~673=_u5Fv_F7&|ZUBu6P-`C9rrP%jE*^0;@A^SpJ0!ZL}Ky9ErsM}T!K4)!v zxCx*skk^6wfi41exNQ5|ZB@)wmvIh^_guUUv_Irzd{$}ZGVzws#M~4tGa5Sj4o(2| z1f`hf(#>&EsF?ZSJvvd^>y|=C{Vk;z<0(Ux)lh0WQL0-9op&cnb=#n$rEycR%zMz$ zN_A5Lem``ywvK|*c&tdiV?zs0L8SS1QyT3obkwDrQu|d`G&hBcxeXm{5QU0?jcm5g z1{KY01KXFsu(68!f1dt4OJF_r&Fo+0O&_3(FB*BhA9E>mT8!2kV^rYA!?uhU*rnN zO95Ii8lFypt061?kv_8q!aBg6flc7IxMZr^27U+N&d}T7_W-mxsQqK`hXLBBXqXe= zPXW|MaT@$tfHo159bKf04#1bzbG4qpP^ z-2_SjAeRE}0?Ywl254ye(_B_SSn3Ku17)J;x*bxdm9VV@C{Ixhehon5Qmg~N37~N) zwt(N(Nj{Day#um4gKvZ11Bf|YRRL9Q?Z?m@2Hf@bDfpv+JKM*>?+4tun2&lq;j+^( zbVYQ^Wv4z)gFoBJ-U$9Y;P!tB{MGfUDlWj4Z3&7;fICBG@HW6*EV`^>(3tM7PnTMq zWnb6=06KKjI4jW;BO$xHeoye7%!kyt^oWU=;i{60R8l;f$>YzmoBfEJF|S@Jo lib_deps = ${common.lib_deps} SoftwareSerialM=https://github.com/FYSETC/SoftwareSerialM/archive/master.zip - #USBComposite_stm32f1@==0.91 USBComposite for STM32F1@==0.91 - #USBComposite for STM32F1 - #USBComposite_stm32f1=https://github.com/arpruss/USBComposite_stm32f1/archive/0.97.zip lib_ignore = Adafruit NeoPixel, SPI monitor_speed = 115200 @@ -319,7 +316,7 @@ extra_scripts = buildroot/share/PlatformIO/scripts/STM32F103RC_SKR_MINI.py src_filter = ${common.default_src_filter} + lib_deps = ${common.lib_deps} SoftwareSerialM=https://github.com/FYSETC/SoftwareSerialM/archive/master.zip - USBComposite_stm32f1@==0.91 + USBComposite for STM32F1@==0.91 lib_ignore = Adafruit NeoPixel, SPI monitor_speed = 115200 @@ -335,7 +332,7 @@ extra_scripts = buildroot/share/PlatformIO/scripts/STM32F103RC_SKR_MINI.py src_filter = ${common.default_src_filter} + lib_deps = ${common.lib_deps} SoftwareSerialM=https://github.com/FYSETC/SoftwareSerialM/archive/master.zip - USBComposite_stm32f1@==0.91 + USBComposite for STM32F1@==0.91 lib_ignore = Adafruit NeoPixel, SPI monitor_speed = 115200 @@ -351,7 +348,7 @@ extra_scripts = buildroot/share/PlatformIO/scripts/STM32F103RC_SKR_MINI.py src_filter = ${common.default_src_filter} + lib_deps = ${common.lib_deps} SoftwareSerialM=https://github.com/FYSETC/SoftwareSerialM/archive/master.zip - USBComposite_stm32f1@==0.91 + USBComposite for STM32F1@==0.91 lib_ignore = Adafruit NeoPixel, SPI monitor_speed = 115200 @@ -795,6 +792,7 @@ build_unflags = -std=gnu++11 src_filter = ${common.default_src_filter} + lib_deps = ${common.lib_deps} SoftwareSerialM=https://github.com/FYSETC/SoftwareSerialM/archive/master.zip + Adafruit_SPIFlash=https://github.com/adafruit/Adafruit_SPIFlash/archive/master.zip debug_tool = jlink #