From b372c22bb47e7d4288040d89bef5955e9956cb21 Mon Sep 17 00:00:00 2001 From: Djonker83 <84191237+Djonker83@users.noreply.github.com> Date: Wed, 7 Jun 2023 03:29:35 -0400 Subject: [PATCH] Bugfix 2.1.x (#1) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * 🩹 Update KEDI / GODI LCD_PINS_EN pin (#25886) * [cron] Bump distribution date (2023-05-29) * 🩹 Fix and improve GT2560 pins (#25890) Co-authored-by: Scott Lahteine * πŸ”¨ Install 'heatshrink' if needed (#25896) * [cron] Bump distribution date (2023-05-30) * πŸ”§ Default has Heated Bed (#25895) Co-authored-by: Scott Lahteine * 🚸 Probe Wizard display fix * πŸ§‘β€πŸ’» ExtUI::onLevelingStart/Done for all leveling (#25913) * 🌐 Update Russian translation (#25840) * 🌐 Remove unused strings * πŸ”§ Update LCD with NeoPixel Contrast (#25893) * [cron] Bump distribution date (2023-06-02) * πŸ“ M122 comment * πŸ”¨ Clarify env error (#25915) * πŸ”¨ Fix pins debugging for Simulator * 🎨 Lowercase method / data member names (#25914) * πŸ§‘β€πŸ’» numtostr use functions * πŸ§‘β€πŸ’» Dump BOTH and EITHER macros (#25908) * πŸ§‘β€πŸ’» Remove LOOP macros (#25917) * [cron] Bump distribution date (2023-06-03) * 🎨 Lowercase followup (#25923) Followup to #25914 * πŸ”¨ STM32H723VG (1024KB) (#25921) * 🩹 Endstop hit state followup (#25885) Followup to #25574 * πŸ§‘β€πŸ’» Fix narrowing conversions (#25924) * πŸ”§ BTT SKR 3 has onboard endstop pullups (#24876) * πŸ› Fix M25/M125 for LCDs with ui.resume_print (#24877) * [cron] Bump distribution date (2023-06-04) * ✏️ Fix LCD contrast typo (#25929) * 🩹 Fix D576 buffer underrun reporting (#25931) * [cron] Bump distribution date (2023-06-05) * πŸ”§ TMC Driver axis baud for Soft Serial (#25664) * 🎨 Detab C/C++ * πŸ§‘β€πŸ’» Dir change is AxisBits Followup to #25761 * 🩹 Wrap HAS_DISPLAY for if() Followup to #24877 * πŸ§‘β€πŸ’» Fix mfconfig trailing space * [cron] Bump distribution date (2023-06-06) * 🩹 Fix JyersUI corner pos Followup to #25631 * πŸ§‘β€πŸ’» Bypass error in build_example * πŸ§‘β€πŸ’» Suppress narrowing warnings Followup to #25924 * ⚑️ Mixer label in PROGMEM * 🩹 Conditional include probe.h --------- Co-authored-by: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com> Co-authored-by: thinkyhead Co-authored-by: DejitaruJin Co-authored-by: EvilGremlin <22657714+EvilGremlin@users.noreply.github.com> Co-authored-by: I3DBeeTech <129617321+I3DBeeTech@users.noreply.github.com> Co-authored-by: alextrical <35117191+alextrical@users.noreply.github.com> Co-authored-by: ellensp <530024+ellensp@users.noreply.github.com> Co-authored-by: Manuel McLure Co-authored-by: Giuliano Zaro <3684609+GMagician@users.noreply.github.com> Co-authored-by: Andrew <18502096+classicrocker883@users.noreply.github.com> Co-authored-by: kisslorand <50251547+kisslorand@users.noreply.github.com> Co-authored-by: Roi RodrΓ­guez Huertas --- Marlin/Configuration.h | 16 +- Marlin/Configuration_adv.h | 42 +- Marlin/Version.h | 2 +- Marlin/src/HAL/AVR/HAL_SPI.cpp | 4 +- Marlin/src/HAL/AVR/MarlinSerial.h | 2 +- Marlin/src/HAL/AVR/eeprom.cpp | 2 +- Marlin/src/HAL/AVR/fast_pwm.cpp | 4 +- Marlin/src/HAL/AVR/inc/SanityCheck.h | 4 +- Marlin/src/HAL/AVR/pinsDebug.h | 4 +- Marlin/src/HAL/AVR/u8g_com_HAL_AVR_sw_spi.cpp | 4 +- Marlin/src/HAL/DUE/HAL_SPI.cpp | 2 +- .../dogm/u8g_com_HAL_DUE_sw_spi_shared.cpp | 4 +- Marlin/src/HAL/DUE/fastio/G2_PWM.h | 2 +- Marlin/src/HAL/DUE/inc/Conditionals_post.h | 2 +- Marlin/src/HAL/DUE/usb/genclk.h | 296 ++++---- Marlin/src/HAL/DUE/usb/osc.h | 211 +++--- Marlin/src/HAL/DUE/usb/pll.h | 254 +++---- Marlin/src/HAL/DUE/usb/sbc_protocol.h | 111 ++- Marlin/src/HAL/DUE/usb/spc_protocol.h | 357 +++++---- Marlin/src/HAL/DUE/usb/sysclk.h | 30 +- Marlin/src/HAL/DUE/usb/udc.h | 411 ++++++----- Marlin/src/HAL/DUE/usb/udc_desc.h | 57 +- Marlin/src/HAL/DUE/usb/udd.h | 58 +- Marlin/src/HAL/DUE/usb/udi.h | 94 +-- Marlin/src/HAL/DUE/usb/udi_cdc.h | 304 ++++---- Marlin/src/HAL/DUE/usb/udi_msc.c | 142 +--- Marlin/src/HAL/DUE/usb/udi_msc.h | 227 +++--- Marlin/src/HAL/DUE/usb/uotghs_otg.h | 27 +- Marlin/src/HAL/DUE/usb/usb_protocol.h | 266 +++---- Marlin/src/HAL/DUE/usb/usb_protocol_cdc.h | 132 ++-- Marlin/src/HAL/DUE/usb/usb_protocol_msc.h | 64 +- Marlin/src/HAL/ESP32/HAL.cpp | 2 +- Marlin/src/HAL/ESP32/i2s.cpp | 2 +- Marlin/src/HAL/ESP32/inc/SanityCheck.h | 8 +- Marlin/src/HAL/ESP32/ota.cpp | 2 +- Marlin/src/HAL/ESP32/spiffs.cpp | 2 +- Marlin/src/HAL/ESP32/u8g_esp32_spi.cpp | 4 +- Marlin/src/HAL/ESP32/web.cpp | 2 +- Marlin/src/HAL/LINUX/spi_pins.h | 2 +- .../src/HAL/LPC1768/inc/Conditionals_post.h | 2 +- Marlin/src/HAL/LPC1768/main.cpp | 2 +- Marlin/src/HAL/LPC1768/spi_pins.h | 2 +- Marlin/src/HAL/LPC1768/tft/tft_spi.cpp | 2 +- .../u8g/u8g_com_HAL_LPC1768_sw_spi.cpp | 26 +- Marlin/src/HAL/NATIVE_SIM/pinsDebug.cpp | 45 ++ Marlin/src/HAL/NATIVE_SIM/pinsDebug.h | 26 +- Marlin/src/HAL/NATIVE_SIM/spi_pins.h | 2 +- .../src/HAL/NATIVE_SIM/u8g/u8g_com_sw_spi.cpp | 26 +- Marlin/src/HAL/SAMD21/HAL_SPI.cpp | 2 +- Marlin/src/HAL/SAMD21/inc/Conditionals_post.h | 2 +- Marlin/src/HAL/SAMD51/HAL.cpp | 6 +- Marlin/src/HAL/SAMD51/HAL_SPI.cpp | 2 +- Marlin/src/HAL/SAMD51/inc/Conditionals_post.h | 2 +- Marlin/src/HAL/STM32/fastio.cpp | 2 +- Marlin/src/HAL/STM32/inc/Conditionals_adv.h | 2 +- Marlin/src/HAL/STM32/inc/Conditionals_post.h | 2 +- Marlin/src/HAL/STM32/tft/gt911.cpp | 12 +- Marlin/src/HAL/STM32/timers.cpp | 10 +- Marlin/src/HAL/STM32/usb_host.cpp | 2 +- Marlin/src/HAL/STM32F1/HAL.cpp | 2 +- Marlin/src/HAL/STM32F1/HAL.h | 2 +- Marlin/src/HAL/STM32F1/MarlinSerial.cpp | 2 +- Marlin/src/HAL/STM32F1/MarlinSerial.h | 2 +- .../STM32F1/dogm/u8g_com_stm32duino_swspi.cpp | 18 +- .../src/HAL/STM32F1/inc/Conditionals_post.h | 2 +- Marlin/src/HAL/STM32F1/pinsDebug.h | 2 +- Marlin/src/HAL/STM32F1/sdio.cpp | 2 +- Marlin/src/HAL/STM32F1/tft/tft_spi.cpp | 2 +- Marlin/src/HAL/shared/HAL_ST7920.h | 2 +- Marlin/src/HAL/shared/eeprom_api.cpp | 2 +- Marlin/src/HAL/shared/servo.cpp | 2 +- Marlin/src/MarlinCore.cpp | 28 +- Marlin/src/core/language.h | 2 +- Marlin/src/core/macros.h | 17 +- Marlin/src/core/serial_base.h | 2 +- Marlin/src/core/types.h | 37 +- Marlin/src/feature/babystep.cpp | 2 +- Marlin/src/feature/babystep.h | 6 +- Marlin/src/feature/backlash.cpp | 2 +- Marlin/src/feature/bedlevel/abl/bbl.cpp | 16 +- Marlin/src/feature/bedlevel/bedlevel.cpp | 14 +- Marlin/src/feature/bedlevel/bedlevel.h | 6 +- .../bedlevel/mbl/mesh_bed_leveling.cpp | 4 +- .../feature/bedlevel/mbl/mesh_bed_leveling.h | 10 +- Marlin/src/feature/bedlevel/ubl/ubl.cpp | 4 +- Marlin/src/feature/bedlevel/ubl/ubl.h | 12 +- Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp | 24 +- .../src/feature/bedlevel/ubl/ubl_motion.cpp | 8 +- Marlin/src/feature/cancel_object.cpp | 2 +- Marlin/src/feature/cooler.cpp | 2 +- .../src/feature/digipot/digipot_mcp4018.cpp | 4 +- .../src/feature/digipot/digipot_mcp4451.cpp | 2 +- Marlin/src/feature/encoder_i2c.cpp | 6 +- Marlin/src/feature/encoder_i2c.h | 2 +- Marlin/src/feature/fancheck.cpp | 10 +- Marlin/src/feature/filwidth.cpp | 2 +- Marlin/src/feature/host_actions.cpp | 6 +- Marlin/src/feature/leds/leds.cpp | 22 +- Marlin/src/feature/leds/leds.h | 4 +- Marlin/src/feature/leds/neopixel.cpp | 2 +- Marlin/src/feature/leds/neopixel.h | 2 +- Marlin/src/feature/max7219.cpp | 22 +- Marlin/src/feature/mixing.cpp | 8 +- Marlin/src/feature/mixing.h | 2 +- Marlin/src/feature/mmu/mmu2.cpp | 12 +- Marlin/src/feature/pause.cpp | 14 +- Marlin/src/feature/pause.h | 2 +- Marlin/src/feature/power.cpp | 14 +- Marlin/src/feature/power.h | 4 +- Marlin/src/feature/powerloss.cpp | 4 +- Marlin/src/feature/probe_temp_comp.cpp | 12 +- Marlin/src/feature/repeat.cpp | 2 +- Marlin/src/feature/repeat.h | 2 +- Marlin/src/feature/runout.h | 24 +- Marlin/src/feature/solenoid.cpp | 2 +- Marlin/src/feature/twibus.cpp | 2 +- Marlin/src/feature/x_twist.cpp | 4 +- Marlin/src/gcode/bedlevel/G26.cpp | 2 +- Marlin/src/gcode/bedlevel/G35.cpp | 6 +- Marlin/src/gcode/bedlevel/abl/G29.cpp | 18 +- Marlin/src/gcode/bedlevel/abl/M421.cpp | 4 +- Marlin/src/gcode/calibrate/G28.cpp | 8 +- Marlin/src/gcode/calibrate/G34_M422.cpp | 20 +- Marlin/src/gcode/calibrate/G425.cpp | 4 +- Marlin/src/gcode/calibrate/G76_M871.cpp | 2 +- Marlin/src/gcode/calibrate/M100.cpp | 6 +- Marlin/src/gcode/calibrate/M48.cpp | 6 +- Marlin/src/gcode/calibrate/M666.cpp | 2 +- Marlin/src/gcode/config/M200-M205.cpp | 4 +- Marlin/src/gcode/config/M218.cpp | 2 +- Marlin/src/gcode/config/M281.cpp | 2 +- Marlin/src/gcode/config/M305.cpp | 2 +- Marlin/src/gcode/config/M43.cpp | 10 +- Marlin/src/gcode/config/M672.cpp | 2 +- Marlin/src/gcode/config/M92.cpp | 2 +- Marlin/src/gcode/control/M111.cpp | 2 +- Marlin/src/gcode/control/M380_M381.cpp | 2 +- Marlin/src/gcode/control/M7-M9.cpp | 2 +- Marlin/src/gcode/control/M80_M81.cpp | 2 +- Marlin/src/gcode/control/T.cpp | 2 +- Marlin/src/gcode/feature/camera/M240.cpp | 2 +- .../src/gcode/feature/digipot/M907-M910.cpp | 6 +- Marlin/src/gcode/feature/leds/M7219.cpp | 2 +- .../src/gcode/feature/network/M552-M554.cpp | 4 +- Marlin/src/gcode/feature/pause/M125.cpp | 2 +- Marlin/src/gcode/feature/pause/M701_M702.cpp | 2 +- Marlin/src/gcode/feature/trinamic/M122.cpp | 8 + Marlin/src/gcode/gcode.cpp | 22 +- Marlin/src/gcode/gcode.h | 18 +- Marlin/src/gcode/geometry/G92.cpp | 14 +- Marlin/src/gcode/host/M114.cpp | 2 +- Marlin/src/gcode/host/M115.cpp | 2 +- Marlin/src/gcode/lcd/M145.cpp | 2 +- Marlin/src/gcode/motion/G0_G1.cpp | 6 +- Marlin/src/gcode/parser.cpp | 4 +- Marlin/src/gcode/probe/G30.cpp | 2 +- Marlin/src/gcode/probe/M423.cpp | 2 +- Marlin/src/gcode/queue.cpp | 10 +- Marlin/src/gcode/sd/M1001.cpp | 2 +- Marlin/src/gcode/sd/M34.cpp | 2 +- Marlin/src/inc/Conditionals_LCD.h | 94 +-- Marlin/src/inc/Conditionals_adv.h | 38 +- Marlin/src/inc/Conditionals_post.h | 82 ++- Marlin/src/inc/SanityCheck.h | 197 ++--- Marlin/src/inc/Version.h | 2 +- Marlin/src/inc/Warnings.cpp | 10 +- Marlin/src/lcd/HD44780/marlinui_HD44780.cpp | 28 +- Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp | 24 +- Marlin/src/lcd/buttons.h | 4 +- Marlin/src/lcd/dogm/dogm_Statusscreen.h | 16 +- Marlin/src/lcd/dogm/marlinui_DOGM.cpp | 6 +- Marlin/src/lcd/dogm/marlinui_DOGM.h | 4 +- Marlin/src/lcd/dogm/status_screen_DOGM.cpp | 16 +- .../lcd/dogm/status_screen_lite_ST7920.cpp | 8 +- .../lcd/dogm/u8g_dev_st7920_128x64_HAL.cpp | 4 +- .../dogm/u8g_dev_tft_upscale_from_128x64.cpp | 12 +- Marlin/src/lcd/e3v2/common/dwin_api.cpp | 4 +- Marlin/src/lcd/e3v2/creality/dwin.cpp | 34 +- Marlin/src/lcd/e3v2/jyersui/dwin.cpp | 36 +- Marlin/src/lcd/e3v2/marlinui/ui_common.cpp | 2 +- .../lcd/e3v2/marlinui/ui_status_480x272.cpp | 2 +- Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp | 2 +- Marlin/src/lcd/e3v2/proui/dwin.cpp | 50 +- Marlin/src/lcd/e3v2/proui/dwin.h | 16 +- Marlin/src/lcd/e3v2/proui/dwin_defines.h | 2 +- Marlin/src/lcd/e3v2/proui/dwin_lcd.cpp | 4 +- Marlin/src/lcd/e3v2/proui/endstop_diag.cpp | 2 +- Marlin/src/lcd/e3v2/proui/gcode_preview.cpp | 2 +- Marlin/src/lcd/e3v2/proui/lockscreen.cpp | 2 +- Marlin/src/lcd/e3v2/proui/meshviewer.cpp | 12 +- Marlin/src/lcd/e3v2/proui/plot.cpp | 2 +- Marlin/src/lcd/e3v2/proui/printstats.cpp | 2 +- Marlin/src/lcd/extui/anycubic/Tunes.cpp | 2 +- .../extui/anycubic_chiron/chiron_extui.cpp | 4 +- .../extui/anycubic_i3mega/anycubic_extui.cpp | 5 +- .../anycubic_i3mega/anycubic_i3mega_lcd.cpp | 2 +- .../src/lcd/extui/anycubic_vyper/dgus_tft.cpp | 42 +- .../src/lcd/extui/anycubic_vyper/dgus_tft.h | 24 +- .../lcd/extui/anycubic_vyper/vyper_extui.cpp | 4 +- Marlin/src/lcd/extui/dgus/DGUSDisplay.cpp | 56 +- Marlin/src/lcd/extui/dgus/DGUSDisplay.h | 46 +- .../src/lcd/extui/dgus/DGUSScreenHandler.cpp | 226 +++--- Marlin/src/lcd/extui/dgus/DGUSScreenHandler.h | 2 +- .../lcd/extui/dgus/DGUSScreenHandlerBase.h | 150 ++-- Marlin/src/lcd/extui/dgus/dgus_extui.cpp | 50 +- .../lcd/extui/dgus/fysetc/DGUSDisplayDef.cpp | 212 +++--- .../lcd/extui/dgus/fysetc/DGUSDisplayDef.h | 58 +- .../extui/dgus/fysetc/DGUSScreenHandler.cpp | 88 +-- .../lcd/extui/dgus/fysetc/DGUSScreenHandler.h | 4 +- .../lcd/extui/dgus/hiprecy/DGUSDisplayDef.cpp | 208 +++--- .../lcd/extui/dgus/hiprecy/DGUSDisplayDef.h | 58 +- .../extui/dgus/hiprecy/DGUSScreenHandler.cpp | 88 +-- .../extui/dgus/hiprecy/DGUSScreenHandler.h | 4 +- .../src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp | 314 ++++---- .../src/lcd/extui/dgus/mks/DGUSDisplayDef.h | 60 +- .../lcd/extui/dgus/mks/DGUSScreenHandler.cpp | 676 +++++++++--------- .../lcd/extui/dgus/mks/DGUSScreenHandler.h | 106 +-- .../lcd/extui/dgus/origin/DGUSDisplayDef.cpp | 182 ++--- .../lcd/extui/dgus/origin/DGUSDisplayDef.h | 48 +- .../extui/dgus/origin/DGUSScreenHandler.cpp | 88 +-- .../lcd/extui/dgus/origin/DGUSScreenHandler.h | 4 +- .../lcd/extui/dgus_reloaded/DGUSDisplay.cpp | 78 +- .../src/lcd/extui/dgus_reloaded/DGUSDisplay.h | 64 +- .../lcd/extui/dgus_reloaded/DGUSRxHandler.cpp | 376 +++++----- .../lcd/extui/dgus_reloaded/DGUSRxHandler.h | 90 +-- .../extui/dgus_reloaded/DGUSScreenHandler.cpp | 301 ++++---- .../extui/dgus_reloaded/DGUSScreenHandler.h | 82 +-- .../extui/dgus_reloaded/DGUSSetupHandler.cpp | 66 +- .../lcd/extui/dgus_reloaded/DGUSTxHandler.cpp | 228 +++--- .../lcd/extui/dgus_reloaded/DGUSTxHandler.h | 88 +-- .../config/{DGUS_Screen.h => DGUS_ScreenID.h} | 2 +- .../definition/DGUS_ScreenAddrList.cpp | 52 +- .../definition/DGUS_ScreenAddrList.h | 6 +- .../definition/DGUS_ScreenSetup.cpp | 34 +- .../definition/DGUS_ScreenSetup.h | 4 +- .../dgus_reloaded/definition/DGUS_VPList.cpp | 224 +++--- .../dgus_reloaded/dgus_reloaded_extui.cpp | 48 +- Marlin/src/lcd/extui/example/example.cpp | 6 +- .../cocoa_press/leveling_menu.cpp | 2 +- .../cocoa_press/main_menu.cpp | 4 +- .../ftdi_eve_touch_ui/ftdi_eve_extui.cpp | 5 +- .../ftdi_eve_lib/basic/commands.cpp | 2 +- .../ftdi_eve_touch_ui/ftdi_eve_lib/compat.h | 7 +- .../extended/unicode/cyrillic_char_set.cpp | 4 +- .../extended/unicode/font_size_t.cpp | 2 +- .../extended/unicode/standard_char_set.cpp | 2 +- .../ftdi_eve_lib/extended/unicode/unicode.cpp | 2 +- .../extended/unicode/western_char_set.cpp | 4 +- .../generic/about_screen.cpp | 8 +- .../generic/advanced_settings_menu.cpp | 8 +- .../generic/bed_mesh_edit_screen.cpp | 2 +- .../generic/bed_mesh_view_screen.cpp | 2 +- .../generic/endstop_state_screen.cpp | 2 +- .../generic/leveling_menu.cpp | 6 +- .../generic/move_axis_screen.cpp | 2 +- .../extui/ftdi_eve_touch_ui/generic/screens.h | 4 +- .../ftdi_eve_touch_ui/generic/tune_menu.cpp | 8 +- .../extui/ftdi_eve_touch_ui/theme/colors.h | 4 +- .../extui/ia_creality/ia_creality_extui.cpp | 4 +- .../lcd/extui/ia_creality/ia_creality_rts.cpp | 2 +- Marlin/src/lcd/extui/malyan/malyan.cpp | 4 +- Marlin/src/lcd/extui/malyan/malyan_extui.cpp | 9 +- .../draw_auto_level_offset_settings.cpp | 2 +- .../src/lcd/extui/mks_ui/draw_cloud_bind.cpp | 2 +- .../lcd/extui/mks_ui/draw_jerk_settings.cpp | 2 +- .../lcd/extui/mks_ui/draw_media_select.cpp | 2 +- .../lcd/extui/mks_ui/draw_pause_message.cpp | 2 +- .../mks_ui/draw_tmc_current_settings.cpp | 2 +- .../mks_ui/draw_tmc_step_mode_settings.cpp | 2 +- .../extui/mks_ui/draw_touch_calibration.cpp | 2 +- Marlin/src/lcd/extui/mks_ui/draw_ui.cpp | 2 +- .../lcd/extui/mks_ui/draw_z_offset_wizard.cpp | 2 +- Marlin/src/lcd/extui/mks_ui/irq_overrid.cpp | 2 +- Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp | 2 +- Marlin/src/lcd/extui/mks_ui/mks_hardware.h | 2 +- Marlin/src/lcd/extui/mks_ui/pic_manager.cpp | 2 +- .../extui/mks_ui/tft_lvgl_configuration.cpp | 4 +- .../src/lcd/extui/mks_ui/wifiSerial_STM32.cpp | 2 +- .../lcd/extui/mks_ui/wifiSerial_STM32F1.cpp | 2 +- Marlin/src/lcd/extui/mks_ui/wifi_module.cpp | 2 +- Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp | 94 +-- .../src/lcd/extui/nextion/nextion_extui.cpp | 4 +- Marlin/src/lcd/extui/nextion/nextion_tft.cpp | 4 +- Marlin/src/lcd/extui/ui_api.cpp | 4 +- Marlin/src/lcd/extui/ui_api.h | 6 +- Marlin/src/lcd/language/language_de.h | 2 - Marlin/src/lcd/language/language_en.h | 2 - Marlin/src/lcd/language/language_it.h | 4 +- Marlin/src/lcd/language/language_ru.h | 371 +++++++--- Marlin/src/lcd/language/language_sk.h | 2 - Marlin/src/lcd/language/language_tr.h | 2 - Marlin/src/lcd/language/language_vi.h | 1 - Marlin/src/lcd/marlinui.cpp | 46 +- Marlin/src/lcd/marlinui.h | 30 +- Marlin/src/lcd/menu/game/brickout.cpp | 8 +- Marlin/src/lcd/menu/game/invaders.cpp | 20 +- Marlin/src/lcd/menu/game/maze.cpp | 2 +- Marlin/src/lcd/menu/game/snake.cpp | 14 +- Marlin/src/lcd/menu/menu.cpp | 2 +- Marlin/src/lcd/menu/menu_advanced.cpp | 16 +- Marlin/src/lcd/menu/menu_backlash.cpp | 4 +- Marlin/src/lcd/menu/menu_bed_leveling.cpp | 6 +- Marlin/src/lcd/menu/menu_bed_tramming.cpp | 10 +- Marlin/src/lcd/menu/menu_cancelobject.cpp | 2 +- Marlin/src/lcd/menu/menu_configuration.cpp | 8 +- Marlin/src/lcd/menu/menu_delta_calibrate.cpp | 2 +- Marlin/src/lcd/menu/menu_filament.cpp | 10 +- Marlin/src/lcd/menu/menu_info.cpp | 2 +- Marlin/src/lcd/menu/menu_job_recovery.cpp | 2 +- Marlin/src/lcd/menu/menu_led.cpp | 2 +- Marlin/src/lcd/menu/menu_main.cpp | 10 +- Marlin/src/lcd/menu/menu_media.cpp | 2 +- Marlin/src/lcd/menu/menu_mixer.cpp | 4 +- Marlin/src/lcd/menu/menu_mmu2.cpp | 2 +- Marlin/src/lcd/menu/menu_motion.cpp | 6 +- Marlin/src/lcd/menu/menu_password.cpp | 4 +- Marlin/src/lcd/menu/menu_probe_offset.cpp | 2 +- Marlin/src/lcd/menu/menu_temperature.cpp | 8 +- Marlin/src/lcd/menu/menu_touch_screen.cpp | 2 +- Marlin/src/lcd/menu/menu_tramming_wizard.cpp | 2 +- Marlin/src/lcd/menu/menu_tune.cpp | 4 +- Marlin/src/lcd/menu/menu_ubl.cpp | 2 +- Marlin/src/lcd/menu/menu_x_twist.cpp | 6 +- Marlin/src/lcd/tft/canvas.cpp | 52 +- Marlin/src/lcd/tft/canvas.h | 32 +- Marlin/src/lcd/tft/tft_queue.cpp | 22 +- Marlin/src/lcd/tft/tft_queue.h | 2 +- Marlin/src/lcd/tft/ui_1024x600.cpp | 8 +- Marlin/src/lcd/tft/ui_320x240.cpp | 8 +- Marlin/src/lcd/tft/ui_480x320.cpp | 8 +- Marlin/src/libs/BL24CXX.cpp | 8 +- Marlin/src/libs/duration_t.h | 14 +- Marlin/src/libs/nozzle.cpp | 12 +- Marlin/src/libs/numtostr.cpp | 25 +- Marlin/src/libs/vector_3.cpp | 12 +- Marlin/src/module/endstops.cpp | 8 +- Marlin/src/module/motion.cpp | 26 +- Marlin/src/module/motion.h | 5 +- Marlin/src/module/planner.cpp | 24 +- Marlin/src/module/planner.h | 6 +- Marlin/src/module/printcounter.h | 2 +- Marlin/src/module/probe.cpp | 24 +- Marlin/src/module/probe.h | 2 +- Marlin/src/module/scara.cpp | 2 +- Marlin/src/module/settings.cpp | 46 +- Marlin/src/module/stepper.cpp | 26 +- Marlin/src/module/stepper.h | 13 +- Marlin/src/module/stepper/trinamic.cpp | 46 +- Marlin/src/module/temperature.cpp | 54 +- Marlin/src/module/temperature.h | 26 +- Marlin/src/module/tool_change.cpp | 15 +- .../pins/esp32/pins_GODI_CONTROLLER_V1_0.h | 2 +- Marlin/src/pins/esp32/pins_MKS_TINYBEE.h | 2 +- Marlin/src/pins/linux/pins_RAMPS_LINUX.h | 6 +- Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h | 2 +- Marlin/src/pins/lpc1768/pins_BIQU_BQ111_A4.h | 2 +- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h | 2 +- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h | 2 +- Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h | 4 +- Marlin/src/pins/lpc1768/pins_MKS_SBASE.h | 4 +- Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h | 2 +- Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h | 8 +- Marlin/src/pins/lpc1769/pins_AZTEEG_X5_GT.h | 2 +- Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI.h | 2 +- .../src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h | 2 +- .../src/pins/lpc1769/pins_COHESION3D_REMIX.h | 2 +- Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h | 2 +- Marlin/src/pins/lpc1769/pins_SMOOTHIEBOARD.h | 2 +- Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h | 2 +- Marlin/src/pins/mega/pins_GT2560_REV_A.h | 122 ++-- Marlin/src/pins/mega/pins_GT2560_REV_A_PLUS.h | 6 +- Marlin/src/pins/pins.h | 10 +- Marlin/src/pins/pinsDebug.h | 10 +- Marlin/src/pins/rambo/pins_RAMBO.h | 2 +- Marlin/src/pins/rambo/pins_SCOOVO_X9H.h | 2 +- Marlin/src/pins/ramps/pins_3DRAG.h | 2 +- Marlin/src/pins/ramps/pins_AZTEEG_X3.h | 2 +- Marlin/src/pins/ramps/pins_AZTEEG_X3_PRO.h | 4 +- Marlin/src/pins/ramps/pins_FYSETC_F6_13.h | 2 +- Marlin/src/pins/ramps/pins_K8400.h | 2 +- Marlin/src/pins/ramps/pins_LONGER3D_LKx_PRO.h | 2 +- Marlin/src/pins/ramps/pins_MKS_GEN_13.h | 2 +- Marlin/src/pins/ramps/pins_RAMPS.h | 20 +- Marlin/src/pins/ramps/pins_RUMBA.h | 4 +- Marlin/src/pins/ramps/pins_TRIGORILLA_14.h | 6 +- Marlin/src/pins/ramps/pins_TT_OSCAR.h | 6 +- Marlin/src/pins/ramps/pins_ULTIMAKER_OLD.h | 10 +- Marlin/src/pins/ramps/pins_ZRIB_V53.h | 4 +- Marlin/src/pins/sam/env_validate.h | 2 +- Marlin/src/pins/sam/pins_KRATOS32.h | 2 +- Marlin/src/pins/sam/pins_RADDS.h | 2 +- Marlin/src/pins/sam/pins_RAMPS_DUO.h | 2 +- Marlin/src/pins/sam/pins_RAMPS_FD_V1.h | 4 +- Marlin/src/pins/sam/pins_RURAMPS4D_11.h | 4 +- Marlin/src/pins/sam/pins_RURAMPS4D_13.h | 4 +- .../src/pins/samd/pins_BRICOLEMON_LITE_V1_0.h | 10 +- Marlin/src/pins/samd/pins_BRICOLEMON_V1_0.h | 10 +- Marlin/src/pins/samd/pins_MINITRONICS20.h | 10 +- Marlin/src/pins/samd/pins_RAMPS_144.h | 10 +- .../pins/sanguino/pins_MELZI_CREALITY_E2.h | 2 +- Marlin/src/pins/sanguino/pins_MELZI_TRONXY.h | 2 +- .../src/pins/sanguino/pins_SANGUINOLOLU_11.h | 4 +- Marlin/src/pins/sanguino/pins_ZMIB_V2.h | 10 +- Marlin/src/pins/sensitive_pins.h | 2 +- Marlin/src/pins/stm32f1/pins_BEAST.h | 2 +- Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h | 8 +- .../stm32f1/pins_BTT_SKR_MINI_E3_common.h | 16 +- .../src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h | 6 +- .../src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h | 2 +- Marlin/src/pins/stm32f1/pins_CHITU3D.h | 4 +- .../pins/stm32f1/pins_CREALITY_V24S1_301.h | 2 +- Marlin/src/pins/stm32f1/pins_CREALITY_V25S1.h | 2 +- Marlin/src/pins/stm32f1/pins_CREALITY_V4.h | 4 +- Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h | 2 +- Marlin/src/pins/stm32f1/pins_CREALITY_V521.h | 2 +- .../src/pins/stm32f1/pins_ERYONE_ERY32_MINI.h | 8 +- Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h | 2 +- Marlin/src/pins/stm32f1/pins_FLY_MINI.h | 2 +- Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h | 2 +- Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h | 4 +- Marlin/src/pins/stm32f1/pins_GTM32_MINI.h | 2 +- Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h | 2 +- Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h | 2 +- Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h | 2 +- .../pins/stm32f1/pins_KEDI_CONTROLLER_V1_2.h | 8 +- .../pins/stm32f1/pins_MINGDA_MPX_ARM_MINI.h | 2 +- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h | 2 +- .../pins/stm32f1/pins_MKS_ROBIN_E3_common.h | 2 +- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h | 2 +- .../src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h | 2 +- .../pins/stm32f1/pins_MKS_ROBIN_NANO_common.h | 2 +- Marlin/src/pins/stm32f1/pins_PANDA_PI_V29.h | 6 +- Marlin/src/pins/stm32f1/pins_STM32F1R.h | 2 +- Marlin/src/pins/stm32f1/pins_STM3R_MINI.h | 2 +- Marlin/src/pins/stm32f1/pins_ZM3E2_V1_0.h | 2 +- Marlin/src/pins/stm32f4/pins_ARMED.h | 2 +- Marlin/src/pins/stm32f4/pins_ARTILLERY_RUBY.h | 4 +- .../src/pins/stm32f4/pins_BTT_BTT002_V1_0.h | 2 +- Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h | 6 +- Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h | 2 +- .../pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h | 4 +- .../stm32f4/pins_BTT_SKR_MINI_E3_V3_0_1.h | 8 +- .../pins/stm32f4/pins_BTT_SKR_PRO_common.h | 6 +- .../pins/stm32f4/pins_BTT_SKR_V2_0_common.h | 6 +- .../pins/stm32f4/pins_FYSETC_CHEETAH_V20.h | 4 +- Marlin/src/pins/stm32f4/pins_FYSETC_S6.h | 2 +- Marlin/src/pins/stm32f4/pins_I3DBEEZ9.h | 6 +- .../pins/stm32f4/pins_MKS_MONSTER8_common.h | 2 +- .../stm32f4/pins_MKS_ROBIN_NANO_V3_common.h | 2 +- Marlin/src/pins/stm32f4/pins_MKS_SKIPR_V1_0.h | 2 +- .../src/pins/stm32f4/pins_TH3D_EZBOARD_V2.h | 4 +- Marlin/src/pins/stm32g0/pins_BTT_EBB42_V1_1.h | 2 +- .../pins/stm32g0/pins_BTT_MANTA_E3_EZ_V1_0.h | 6 +- .../pins/stm32g0/pins_BTT_MANTA_M4P_V1_0.h | 4 +- .../pins/stm32g0/pins_BTT_MANTA_M5P_V1_0.h | 4 +- .../pins/stm32g0/pins_BTT_MANTA_M8P_common.h | 4 +- .../pins/stm32g0/pins_BTT_SKR_MINI_E3_V3_0.h | 8 +- .../pins/stm32h7/pins_BTT_OCTOPUS_MAX_EZ.h | 4 +- .../pins/stm32h7/pins_BTT_SKR_V3_0_common.h | 9 +- Marlin/src/pins/teensy2/pins_PRINTRBOARD.h | 2 +- .../src/pins/teensy2/pins_PRINTRBOARD_REVF.h | 2 +- Marlin/src/pins/teensy2/pins_SAV_MKI.h | 2 +- Marlin/src/sd/Sd2Card.cpp | 10 +- Marlin/src/sd/Sd2Card.h | 2 +- Marlin/src/sd/SdBaseFile.cpp | 18 +- Marlin/src/sd/cardreader.cpp | 14 +- Marlin/src/sd/cardreader.h | 2 +- .../sd/usb_flashdrive/Sd2Card_FlashDrive.h | 2 +- buildroot/bin/build_example | 3 + ...M32H723Vx.json => marlin_STM32H723VE.json} | 4 +- .../PlatformIO/boards/marlin_STM32H723VG.json | 61 ++ .../PlatformIO/scripts/common-dependencies.h | 6 +- .../PlatformIO/scripts/preflight-checks.py | 2 +- .../PeripheralPins.c | 0 .../PinNamesVar.h | 0 .../ldscript.ld | 0 .../variant_MARLIN_STM32H723VE.cpp} | 0 .../variant_MARLIN_STM32H723VE.h} | 0 .../variants/MARLIN_H723VG/PeripheralPins.c | 590 +++++++++++++++ .../variants/MARLIN_H723VG/PinNamesVar.h | 108 +++ .../variants/MARLIN_H723VG/ldscript.ld | 174 +++++ .../variant_MARLIN_STM32H723VG.cpp | 273 +++++++ .../variant_MARLIN_STM32H723VG.h | 269 +++++++ .../marlin_maple_CHITU_F103/board/board.h | 12 +- .../marlin_maple_MEEB_3DP/board/board.h | 12 +- buildroot/share/git/mfconfig | 2 +- .../share/scripts/MarlinBinaryProtocol.py | 28 +- buildroot/share/scripts/upload.py | 26 +- buildroot/tests/DUE | 2 +- buildroot/tests/mega2560 | 2 +- buildroot/tests/rumba32 | 2 +- ini/renamed.ini | 3 + ini/stm32h7.ini | 24 +- 493 files changed, 7275 insertions(+), 5613 deletions(-) create mode 100644 Marlin/src/HAL/NATIVE_SIM/pinsDebug.cpp rename Marlin/src/lcd/extui/dgus_reloaded/config/{DGUS_Screen.h => DGUS_ScreenID.h} (97%) rename buildroot/share/PlatformIO/boards/{marlin_STM32H723Vx.json => marlin_STM32H723VE.json} (96%) create mode 100644 buildroot/share/PlatformIO/boards/marlin_STM32H723VG.json rename buildroot/share/PlatformIO/variants/{MARLIN_H723Vx => MARLIN_H723VE}/PeripheralPins.c (100%) rename buildroot/share/PlatformIO/variants/{MARLIN_H723Vx => MARLIN_H723VE}/PinNamesVar.h (100%) rename buildroot/share/PlatformIO/variants/{MARLIN_H723Vx => MARLIN_H723VE}/ldscript.ld (100%) rename buildroot/share/PlatformIO/variants/{MARLIN_H723Vx/variant_MARLIN_STM32H723VX.cpp => MARLIN_H723VE/variant_MARLIN_STM32H723VE.cpp} (100%) rename buildroot/share/PlatformIO/variants/{MARLIN_H723Vx/variant_MARLIN_STM32H723VX.h => MARLIN_H723VE/variant_MARLIN_STM32H723VE.h} (100%) create mode 100644 buildroot/share/PlatformIO/variants/MARLIN_H723VG/PeripheralPins.c create mode 100644 buildroot/share/PlatformIO/variants/MARLIN_H723VG/PinNamesVar.h create mode 100644 buildroot/share/PlatformIO/variants/MARLIN_H723VG/ldscript.ld create mode 100644 buildroot/share/PlatformIO/variants/MARLIN_H723VG/variant_MARLIN_STM32H723VG.cpp create mode 100644 buildroot/share/PlatformIO/variants/MARLIN_H723VG/variant_MARLIN_STM32H723VG.h diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 730ab5a7590c..f6f376353f07 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -266,7 +266,7 @@ */ //#define MAGNETIC_PARKING_EXTRUDER -#if EITHER(PARKING_EXTRUDER, MAGNETIC_PARKING_EXTRUDER) +#if ANY(PARKING_EXTRUDER, MAGNETIC_PARKING_EXTRUDER) #define PARKING_EXTRUDER_PARKING_X { -78, 184 } // X positions for parking the extruders #define PARKING_EXTRUDER_GRAB_DISTANCE 1 // (mm) Distance to move beyond the parking point to grab the extruder @@ -419,7 +419,7 @@ #define POWER_TIMEOUT 30 // (s) Turn off power if the machine is idle for this duration //#define POWER_OFF_DELAY 60 // (s) Delay of poweroff after M81 command. Useful to let fans run for extra time. #endif - #if EITHER(AUTO_POWER_CONTROL, POWER_OFF_WAIT_FOR_COOLDOWN) + #if ANY(AUTO_POWER_CONTROL, POWER_OFF_WAIT_FOR_COOLDOWN) //#define AUTO_POWER_E_TEMP 50 // (Β°C) PSU on if any extruder is over this temperature //#define AUTO_POWER_CHAMBER_TEMP 30 // (Β°C) PSU on if the chamber is over this temperature //#define AUTO_POWER_COOLER_TEMP 26 // (Β°C) PSU on if the cooler is over this temperature @@ -921,7 +921,7 @@ #define DELTA_CALIBRATION_DEFAULT_POINTS 4 #endif - #if EITHER(DELTA_AUTO_CALIBRATION, DELTA_CALIBRATION_MENU) + #if ANY(DELTA_AUTO_CALIBRATION, DELTA_CALIBRATION_MENU) // Step size for paper-test probing #define PROBE_MANUALLY_STEP 0.05 // (mm) #endif @@ -965,7 +965,7 @@ */ //#define MORGAN_SCARA //#define MP_SCARA -#if EITHER(MORGAN_SCARA, MP_SCARA) +#if ANY(MORGAN_SCARA, MP_SCARA) // If movement is choppy try lowering this value #define DEFAULT_SEGMENTS_PER_SECOND 200 @@ -1809,7 +1809,7 @@ #define MAX_SOFTWARE_ENDSTOP_W #endif -#if EITHER(MIN_SOFTWARE_ENDSTOPS, MAX_SOFTWARE_ENDSTOPS) +#if ANY(MIN_SOFTWARE_ENDSTOPS, MAX_SOFTWARE_ENDSTOPS) //#define SOFT_ENDSTOPS_MENU_ITEM // Enable/Disable software endstops from the LCD #endif @@ -2046,7 +2046,7 @@ #endif -#if EITHER(AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_BILINEAR) +#if ANY(AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_BILINEAR) // Set the number of grid points per dimension. #define GRID_MAX_POINTS_X 10 @@ -3340,7 +3340,7 @@ //#define TOUCH_OFFSET_Y 257 //#define TOUCH_ORIENTATION TOUCH_LANDSCAPE - #if BOTH(TOUCH_SCREEN_CALIBRATION, EEPROM_SETTINGS) + #if ALL(TOUCH_SCREEN_CALIBRATION, EEPROM_SETTINGS) #define TOUCH_CALIBRATION_AUTO_SAVE // Auto save successful calibration values to EEPROM #endif @@ -3437,7 +3437,7 @@ //#define RGB_LED //#define RGBW_LED -#if EITHER(RGB_LED, RGBW_LED) +#if ANY(RGB_LED, RGBW_LED) //#define RGB_LED_R_PIN 34 //#define RGB_LED_G_PIN 43 //#define RGB_LED_B_PIN 35 diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 95e06db440ec..7021d768ff6a 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -310,7 +310,7 @@ //#define ADAPTIVE_FAN_SLOWING // Slow down the part-cooling fan if the temperature drops #if ENABLED(ADAPTIVE_FAN_SLOWING) //#define REPORT_ADAPTIVE_FAN_SLOWING // Report fan slowing activity to the console - #if EITHER(MPCTEMP, PIDTEMP) + #if ANY(MPCTEMP, PIDTEMP) //#define TEMP_TUNING_MAINTAIN_FAN // Don't slow down the fan speed during M303 or M306 T #endif #endif @@ -759,10 +759,10 @@ #if ENABLED(NEOPIXEL_LED) //#define CASE_LIGHT_USE_NEOPIXEL // Use NeoPixel LED as case light #endif - #if EITHER(RGB_LED, RGBW_LED) + #if ANY(RGB_LED, RGBW_LED) //#define CASE_LIGHT_USE_RGB_LED // Use RGB / RGBW LED as case light #endif - #if EITHER(CASE_LIGHT_USE_NEOPIXEL, CASE_LIGHT_USE_RGB_LED) + #if ANY(CASE_LIGHT_USE_NEOPIXEL, CASE_LIGHT_USE_RGB_LED) #define CASE_LIGHT_DEFAULT_COLOR { 255, 255, 255, 255 } // { Red, Green, Blue, White } #endif #endif @@ -1175,7 +1175,7 @@ */ //#define INPUT_SHAPING_X //#define INPUT_SHAPING_Y -#if EITHER(INPUT_SHAPING_X, INPUT_SHAPING_Y) +#if ANY(INPUT_SHAPING_X, INPUT_SHAPING_Y) #if ENABLED(INPUT_SHAPING_X) #define SHAPING_FREQ_X 40 // (Hz) The default dominant resonant frequency on the X axis. #define SHAPING_ZETA_X 0.15f // Damping ratio of the X axis (range: 0.0 = no damping to 1.0 = critical damping). @@ -1417,7 +1417,7 @@ */ //#define DIGIPOT_MCP4018 // Requires https://github.com/felias-fogg/SlowSoftI2CMaster //#define DIGIPOT_MCP4451 -#if EITHER(DIGIPOT_MCP4018, DIGIPOT_MCP4451) +#if ANY(DIGIPOT_MCP4018, DIGIPOT_MCP4451) #define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT:4 AZTEEG_X3_PRO:8 MKS_SBASE:5 MIGHTYBOARD_REVE:5 // Actual motor currents in Amps. The number of entries must match DIGIPOT_I2C_NUM_CHANNELS. @@ -1474,7 +1474,7 @@ // //#define LCD_BACKLIGHT_TIMEOUT_MINS 1 // (minutes) Timeout before turning off the backlight -#if HAS_BED_PROBE && EITHER(HAS_MARLINUI_MENU, HAS_TFT_LVGL_UI) +#if HAS_BED_PROBE && ANY(HAS_MARLINUI_MENU, HAS_TFT_LVGL_UI) //#define PROBE_OFFSET_WIZARD // Add a Probe Z Offset calibration option to the LCD menu #if ENABLED(PROBE_OFFSET_WIZARD) /** @@ -1543,14 +1543,14 @@ */ #define SHOW_BOOTSCREEN // Show the Marlin bootscreen on startup. ** ENABLE FOR PRODUCTION ** #if ENABLED(SHOW_BOOTSCREEN) - #define BOOTSCREEN_TIMEOUT 4000 // (ms) Total Duration to display the boot screen(s) - #if EITHER(HAS_MARLINUI_U8GLIB, TFT_COLOR_UI) + #define BOOTSCREEN_TIMEOUT 3000 // (ms) Total Duration to display the boot screen(s) + #if ANY(HAS_MARLINUI_U8GLIB, TFT_COLOR_UI) #define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving lots of flash) #endif #if HAS_MARLINUI_U8GLIB //#define BOOT_MARLIN_LOGO_ANIMATED // Animated Marlin logo. Costs ~3260 (or ~940) bytes of flash. #endif - #if EITHER(HAS_MARLINUI_U8GLIB, TOUCH_UI_FTDI_EVE) + #if ANY(HAS_MARLINUI_U8GLIB, TOUCH_UI_FTDI_EVE) //#define SHOW_CUSTOM_BOOTSCREEN // Show the bitmap in Marlin/_Bootscreen.h on startup. #endif #endif @@ -1615,13 +1615,13 @@ #define SET_REMAINING_TIME // Add 'R' parameter to set remaining time //#define SET_INTERACTION_TIME // Add 'C' parameter to set time until next filament change or other user interaction //#define M73_REPORT // Report M73 values to host - #if BOTH(M73_REPORT, HAS_MEDIA) + #if ALL(M73_REPORT, HAS_MEDIA) #define M73_REPORT_SD_ONLY // Report only when printing from SD #endif #endif // LCD Print Progress options. Multiple times may be displayed in turn. -#if HAS_DISPLAY && EITHER(HAS_MEDIA, SET_PROGRESS_MANUALLY) +#if HAS_DISPLAY && ANY(HAS_MEDIA, SET_PROGRESS_MANUALLY) #define SHOW_PROGRESS_PERCENT // Show print progress percentage (doesn't affect progress bar) #define SHOW_ELAPSED_TIME // Display elapsed printing time (prefix 'E') //#define SHOW_REMAINING_TIME // Display estimated time to completion (prefix 'R') @@ -1630,7 +1630,7 @@ #endif //#define PRINT_PROGRESS_SHOW_DECIMALS // Show/report progress with decimal digits, not all UIs support this - #if EITHER(HAS_MARLINUI_HD44780, IS_TFTGLCD_PANEL) + #if ANY(HAS_MARLINUI_HD44780, IS_TFTGLCD_PANEL) //#define LCD_PROGRESS_BAR // Show a progress bar on HD44780 LCDs for SD printing #if ENABLED(LCD_PROGRESS_BAR) #define PROGRESS_BAR_BAR_TIME 2000 // (ms) Amount of time to show the bar @@ -2301,7 +2301,7 @@ //#define PROBING_MARGIN_BACK PROBING_MARGIN #endif -#if EITHER(MESH_BED_LEVELING, AUTO_BED_LEVELING_UBL) +#if ANY(MESH_BED_LEVELING, AUTO_BED_LEVELING_UBL) // Override the mesh area if the automatic (max) area is too large //#define MESH_MIN_X MESH_INSET //#define MESH_MIN_Y MESH_INSET @@ -2309,7 +2309,7 @@ //#define MESH_MAX_Y Y_BED_SIZE - (MESH_INSET) #endif -#if BOTH(AUTO_BED_LEVELING_UBL, EEPROM_SETTINGS) +#if ALL(AUTO_BED_LEVELING_UBL, EEPROM_SETTINGS) //#define OPTIMIZED_MESH_STORAGE // Store mesh with less precision to save EEPROM space #endif @@ -2379,7 +2379,7 @@ #endif // G76 options - #if BOTH(PTC_PROBE, PTC_BED) + #if ALL(PTC_PROBE, PTC_BED) // Park position to wait for probe cooldown #define PTC_PARK_POS { 0, 0, 100 } @@ -2421,7 +2421,7 @@ // G5 BΓ©zier Curve Support with XYZE destination and IJPQ offsets //#define BEZIER_CURVE_SUPPORT // Requires ~2666 bytes -#if EITHER(ARC_SUPPORT, BEZIER_CURVE_SUPPORT) +#if ANY(ARC_SUPPORT, BEZIER_CURVE_SUPPORT) //#define CNC_WORKSPACE_PLANES // Allow G2/G3/G5 to operate in XY, ZX, or YZ planes #endif @@ -2507,8 +2507,8 @@ // The number of linear moves that can be in the planner at once. // The value of BLOCK_BUFFER_SIZE must be a power of 2 (e.g., 8, 16, 32) -#if BOTH(HAS_MEDIA, DIRECT_STEPPING) - #define BLOCK_BUFFER_SIZE 16 +#if ALL(HAS_MEDIA, DIRECT_STEPPING) + #define BLOCK_BUFFER_SIZE 8 #elif HAS_MEDIA #define BLOCK_BUFFER_SIZE 16 #else @@ -3289,7 +3289,7 @@ */ //#define SENSORLESS_HOMING // StallGuard capable drivers only - #if EITHER(SENSORLESS_HOMING, SENSORLESS_PROBING) + #if ANY(SENSORLESS_HOMING, SENSORLESS_PROBING) // TMC2209: 0...255. TMC2130: -64...63 #define X_STALL_SENSITIVITY 8 #define X2_STALL_SENSITIVITY X_STALL_SENSITIVITY @@ -3452,7 +3452,7 @@ */ //#define SPINDLE_FEATURE //#define LASER_FEATURE -#if EITHER(SPINDLE_FEATURE, LASER_FEATURE) +#if ANY(SPINDLE_FEATURE, LASER_FEATURE) #define SPINDLE_LASER_ACTIVE_STATE LOW // Set to "HIGH" if SPINDLE_LASER_ENA_PIN is active HIGH #define SPINDLE_LASER_USE_PWM // Enable if your controller supports setting the speed/power @@ -4204,7 +4204,7 @@ //#define WIFISUPPORT // Marlin embedded WiFi management //#define ESP3D_WIFISUPPORT // ESP3D Library WiFi management (https://github.com/luc-github/ESP3DLib) -#if EITHER(WIFISUPPORT, ESP3D_WIFISUPPORT) +#if ANY(WIFISUPPORT, ESP3D_WIFISUPPORT) //#define WEBSUPPORT // Start a webserver (which may include auto-discovery) //#define OTASUPPORT // Support over-the-air firmware updates //#define WIFI_CUSTOM_COMMAND // Accept feature config commands (e.g., WiFi ESP3D) from the host diff --git a/Marlin/Version.h b/Marlin/Version.h index cac9dbda5dda..b5808dcf44f0 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2023-05-27" +//#define STRING_DISTRIBUTION_DATE "2023-06-06" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/HAL/AVR/HAL_SPI.cpp b/Marlin/src/HAL/AVR/HAL_SPI.cpp index dc98f2f79e71..32c0361d0352 100644 --- a/Marlin/src/HAL/AVR/HAL_SPI.cpp +++ b/Marlin/src/HAL/AVR/HAL_SPI.cpp @@ -198,7 +198,7 @@ void spiBegin() { // output pin high - like sending 0xFF WRITE(SD_MOSI_PIN, HIGH); - LOOP_L_N(i, 8) { + for (uint8_t i = 0; i < 8; ++i) { WRITE(SD_SCK_PIN, HIGH); nop; // adjust so SCK is nice @@ -225,7 +225,7 @@ void spiBegin() { void spiSend(uint8_t data) { // no interrupts during byte send - about 8Β΅s cli(); - LOOP_L_N(i, 8) { + for (uint8_t i = 0; i < 8; ++i) { WRITE(SD_SCK_PIN, LOW); WRITE(SD_MOSI_PIN, data & 0x80); data <<= 1; diff --git a/Marlin/src/HAL/AVR/MarlinSerial.h b/Marlin/src/HAL/AVR/MarlinSerial.h index 7dd208e54e85..f47541f12dc5 100644 --- a/Marlin/src/HAL/AVR/MarlinSerial.h +++ b/Marlin/src/HAL/AVR/MarlinSerial.h @@ -280,7 +280,7 @@ static constexpr bool DROPPED_RX = false; static constexpr bool RX_FRAMING_ERRORS = false; static constexpr bool MAX_RX_QUEUED = false; - static constexpr bool RX_OVERRUNS = BOTH(HAS_DGUS_LCD, SERIAL_STATS_RX_BUFFER_OVERRUNS); + static constexpr bool RX_OVERRUNS = ALL(HAS_DGUS_LCD, SERIAL_STATS_RX_BUFFER_OVERRUNS); }; typedef Serial1Class< MarlinSerial< LCDSerialCfg > > MSerialLCD; diff --git a/Marlin/src/HAL/AVR/eeprom.cpp b/Marlin/src/HAL/AVR/eeprom.cpp index 8d084dec7fdf..6465e4702544 100644 --- a/Marlin/src/HAL/AVR/eeprom.cpp +++ b/Marlin/src/HAL/AVR/eeprom.cpp @@ -23,7 +23,7 @@ #include "../../inc/MarlinConfig.h" -#if EITHER(EEPROM_SETTINGS, SD_FIRMWARE_UPDATE) +#if ANY(EEPROM_SETTINGS, SD_FIRMWARE_UPDATE) /** * PersistentStore for Arduino-style EEPROM interface diff --git a/Marlin/src/HAL/AVR/fast_pwm.cpp b/Marlin/src/HAL/AVR/fast_pwm.cpp index 0b2b8fd0b3a4..6da68e6245d3 100644 --- a/Marlin/src/HAL/AVR/fast_pwm.cpp +++ b/Marlin/src/HAL/AVR/fast_pwm.cpp @@ -132,7 +132,7 @@ void MarlinHAL::set_pwm_frequency(const pin_t pin, const uint16_t f_desired) { DEBUG_ECHOLNPGM("f=", f); DEBUG_ECHOLNPGM("(prescaler loop)"); - LOOP_L_N(i, COUNT(prescaler)) { // Loop through all prescaler values + for (uint8_t i = 0; i < COUNT(prescaler); ++i) { // Loop through all prescaler values const uint32_t p = prescaler[i]; // Extend to 32 bits for calculations DEBUG_ECHOLNPGM("prescaler[", i, "]=", p); uint16_t res_fast_temp, res_pc_temp; @@ -232,7 +232,7 @@ void MarlinHAL::init_pwm_timers() { #endif }; - LOOP_L_N(i, COUNT(pwm_pin)) + for (uint8_t i = 0; i < COUNT(pwm_pin); ++i) set_pwm_frequency(pwm_pin[i], 1000); } diff --git a/Marlin/src/HAL/AVR/inc/SanityCheck.h b/Marlin/src/HAL/AVR/inc/SanityCheck.h index 665e68043a85..6a7e1728891d 100644 --- a/Marlin/src/HAL/AVR/inc/SanityCheck.h +++ b/Marlin/src/HAL/AVR/inc/SanityCheck.h @@ -95,11 +95,11 @@ /** * The Trinamic library includes SoftwareSerial.h, leading to a compile error. */ -#if BOTH(HAS_TRINAMIC_CONFIG, ENDSTOP_INTERRUPTS_FEATURE) +#if ALL(HAS_TRINAMIC_CONFIG, ENDSTOP_INTERRUPTS_FEATURE) #error "TMCStepper includes SoftwareSerial.h which is incompatible with ENDSTOP_INTERRUPTS_FEATURE. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif -#if BOTH(HAS_TMC_SW_SERIAL, MONITOR_DRIVER_STATUS) +#if ALL(HAS_TMC_SW_SERIAL, MONITOR_DRIVER_STATUS) #error "MONITOR_DRIVER_STATUS causes performance issues when used with SoftwareSerial-connected drivers. Disable MONITOR_DRIVER_STATUS or use hardware serial to continue." #endif diff --git a/Marlin/src/HAL/AVR/pinsDebug.h b/Marlin/src/HAL/AVR/pinsDebug.h index accd3c663f71..fc51f41ef81e 100644 --- a/Marlin/src/HAL/AVR/pinsDebug.h +++ b/Marlin/src/HAL/AVR/pinsDebug.h @@ -77,12 +77,12 @@ void PRINT_ARRAY_NAME(uint8_t x) { PGM_P const name_mem_pointer = (PGM_P)pgm_read_ptr(&pin_array[x].name); - LOOP_L_N(y, MAX_NAME_LENGTH) { + for (uint8_t y = 0; y < MAX_NAME_LENGTH; ++y) { char temp_char = pgm_read_byte(name_mem_pointer + y); if (temp_char != 0) SERIAL_CHAR(temp_char); else { - LOOP_L_N(i, MAX_NAME_LENGTH - y) SERIAL_CHAR(' '); + for (uint8_t i = 0; i < MAX_NAME_LENGTH - y; ++i) SERIAL_CHAR(' '); break; } } diff --git a/Marlin/src/HAL/AVR/u8g_com_HAL_AVR_sw_spi.cpp b/Marlin/src/HAL/AVR/u8g_com_HAL_AVR_sw_spi.cpp index 45b54379dba7..79bafe293967 100644 --- a/Marlin/src/HAL/AVR/u8g_com_HAL_AVR_sw_spi.cpp +++ b/Marlin/src/HAL/AVR/u8g_com_HAL_AVR_sw_spi.cpp @@ -88,7 +88,7 @@ void u8g_spiSend_sw_AVR_mode_0(uint8_t val) { volatile uint8_t *outData = u8g_outData, *outClock = u8g_outClock; U8G_ATOMIC_START(); - LOOP_L_N(i, 8) { + for (uint8_t i = 0; i < 8; ++i) { if (val & 0x80) *outData |= bitData; else @@ -108,7 +108,7 @@ void u8g_spiSend_sw_AVR_mode_3(uint8_t val) { volatile uint8_t *outData = u8g_outData, *outClock = u8g_outClock; U8G_ATOMIC_START(); - LOOP_L_N(i, 8) { + for (uint8_t i = 0; i < 8; ++i) { *outClock &= bitNotClock; if (val & 0x80) *outData |= bitData; diff --git a/Marlin/src/HAL/DUE/HAL_SPI.cpp b/Marlin/src/HAL/DUE/HAL_SPI.cpp index f5bcaacee505..63ebf164f2b1 100644 --- a/Marlin/src/HAL/DUE/HAL_SPI.cpp +++ b/Marlin/src/HAL/DUE/HAL_SPI.cpp @@ -42,7 +42,7 @@ // Public functions // ------------------------ -#if EITHER(DUE_SOFTWARE_SPI, FORCE_SOFT_SPI) +#if ANY(DUE_SOFTWARE_SPI, FORCE_SOFT_SPI) // ------------------------ // Software SPI diff --git a/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.cpp b/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.cpp index 904924793b4c..86c8a4847026 100644 --- a/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.cpp +++ b/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.cpp @@ -81,7 +81,7 @@ Pio *SCK_pPio, *MOSI_pPio; uint32_t SCK_dwMask, MOSI_dwMask; void u8g_spiSend_sw_DUE_mode_0(uint8_t val) { // 3MHz - LOOP_L_N(i, 8) { + for (uint8_t i = 0; i < 8; ++i) { if (val & 0x80) MOSI_pPio->PIO_SODR = MOSI_dwMask; else @@ -95,7 +95,7 @@ void u8g_spiSend_sw_DUE_mode_0(uint8_t val) { // 3MHz } void u8g_spiSend_sw_DUE_mode_3(uint8_t val) { // 3.5MHz - LOOP_L_N(i, 8) { + for (uint8_t i = 0; i < 8; ++i) { SCK_pPio->PIO_CODR = SCK_dwMask; DELAY_NS(50); if (val & 0x80) diff --git a/Marlin/src/HAL/DUE/fastio/G2_PWM.h b/Marlin/src/HAL/DUE/fastio/G2_PWM.h index dc4edffff851..2afe246ceaea 100644 --- a/Marlin/src/HAL/DUE/fastio/G2_PWM.h +++ b/Marlin/src/HAL/DUE/fastio/G2_PWM.h @@ -63,7 +63,7 @@ extern PWM_map ISR_table[NUM_PWMS]; extern uint32_t motor_current_setting[3]; #define IR_BIT(p) (WITHIN(p, 0, 3) ? (p) : (p) + 4) -#define COPY_ACTIVE_TABLE() do{ LOOP_L_N(i, 6) work_table[i] = active_table[i]; }while(0) +#define COPY_ACTIVE_TABLE() do{ for (uint8_t i = 0; i < 6; ++i) work_table[i] = active_table[i]; }while(0) #define PWM_MR0 19999 // base repetition rate minus one count - 20mS #define PWM_PR 24 // prescaler value - prescaler divide by 24 + 1 - 1 MHz output diff --git a/Marlin/src/HAL/DUE/inc/Conditionals_post.h b/Marlin/src/HAL/DUE/inc/Conditionals_post.h index ce6d3fdde27f..295596b78b19 100644 --- a/Marlin/src/HAL/DUE/inc/Conditionals_post.h +++ b/Marlin/src/HAL/DUE/inc/Conditionals_post.h @@ -23,6 +23,6 @@ #if USE_FALLBACK_EEPROM #define FLASH_EEPROM_EMULATION -#elif EITHER(I2C_EEPROM, SPI_EEPROM) +#elif ANY(I2C_EEPROM, SPI_EEPROM) #define USE_SHARED_EEPROM 1 #endif diff --git a/Marlin/src/HAL/DUE/usb/genclk.h b/Marlin/src/HAL/DUE/usb/genclk.h index cde03bc0d107..45eba5873f8c 100644 --- a/Marlin/src/HAL/DUE/usb/genclk.h +++ b/Marlin/src/HAL/DUE/usb/genclk.h @@ -74,17 +74,17 @@ extern "C" { //@{ enum genclk_source { - GENCLK_PCK_SRC_SLCK_RC = 0, //!< Internal 32kHz RC oscillator as PCK source clock - GENCLK_PCK_SRC_SLCK_XTAL = 1, //!< External 32kHz crystal oscillator as PCK source clock - GENCLK_PCK_SRC_SLCK_BYPASS = 2, //!< External 32kHz bypass oscillator as PCK source clock - GENCLK_PCK_SRC_MAINCK_4M_RC = 3, //!< Internal 4MHz RC oscillator as PCK source clock - GENCLK_PCK_SRC_MAINCK_8M_RC = 4, //!< Internal 8MHz RC oscillator as PCK source clock - GENCLK_PCK_SRC_MAINCK_12M_RC = 5, //!< Internal 12MHz RC oscillator as PCK source clock - GENCLK_PCK_SRC_MAINCK_XTAL = 6, //!< External crystal oscillator as PCK source clock - GENCLK_PCK_SRC_MAINCK_BYPASS = 7, //!< External bypass oscillator as PCK source clock - GENCLK_PCK_SRC_PLLACK = 8, //!< Use PLLACK as PCK source clock - GENCLK_PCK_SRC_PLLBCK = 9, //!< Use PLLBCK as PCK source clock - GENCLK_PCK_SRC_MCK = 10, //!< Use Master Clk as PCK source clock + GENCLK_PCK_SRC_SLCK_RC = 0, //!< Internal 32kHz RC oscillator as PCK source clock + GENCLK_PCK_SRC_SLCK_XTAL = 1, //!< External 32kHz crystal oscillator as PCK source clock + GENCLK_PCK_SRC_SLCK_BYPASS = 2, //!< External 32kHz bypass oscillator as PCK source clock + GENCLK_PCK_SRC_MAINCK_4M_RC = 3, //!< Internal 4MHz RC oscillator as PCK source clock + GENCLK_PCK_SRC_MAINCK_8M_RC = 4, //!< Internal 8MHz RC oscillator as PCK source clock + GENCLK_PCK_SRC_MAINCK_12M_RC = 5, //!< Internal 12MHz RC oscillator as PCK source clock + GENCLK_PCK_SRC_MAINCK_XTAL = 6, //!< External crystal oscillator as PCK source clock + GENCLK_PCK_SRC_MAINCK_BYPASS = 7, //!< External bypass oscillator as PCK source clock + GENCLK_PCK_SRC_PLLACK = 8, //!< Use PLLACK as PCK source clock + GENCLK_PCK_SRC_PLLBCK = 9, //!< Use PLLBCK as PCK source clock + GENCLK_PCK_SRC_MCK = 10, //!< Use Master Clk as PCK source clock }; //@} @@ -93,176 +93,162 @@ enum genclk_source { //@{ enum genclk_divider { - GENCLK_PCK_PRES_1 = PMC_PCK_PRES_CLK_1, //!< Set PCK clock prescaler to 1 - GENCLK_PCK_PRES_2 = PMC_PCK_PRES_CLK_2, //!< Set PCK clock prescaler to 2 - GENCLK_PCK_PRES_4 = PMC_PCK_PRES_CLK_4, //!< Set PCK clock prescaler to 4 - GENCLK_PCK_PRES_8 = PMC_PCK_PRES_CLK_8, //!< Set PCK clock prescaler to 8 - GENCLK_PCK_PRES_16 = PMC_PCK_PRES_CLK_16, //!< Set PCK clock prescaler to 16 - GENCLK_PCK_PRES_32 = PMC_PCK_PRES_CLK_32, //!< Set PCK clock prescaler to 32 - GENCLK_PCK_PRES_64 = PMC_PCK_PRES_CLK_64, //!< Set PCK clock prescaler to 64 + GENCLK_PCK_PRES_1 = PMC_PCK_PRES_CLK_1, //!< Set PCK clock prescaler to 1 + GENCLK_PCK_PRES_2 = PMC_PCK_PRES_CLK_2, //!< Set PCK clock prescaler to 2 + GENCLK_PCK_PRES_4 = PMC_PCK_PRES_CLK_4, //!< Set PCK clock prescaler to 4 + GENCLK_PCK_PRES_8 = PMC_PCK_PRES_CLK_8, //!< Set PCK clock prescaler to 8 + GENCLK_PCK_PRES_16 = PMC_PCK_PRES_CLK_16, //!< Set PCK clock prescaler to 16 + GENCLK_PCK_PRES_32 = PMC_PCK_PRES_CLK_32, //!< Set PCK clock prescaler to 32 + GENCLK_PCK_PRES_64 = PMC_PCK_PRES_CLK_64, //!< Set PCK clock prescaler to 64 }; //@} struct genclk_config { - uint32_t ctrl; + uint32_t ctrl; }; -static inline void genclk_config_defaults(struct genclk_config *p_cfg, - uint32_t ul_id) -{ - ul_id = ul_id; - p_cfg->ctrl = 0; +static inline void genclk_config_defaults(struct genclk_config *p_cfg, uint32_t ul_id) { + ul_id = ul_id; + p_cfg->ctrl = 0; } -static inline void genclk_config_read(struct genclk_config *p_cfg, - uint32_t ul_id) -{ - p_cfg->ctrl = PMC->PMC_PCK[ul_id]; +static inline void genclk_config_read(struct genclk_config *p_cfg, uint32_t ul_id) { + p_cfg->ctrl = PMC->PMC_PCK[ul_id]; } -static inline void genclk_config_write(const struct genclk_config *p_cfg, - uint32_t ul_id) -{ - PMC->PMC_PCK[ul_id] = p_cfg->ctrl; +static inline void genclk_config_write(const struct genclk_config *p_cfg, uint32_t ul_id) { + PMC->PMC_PCK[ul_id] = p_cfg->ctrl; } //! \name Programmable Clock Source and Prescaler configuration //@{ -static inline void genclk_config_set_source(struct genclk_config *p_cfg, - enum genclk_source e_src) -{ - p_cfg->ctrl &= (~PMC_PCK_CSS_Msk); - - switch (e_src) { - case GENCLK_PCK_SRC_SLCK_RC: - case GENCLK_PCK_SRC_SLCK_XTAL: - case GENCLK_PCK_SRC_SLCK_BYPASS: - p_cfg->ctrl |= (PMC_PCK_CSS_SLOW_CLK); - break; - - case GENCLK_PCK_SRC_MAINCK_4M_RC: - case GENCLK_PCK_SRC_MAINCK_8M_RC: - case GENCLK_PCK_SRC_MAINCK_12M_RC: - case GENCLK_PCK_SRC_MAINCK_XTAL: - case GENCLK_PCK_SRC_MAINCK_BYPASS: - p_cfg->ctrl |= (PMC_PCK_CSS_MAIN_CLK); - break; - - case GENCLK_PCK_SRC_PLLACK: - p_cfg->ctrl |= (PMC_PCK_CSS_PLLA_CLK); - break; - - case GENCLK_PCK_SRC_PLLBCK: - p_cfg->ctrl |= (PMC_PCK_CSS_UPLL_CLK); - break; - - case GENCLK_PCK_SRC_MCK: - p_cfg->ctrl |= (PMC_PCK_CSS_MCK); - break; - } +static inline void genclk_config_set_source(struct genclk_config *p_cfg, enum genclk_source e_src) { + p_cfg->ctrl &= (~PMC_PCK_CSS_Msk); + + switch (e_src) { + case GENCLK_PCK_SRC_SLCK_RC: + case GENCLK_PCK_SRC_SLCK_XTAL: + case GENCLK_PCK_SRC_SLCK_BYPASS: + p_cfg->ctrl |= (PMC_PCK_CSS_SLOW_CLK); + break; + + case GENCLK_PCK_SRC_MAINCK_4M_RC: + case GENCLK_PCK_SRC_MAINCK_8M_RC: + case GENCLK_PCK_SRC_MAINCK_12M_RC: + case GENCLK_PCK_SRC_MAINCK_XTAL: + case GENCLK_PCK_SRC_MAINCK_BYPASS: + p_cfg->ctrl |= (PMC_PCK_CSS_MAIN_CLK); + break; + + case GENCLK_PCK_SRC_PLLACK: + p_cfg->ctrl |= (PMC_PCK_CSS_PLLA_CLK); + break; + + case GENCLK_PCK_SRC_PLLBCK: + p_cfg->ctrl |= (PMC_PCK_CSS_UPLL_CLK); + break; + + case GENCLK_PCK_SRC_MCK: + p_cfg->ctrl |= (PMC_PCK_CSS_MCK); + break; + } } -static inline void genclk_config_set_divider(struct genclk_config *p_cfg, - uint32_t e_divider) -{ - p_cfg->ctrl &= ~PMC_PCK_PRES_Msk; - p_cfg->ctrl |= e_divider; +static inline void genclk_config_set_divider(struct genclk_config *p_cfg, uint32_t e_divider) { + p_cfg->ctrl &= ~PMC_PCK_PRES_Msk; + p_cfg->ctrl |= e_divider; } //@} -static inline void genclk_enable(const struct genclk_config *p_cfg, - uint32_t ul_id) -{ - PMC->PMC_PCK[ul_id] = p_cfg->ctrl; - pmc_enable_pck(ul_id); +static inline void genclk_enable(const struct genclk_config *p_cfg, uint32_t ul_id) { + PMC->PMC_PCK[ul_id] = p_cfg->ctrl; + pmc_enable_pck(ul_id); } -static inline void genclk_disable(uint32_t ul_id) -{ - pmc_disable_pck(ul_id); +static inline void genclk_disable(uint32_t ul_id) { + pmc_disable_pck(ul_id); } -static inline void genclk_enable_source(enum genclk_source e_src) -{ - switch (e_src) { - case GENCLK_PCK_SRC_SLCK_RC: - if (!osc_is_ready(OSC_SLCK_32K_RC)) { - osc_enable(OSC_SLCK_32K_RC); - osc_wait_ready(OSC_SLCK_32K_RC); - } - break; - - case GENCLK_PCK_SRC_SLCK_XTAL: - if (!osc_is_ready(OSC_SLCK_32K_XTAL)) { - osc_enable(OSC_SLCK_32K_XTAL); - osc_wait_ready(OSC_SLCK_32K_XTAL); - } - break; - - case GENCLK_PCK_SRC_SLCK_BYPASS: - if (!osc_is_ready(OSC_SLCK_32K_BYPASS)) { - osc_enable(OSC_SLCK_32K_BYPASS); - osc_wait_ready(OSC_SLCK_32K_BYPASS); - } - break; - - case GENCLK_PCK_SRC_MAINCK_4M_RC: - if (!osc_is_ready(OSC_MAINCK_4M_RC)) { - osc_enable(OSC_MAINCK_4M_RC); - osc_wait_ready(OSC_MAINCK_4M_RC); - } - break; - - case GENCLK_PCK_SRC_MAINCK_8M_RC: - if (!osc_is_ready(OSC_MAINCK_8M_RC)) { - osc_enable(OSC_MAINCK_8M_RC); - osc_wait_ready(OSC_MAINCK_8M_RC); - } - break; - - case GENCLK_PCK_SRC_MAINCK_12M_RC: - if (!osc_is_ready(OSC_MAINCK_12M_RC)) { - osc_enable(OSC_MAINCK_12M_RC); - osc_wait_ready(OSC_MAINCK_12M_RC); - } - break; - - case GENCLK_PCK_SRC_MAINCK_XTAL: - if (!osc_is_ready(OSC_MAINCK_XTAL)) { - osc_enable(OSC_MAINCK_XTAL); - osc_wait_ready(OSC_MAINCK_XTAL); - } - break; - - case GENCLK_PCK_SRC_MAINCK_BYPASS: - if (!osc_is_ready(OSC_MAINCK_BYPASS)) { - osc_enable(OSC_MAINCK_BYPASS); - osc_wait_ready(OSC_MAINCK_BYPASS); - } - break; - -#ifdef CONFIG_PLL0_SOURCE - case GENCLK_PCK_SRC_PLLACK: - pll_enable_config_defaults(0); - break; -#endif - -#ifdef CONFIG_PLL1_SOURCE - case GENCLK_PCK_SRC_PLLBCK: - pll_enable_config_defaults(1); - break; -#endif - - case GENCLK_PCK_SRC_MCK: - break; - - default: - Assert(false); - break; - } +static inline void genclk_enable_source(enum genclk_source e_src) { + switch (e_src) { + case GENCLK_PCK_SRC_SLCK_RC: + if (!osc_is_ready(OSC_SLCK_32K_RC)) { + osc_enable(OSC_SLCK_32K_RC); + osc_wait_ready(OSC_SLCK_32K_RC); + } + break; + + case GENCLK_PCK_SRC_SLCK_XTAL: + if (!osc_is_ready(OSC_SLCK_32K_XTAL)) { + osc_enable(OSC_SLCK_32K_XTAL); + osc_wait_ready(OSC_SLCK_32K_XTAL); + } + break; + + case GENCLK_PCK_SRC_SLCK_BYPASS: + if (!osc_is_ready(OSC_SLCK_32K_BYPASS)) { + osc_enable(OSC_SLCK_32K_BYPASS); + osc_wait_ready(OSC_SLCK_32K_BYPASS); + } + break; + + case GENCLK_PCK_SRC_MAINCK_4M_RC: + if (!osc_is_ready(OSC_MAINCK_4M_RC)) { + osc_enable(OSC_MAINCK_4M_RC); + osc_wait_ready(OSC_MAINCK_4M_RC); + } + break; + + case GENCLK_PCK_SRC_MAINCK_8M_RC: + if (!osc_is_ready(OSC_MAINCK_8M_RC)) { + osc_enable(OSC_MAINCK_8M_RC); + osc_wait_ready(OSC_MAINCK_8M_RC); + } + break; + + case GENCLK_PCK_SRC_MAINCK_12M_RC: + if (!osc_is_ready(OSC_MAINCK_12M_RC)) { + osc_enable(OSC_MAINCK_12M_RC); + osc_wait_ready(OSC_MAINCK_12M_RC); + } + break; + + case GENCLK_PCK_SRC_MAINCK_XTAL: + if (!osc_is_ready(OSC_MAINCK_XTAL)) { + osc_enable(OSC_MAINCK_XTAL); + osc_wait_ready(OSC_MAINCK_XTAL); + } + break; + + case GENCLK_PCK_SRC_MAINCK_BYPASS: + if (!osc_is_ready(OSC_MAINCK_BYPASS)) { + osc_enable(OSC_MAINCK_BYPASS); + osc_wait_ready(OSC_MAINCK_BYPASS); + } + break; + + #ifdef CONFIG_PLL0_SOURCE + case GENCLK_PCK_SRC_PLLACK: + pll_enable_config_defaults(0); + break; + #endif + + #ifdef CONFIG_PLL1_SOURCE + case GENCLK_PCK_SRC_PLLBCK: + pll_enable_config_defaults(1); + break; + #endif + + case GENCLK_PCK_SRC_MCK: + break; + + default: + Assert(false); + break; + } } //! @} diff --git a/Marlin/src/HAL/DUE/usb/osc.h b/Marlin/src/HAL/DUE/usb/osc.h index 953bcbbed1d3..c0ae24381a39 100644 --- a/Marlin/src/HAL/DUE/usb/osc.h +++ b/Marlin/src/HAL/DUE/usb/osc.h @@ -62,28 +62,28 @@ extern "C" { * should be defined by the board code, otherwise default value are used. */ #ifndef BOARD_FREQ_SLCK_XTAL -# warning The board slow clock xtal frequency has not been defined. -# define BOARD_FREQ_SLCK_XTAL (32768UL) + #warning The board slow clock xtal frequency has not been defined. + #define BOARD_FREQ_SLCK_XTAL (32768UL) #endif #ifndef BOARD_FREQ_SLCK_BYPASS -# warning The board slow clock bypass frequency has not been defined. -# define BOARD_FREQ_SLCK_BYPASS (32768UL) + #warning The board slow clock bypass frequency has not been defined. + #define BOARD_FREQ_SLCK_BYPASS (32768UL) #endif #ifndef BOARD_FREQ_MAINCK_XTAL -# warning The board main clock xtal frequency has not been defined. -# define BOARD_FREQ_MAINCK_XTAL (12000000UL) + #warning The board main clock xtal frequency has not been defined. + #define BOARD_FREQ_MAINCK_XTAL (12000000UL) #endif #ifndef BOARD_FREQ_MAINCK_BYPASS -# warning The board main clock bypass frequency has not been defined. -# define BOARD_FREQ_MAINCK_BYPASS (12000000UL) + #warning The board main clock bypass frequency has not been defined. + #define BOARD_FREQ_MAINCK_BYPASS (12000000UL) #endif #ifndef BOARD_OSC_STARTUP_US -# warning The board main clock xtal startup time has not been defined. -# define BOARD_OSC_STARTUP_US (15625UL) + #warning The board main clock xtal startup time has not been defined. + #define BOARD_OSC_STARTUP_US (15625UL) #endif /** @@ -115,122 +115,118 @@ extern "C" { #define OSC_MAINCK_BYPASS_HZ BOARD_FREQ_MAINCK_BYPASS //!< External bypass oscillator. //@} -static inline void osc_enable(uint32_t ul_id) -{ - switch (ul_id) { - case OSC_SLCK_32K_RC: - break; +static inline void osc_enable(uint32_t ul_id) { + switch (ul_id) { + case OSC_SLCK_32K_RC: + break; - case OSC_SLCK_32K_XTAL: - pmc_switch_sclk_to_32kxtal(PMC_OSC_XTAL); - break; + case OSC_SLCK_32K_XTAL: + pmc_switch_sclk_to_32kxtal(PMC_OSC_XTAL); + break; - case OSC_SLCK_32K_BYPASS: - pmc_switch_sclk_to_32kxtal(PMC_OSC_BYPASS); - break; + case OSC_SLCK_32K_BYPASS: + pmc_switch_sclk_to_32kxtal(PMC_OSC_BYPASS); + break; - case OSC_MAINCK_4M_RC: - pmc_switch_mainck_to_fastrc(CKGR_MOR_MOSCRCF_4_MHz); - break; + case OSC_MAINCK_4M_RC: + pmc_switch_mainck_to_fastrc(CKGR_MOR_MOSCRCF_4_MHz); + break; - case OSC_MAINCK_8M_RC: - pmc_switch_mainck_to_fastrc(CKGR_MOR_MOSCRCF_8_MHz); - break; + case OSC_MAINCK_8M_RC: + pmc_switch_mainck_to_fastrc(CKGR_MOR_MOSCRCF_8_MHz); + break; - case OSC_MAINCK_12M_RC: - pmc_switch_mainck_to_fastrc(CKGR_MOR_MOSCRCF_12_MHz); - break; + case OSC_MAINCK_12M_RC: + pmc_switch_mainck_to_fastrc(CKGR_MOR_MOSCRCF_12_MHz); + break; - case OSC_MAINCK_XTAL: - pmc_switch_mainck_to_xtal(PMC_OSC_XTAL/*, - pmc_us_to_moscxtst(BOARD_OSC_STARTUP_US, - OSC_SLCK_32K_RC_HZ)*/); - break; + case OSC_MAINCK_XTAL: + pmc_switch_mainck_to_xtal(PMC_OSC_XTAL/*, + pmc_us_to_moscxtst(BOARD_OSC_STARTUP_US, + OSC_SLCK_32K_RC_HZ)*/); + break; - case OSC_MAINCK_BYPASS: - pmc_switch_mainck_to_xtal(PMC_OSC_BYPASS/*, - pmc_us_to_moscxtst(BOARD_OSC_STARTUP_US, - OSC_SLCK_32K_RC_HZ)*/); - break; - } + case OSC_MAINCK_BYPASS: + pmc_switch_mainck_to_xtal(PMC_OSC_BYPASS/*, + pmc_us_to_moscxtst(BOARD_OSC_STARTUP_US, + OSC_SLCK_32K_RC_HZ)*/); + break; + } } -static inline void osc_disable(uint32_t ul_id) -{ - switch (ul_id) { - case OSC_SLCK_32K_RC: - case OSC_SLCK_32K_XTAL: - case OSC_SLCK_32K_BYPASS: - break; - - case OSC_MAINCK_4M_RC: - case OSC_MAINCK_8M_RC: - case OSC_MAINCK_12M_RC: - pmc_osc_disable_fastrc(); - break; - - case OSC_MAINCK_XTAL: - pmc_osc_disable_xtal(PMC_OSC_XTAL); - break; - - case OSC_MAINCK_BYPASS: - pmc_osc_disable_xtal(PMC_OSC_BYPASS); - break; - } +static inline void osc_disable(uint32_t ul_id) { + switch (ul_id) { + case OSC_SLCK_32K_RC: + case OSC_SLCK_32K_XTAL: + case OSC_SLCK_32K_BYPASS: + break; + + case OSC_MAINCK_4M_RC: + case OSC_MAINCK_8M_RC: + case OSC_MAINCK_12M_RC: + pmc_osc_disable_fastrc(); + break; + + case OSC_MAINCK_XTAL: + pmc_osc_disable_xtal(PMC_OSC_XTAL); + break; + + case OSC_MAINCK_BYPASS: + pmc_osc_disable_xtal(PMC_OSC_BYPASS); + break; + } } -static inline bool osc_is_ready(uint32_t ul_id) -{ - switch (ul_id) { - case OSC_SLCK_32K_RC: - return 1; - - case OSC_SLCK_32K_XTAL: - case OSC_SLCK_32K_BYPASS: - return pmc_osc_is_ready_32kxtal(); - - case OSC_MAINCK_4M_RC: - case OSC_MAINCK_8M_RC: - case OSC_MAINCK_12M_RC: - case OSC_MAINCK_XTAL: - case OSC_MAINCK_BYPASS: - return pmc_osc_is_ready_mainck(); - } - - return 0; +static inline bool osc_is_ready(uint32_t ul_id) { + switch (ul_id) { + case OSC_SLCK_32K_RC: + return 1; + + case OSC_SLCK_32K_XTAL: + case OSC_SLCK_32K_BYPASS: + return pmc_osc_is_ready_32kxtal(); + + case OSC_MAINCK_4M_RC: + case OSC_MAINCK_8M_RC: + case OSC_MAINCK_12M_RC: + case OSC_MAINCK_XTAL: + case OSC_MAINCK_BYPASS: + return pmc_osc_is_ready_mainck(); + } + + return 0; } -static inline uint32_t osc_get_rate(uint32_t ul_id) -{ - switch (ul_id) { - case OSC_SLCK_32K_RC: - return OSC_SLCK_32K_RC_HZ; +static inline uint32_t osc_get_rate(uint32_t ul_id) { + switch (ul_id) { + case OSC_SLCK_32K_RC: + return OSC_SLCK_32K_RC_HZ; - case OSC_SLCK_32K_XTAL: - return BOARD_FREQ_SLCK_XTAL; + case OSC_SLCK_32K_XTAL: + return BOARD_FREQ_SLCK_XTAL; - case OSC_SLCK_32K_BYPASS: - return BOARD_FREQ_SLCK_BYPASS; + case OSC_SLCK_32K_BYPASS: + return BOARD_FREQ_SLCK_BYPASS; - case OSC_MAINCK_4M_RC: - return OSC_MAINCK_4M_RC_HZ; + case OSC_MAINCK_4M_RC: + return OSC_MAINCK_4M_RC_HZ; - case OSC_MAINCK_8M_RC: - return OSC_MAINCK_8M_RC_HZ; + case OSC_MAINCK_8M_RC: + return OSC_MAINCK_8M_RC_HZ; - case OSC_MAINCK_12M_RC: - return OSC_MAINCK_12M_RC_HZ; + case OSC_MAINCK_12M_RC: + return OSC_MAINCK_12M_RC_HZ; - case OSC_MAINCK_XTAL: - return BOARD_FREQ_MAINCK_XTAL; + case OSC_MAINCK_XTAL: + return BOARD_FREQ_MAINCK_XTAL; - case OSC_MAINCK_BYPASS: - return BOARD_FREQ_MAINCK_BYPASS; - } + case OSC_MAINCK_BYPASS: + return BOARD_FREQ_MAINCK_BYPASS; + } - return 0; + return 0; } /** @@ -241,11 +237,10 @@ static inline uint32_t osc_get_rate(uint32_t ul_id) * * \param id A number identifying the oscillator to wait for. */ -static inline void osc_wait_ready(uint8_t id) -{ - while (!osc_is_ready(id)) { - /* Do nothing */ - } +static inline void osc_wait_ready(uint8_t id) { + while (!osc_is_ready(id)) { + /* Do nothing */ + } } //! @} diff --git a/Marlin/src/HAL/DUE/usb/pll.h b/Marlin/src/HAL/DUE/usb/pll.h index 8eaf27672b25..d25a1f65d09b 100644 --- a/Marlin/src/HAL/DUE/usb/pll.h +++ b/Marlin/src/HAL/DUE/usb/pll.h @@ -77,22 +77,22 @@ extern "C" { #define PLL_COUNT 0x3FU enum pll_source { - PLL_SRC_MAINCK_4M_RC = OSC_MAINCK_4M_RC, //!< Internal 4MHz RC oscillator. - PLL_SRC_MAINCK_8M_RC = OSC_MAINCK_8M_RC, //!< Internal 8MHz RC oscillator. - PLL_SRC_MAINCK_12M_RC = OSC_MAINCK_12M_RC, //!< Internal 12MHz RC oscillator. - PLL_SRC_MAINCK_XTAL = OSC_MAINCK_XTAL, //!< External crystal oscillator. - PLL_SRC_MAINCK_BYPASS = OSC_MAINCK_BYPASS, //!< External bypass oscillator. - PLL_NR_SOURCES, //!< Number of PLL sources. + PLL_SRC_MAINCK_4M_RC = OSC_MAINCK_4M_RC, //!< Internal 4MHz RC oscillator. + PLL_SRC_MAINCK_8M_RC = OSC_MAINCK_8M_RC, //!< Internal 8MHz RC oscillator. + PLL_SRC_MAINCK_12M_RC = OSC_MAINCK_12M_RC, //!< Internal 12MHz RC oscillator. + PLL_SRC_MAINCK_XTAL = OSC_MAINCK_XTAL, //!< External crystal oscillator. + PLL_SRC_MAINCK_BYPASS = OSC_MAINCK_BYPASS, //!< External bypass oscillator. + PLL_NR_SOURCES, //!< Number of PLL sources. }; struct pll_config { - uint32_t ctrl; + uint32_t ctrl; }; #define pll_get_default_rate(pll_id) \ - ((osc_get_rate(CONFIG_PLL##pll_id##_SOURCE) \ - * CONFIG_PLL##pll_id##_MUL) \ - / CONFIG_PLL##pll_id##_DIV) + ((osc_get_rate(CONFIG_PLL##pll_id##_SOURCE) \ + * CONFIG_PLL##pll_id##_MUL) \ + / CONFIG_PLL##pll_id##_DIV) /* Force UTMI PLL parameters (Hardware defined) */ #ifdef CONFIG_PLL1_SOURCE @@ -113,145 +113,130 @@ struct pll_config { * is hidden in this implementation. Use mul as mul effective value. */ static inline void pll_config_init(struct pll_config *p_cfg, - enum pll_source e_src, uint32_t ul_div, uint32_t ul_mul) -{ - uint32_t vco_hz; - - Assert(e_src < PLL_NR_SOURCES); - - if (ul_div == 0 && ul_mul == 0) { /* Must only be true for UTMI PLL */ - p_cfg->ctrl = CKGR_UCKR_UPLLCOUNT(PLL_COUNT); - } else { /* PLLA */ - /* Calculate internal VCO frequency */ - vco_hz = osc_get_rate(e_src) / ul_div; - Assert(vco_hz >= PLL_INPUT_MIN_HZ); - Assert(vco_hz <= PLL_INPUT_MAX_HZ); - - vco_hz *= ul_mul; - Assert(vco_hz >= PLL_OUTPUT_MIN_HZ); - Assert(vco_hz <= PLL_OUTPUT_MAX_HZ); - - /* PMC hardware will automatically make it mul+1 */ - p_cfg->ctrl = CKGR_PLLAR_MULA(ul_mul - 1) | CKGR_PLLAR_DIVA(ul_div) | CKGR_PLLAR_PLLACOUNT(PLL_COUNT); - } + enum pll_source e_src, uint32_t ul_div, uint32_t ul_mul) { + uint32_t vco_hz; + + Assert(e_src < PLL_NR_SOURCES); + + if (ul_div == 0 && ul_mul == 0) { /* Must only be true for UTMI PLL */ + p_cfg->ctrl = CKGR_UCKR_UPLLCOUNT(PLL_COUNT); + } + else { /* PLLA */ + /* Calculate internal VCO frequency */ + vco_hz = osc_get_rate(e_src) / ul_div; + Assert(vco_hz >= PLL_INPUT_MIN_HZ); + Assert(vco_hz <= PLL_INPUT_MAX_HZ); + + vco_hz *= ul_mul; + Assert(vco_hz >= PLL_OUTPUT_MIN_HZ); + Assert(vco_hz <= PLL_OUTPUT_MAX_HZ); + + /* PMC hardware will automatically make it mul+1 */ + p_cfg->ctrl = CKGR_PLLAR_MULA(ul_mul - 1) | CKGR_PLLAR_DIVA(ul_div) | CKGR_PLLAR_PLLACOUNT(PLL_COUNT); + } } -#define pll_config_defaults(cfg, pll_id) \ - pll_config_init(cfg, \ - CONFIG_PLL##pll_id##_SOURCE, \ - CONFIG_PLL##pll_id##_DIV, \ - CONFIG_PLL##pll_id##_MUL) - -static inline void pll_config_read(struct pll_config *p_cfg, uint32_t ul_pll_id) -{ - Assert(ul_pll_id < NR_PLLS); - - if (ul_pll_id == PLLA_ID) { - p_cfg->ctrl = PMC->CKGR_PLLAR; - } else { - p_cfg->ctrl = PMC->CKGR_UCKR; - } +#define pll_config_defaults(cfg, pll_id) \ + pll_config_init(cfg, \ + CONFIG_PLL##pll_id##_SOURCE, \ + CONFIG_PLL##pll_id##_DIV, \ + CONFIG_PLL##pll_id##_MUL) + +static inline void pll_config_read(struct pll_config *p_cfg, uint32_t ul_pll_id) { + Assert(ul_pll_id < NR_PLLS); + p_cfg->ctrl = ul_pll_id == PLLA_ID ? PMC->CKGR_PLLAR : PMC->CKGR_UCKR; } -static inline void pll_config_write(const struct pll_config *p_cfg, uint32_t ul_pll_id) -{ - Assert(ul_pll_id < NR_PLLS); +static inline void pll_config_write(const struct pll_config *p_cfg, uint32_t ul_pll_id) { + Assert(ul_pll_id < NR_PLLS); - if (ul_pll_id == PLLA_ID) { - pmc_disable_pllack(); // Always stop PLL first! - PMC->CKGR_PLLAR = CKGR_PLLAR_ONE | p_cfg->ctrl; - } else { - PMC->CKGR_UCKR = p_cfg->ctrl; - } + if (ul_pll_id == PLLA_ID) { + pmc_disable_pllack(); // Always stop PLL first! + PMC->CKGR_PLLAR = CKGR_PLLAR_ONE | p_cfg->ctrl; + } + else + PMC->CKGR_UCKR = p_cfg->ctrl; } -static inline void pll_enable(const struct pll_config *p_cfg, uint32_t ul_pll_id) -{ - Assert(ul_pll_id < NR_PLLS); +static inline void pll_enable(const struct pll_config *p_cfg, uint32_t ul_pll_id) { + Assert(ul_pll_id < NR_PLLS); - if (ul_pll_id == PLLA_ID) { - pmc_disable_pllack(); // Always stop PLL first! - PMC->CKGR_PLLAR = CKGR_PLLAR_ONE | p_cfg->ctrl; - } else { - PMC->CKGR_UCKR = p_cfg->ctrl | CKGR_UCKR_UPLLEN; - } + if (ul_pll_id == PLLA_ID) { + pmc_disable_pllack(); // Always stop PLL first! + PMC->CKGR_PLLAR = CKGR_PLLAR_ONE | p_cfg->ctrl; + } + else + PMC->CKGR_UCKR = p_cfg->ctrl | CKGR_UCKR_UPLLEN; } /** * \note This will only disable the selected PLL, not the underlying oscillator (mainck). */ -static inline void pll_disable(uint32_t ul_pll_id) -{ - Assert(ul_pll_id < NR_PLLS); - - if (ul_pll_id == PLLA_ID) { - pmc_disable_pllack(); - } else { - PMC->CKGR_UCKR &= ~CKGR_UCKR_UPLLEN; - } +static inline void pll_disable(uint32_t ul_pll_id) { + Assert(ul_pll_id < NR_PLLS); + + if (ul_pll_id == PLLA_ID) + pmc_disable_pllack(); + else + PMC->CKGR_UCKR &= ~CKGR_UCKR_UPLLEN; } -static inline uint32_t pll_is_locked(uint32_t ul_pll_id) -{ - Assert(ul_pll_id < NR_PLLS); +static inline uint32_t pll_is_locked(uint32_t ul_pll_id) { + Assert(ul_pll_id < NR_PLLS); - if (ul_pll_id == PLLA_ID) { - return pmc_is_locked_pllack(); - } else { - return pmc_is_locked_upll(); - } + if (ul_pll_id == PLLA_ID) + return pmc_is_locked_pllack(); + else + return pmc_is_locked_upll(); } -static inline void pll_enable_source(enum pll_source e_src) -{ - switch (e_src) { - case PLL_SRC_MAINCK_4M_RC: - case PLL_SRC_MAINCK_8M_RC: - case PLL_SRC_MAINCK_12M_RC: - case PLL_SRC_MAINCK_XTAL: - case PLL_SRC_MAINCK_BYPASS: - osc_enable(e_src); - osc_wait_ready(e_src); - break; - - default: - Assert(false); - break; - } +static inline void pll_enable_source(enum pll_source e_src) { + switch (e_src) { + case PLL_SRC_MAINCK_4M_RC: + case PLL_SRC_MAINCK_8M_RC: + case PLL_SRC_MAINCK_12M_RC: + case PLL_SRC_MAINCK_XTAL: + case PLL_SRC_MAINCK_BYPASS: + osc_enable(e_src); + osc_wait_ready(e_src); + break; + + default: + Assert(false); + break; + } } -static inline void pll_enable_config_defaults(unsigned int ul_pll_id) -{ - struct pll_config pllcfg; - - if (pll_is_locked(ul_pll_id)) { - return; // Pll already running - } - switch (ul_pll_id) { -#ifdef CONFIG_PLL0_SOURCE - case 0: - pll_enable_source(CONFIG_PLL0_SOURCE); - pll_config_init(&pllcfg, - CONFIG_PLL0_SOURCE, - CONFIG_PLL0_DIV, - CONFIG_PLL0_MUL); - break; -#endif -#ifdef CONFIG_PLL1_SOURCE - case 1: - pll_enable_source(CONFIG_PLL1_SOURCE); - pll_config_init(&pllcfg, - CONFIG_PLL1_SOURCE, - CONFIG_PLL1_DIV, - CONFIG_PLL1_MUL); - break; -#endif - default: - Assert(false); - break; - } - pll_enable(&pllcfg, ul_pll_id); - while (!pll_is_locked(ul_pll_id)); +static inline void pll_enable_config_defaults(unsigned int ul_pll_id) { + struct pll_config pllcfg; + + if (pll_is_locked(ul_pll_id)) return; // Pll already running + + switch (ul_pll_id) { + #ifdef CONFIG_PLL0_SOURCE + case 0: + pll_enable_source(CONFIG_PLL0_SOURCE); + pll_config_init(&pllcfg, + CONFIG_PLL0_SOURCE, + CONFIG_PLL0_DIV, + CONFIG_PLL0_MUL); + break; + #endif + #ifdef CONFIG_PLL1_SOURCE + case 1: + pll_enable_source(CONFIG_PLL1_SOURCE); + pll_config_init(&pllcfg, + CONFIG_PLL1_SOURCE, + CONFIG_PLL1_DIV, + CONFIG_PLL1_MUL); + break; + #endif + default: + Assert(false); + break; + } + pll_enable(&pllcfg, ul_pll_id); + while (!pll_is_locked(ul_pll_id)); } /** @@ -264,15 +249,12 @@ static inline void pll_enable_config_defaults(unsigned int ul_pll_id) * \retval STATUS_OK The PLL is now locked. * \retval ERR_TIMEOUT Timed out waiting for PLL to become locked. */ -static inline int pll_wait_for_lock(unsigned int pll_id) -{ - Assert(pll_id < NR_PLLS); +static inline int pll_wait_for_lock(unsigned int pll_id) { + Assert(pll_id < NR_PLLS); - while (!pll_is_locked(pll_id)) { - /* Do nothing */ - } + while (!pll_is_locked(pll_id)) { /* Do nothing */ } - return 0; + return 0; } //! @} diff --git a/Marlin/src/HAL/DUE/usb/sbc_protocol.h b/Marlin/src/HAL/DUE/usb/sbc_protocol.h index ab845739fd48..983ec7adca1c 100644 --- a/Marlin/src/HAL/DUE/usb/sbc_protocol.h +++ b/Marlin/src/HAL/DUE/usb/sbc_protocol.h @@ -57,7 +57,6 @@ #ifndef _SBC_PROTOCOL_H_ #define _SBC_PROTOCOL_H_ - /** * \ingroup usb_msc_protocol * \defgroup usb_sbc_protocol SCSI Block Commands protocol definitions @@ -81,82 +80,82 @@ //@{ enum scsi_sbc_mode { - SCSI_MS_MODE_RW_ERR_RECOV = 0x01, //!< Read-Write Error Recovery mode page - SCSI_MS_MODE_FORMAT_DEVICE = 0x03, //!< Format Device mode page - SCSI_MS_MODE_FLEXIBLE_DISK = 0x05, //!< Flexible Disk mode page - SCSI_MS_MODE_CACHING = 0x08, //!< Caching mode page + SCSI_MS_MODE_RW_ERR_RECOV = 0x01, //!< Read-Write Error Recovery mode page + SCSI_MS_MODE_FORMAT_DEVICE = 0x03, //!< Format Device mode page + SCSI_MS_MODE_FLEXIBLE_DISK = 0x05, //!< Flexible Disk mode page + SCSI_MS_MODE_CACHING = 0x08, //!< Caching mode page }; //! \name SBC-2 Device-Specific Parameter //@{ -#define SCSI_MS_SBC_WP 0x80 //!< Write Protected -#define SCSI_MS_SBC_DPOFUA 0x10 //!< DPO and FUA supported +#define SCSI_MS_SBC_WP 0x80 //!< Write Protected +#define SCSI_MS_SBC_DPOFUA 0x10 //!< DPO and FUA supported //@} /** * \brief SBC-2 Short LBA mode parameter block descriptor */ struct sbc_slba_block_desc { - be32_t nr_blocks; //!< Number of Blocks - be32_t block_len; //!< Block Length -#define SBC_SLBA_BLOCK_LEN_MASK 0x00FFFFFFU //!< Mask reserved bits + be32_t nr_blocks; //!< Number of Blocks + be32_t block_len; //!< Block Length +#define SBC_SLBA_BLOCK_LEN_MASK 0x00FFFFFFU //!< Mask reserved bits }; /** * \brief SBC-2 Caching mode page */ struct sbc_caching_mode_page { - uint8_t page_code; - uint8_t page_length; - uint8_t flags2; -#define SBC_MP_CACHE_IC (1 << 7) //!< Initiator Control -#define SBC_MP_CACHE_ABPF (1 << 6) //!< Abort Pre-Fetch -#define SBC_MP_CACHE_CAP (1 << 5) //!< Catching Analysis Permitted -#define SBC_MP_CACHE_DISC (1 << 4) //!< Discontinuity -#define SBC_MP_CACHE_SIZE (1 << 3) //!< Size enable -#define SBC_MP_CACHE_WCE (1 << 2) //!< Write back Cache Enable -#define SBC_MP_CACHE_MF (1 << 1) //!< Multiplication Factor -#define SBC_MP_CACHE_RCD (1 << 0) //!< Read Cache Disable - uint8_t retention; - be16_t dis_pf_transfer_len; - be16_t min_prefetch; - be16_t max_prefetch; - be16_t max_prefetch_ceil; - uint8_t flags12; -#define SBC_MP_CACHE_FSW (1 << 7) //!< Force Sequential Write -#define SBC_MP_CACHE_LBCSS (1 << 6) //!< Logical Blk Cache Seg Sz -#define SBC_MP_CACHE_DRA (1 << 5) //!< Disable Read-Ahead -#define SBC_MP_CACHE_NV_DIS (1 << 0) //!< Non-Volatile Cache Disable - uint8_t nr_cache_segments; - be16_t cache_segment_size; - uint8_t reserved[4]; + uint8_t page_code; + uint8_t page_length; + uint8_t flags2; +#define SBC_MP_CACHE_IC (1 << 7) //!< Initiator Control +#define SBC_MP_CACHE_ABPF (1 << 6) //!< Abort Pre-Fetch +#define SBC_MP_CACHE_CAP (1 << 5) //!< Catching Analysis Permitted +#define SBC_MP_CACHE_DISC (1 << 4) //!< Discontinuity +#define SBC_MP_CACHE_SIZE (1 << 3) //!< Size enable +#define SBC_MP_CACHE_WCE (1 << 2) //!< Write back Cache Enable +#define SBC_MP_CACHE_MF (1 << 1) //!< Multiplication Factor +#define SBC_MP_CACHE_RCD (1 << 0) //!< Read Cache Disable + uint8_t retention; + be16_t dis_pf_transfer_len; + be16_t min_prefetch; + be16_t max_prefetch; + be16_t max_prefetch_ceil; + uint8_t flags12; +#define SBC_MP_CACHE_FSW (1 << 7) //!< Force Sequential Write +#define SBC_MP_CACHE_LBCSS (1 << 6) //!< Logical Blk Cache Seg Sz +#define SBC_MP_CACHE_DRA (1 << 5) //!< Disable Read-Ahead +#define SBC_MP_CACHE_NV_DIS (1 << 0) //!< Non-Volatile Cache Disable + uint8_t nr_cache_segments; + be16_t cache_segment_size; + uint8_t reserved[4]; }; /** * \brief SBC-2 Read-Write Error Recovery mode page */ struct sbc_rdwr_error_recovery_mode_page { - uint8_t page_code; - uint8_t page_length; -#define SPC_MP_RW_ERR_RECOV_PAGE_LENGTH 0x0A - uint8_t flags1; -#define SBC_MP_RW_ERR_RECOV_AWRE (1 << 7) -#define SBC_MP_RW_ERR_RECOV_ARRE (1 << 6) -#define SBC_MP_RW_ERR_RECOV_TB (1 << 5) -#define SBC_MP_RW_ERR_RECOV_RC (1 << 4) -#define SBC_MP_RW_ERR_RECOV_ERR (1 << 3) -#define SBC_MP_RW_ERR_RECOV_PER (1 << 2) -#define SBC_MP_RW_ERR_RECOV_DTE (1 << 1) -#define SBC_MP_RW_ERR_RECOV_DCR (1 << 0) - uint8_t read_retry_count; - uint8_t correction_span; - uint8_t head_offset_count; - uint8_t data_strobe_offset_count; - uint8_t flags2; - uint8_t write_retry_count; - uint8_t flags3; - be16_t recovery_time_limit; + uint8_t page_code; + uint8_t page_length; + #define SPC_MP_RW_ERR_RECOV_PAGE_LENGTH 0x0A + uint8_t flags1; + #define SBC_MP_RW_ERR_RECOV_AWRE (1 << 7) + #define SBC_MP_RW_ERR_RECOV_ARRE (1 << 6) + #define SBC_MP_RW_ERR_RECOV_TB (1 << 5) + #define SBC_MP_RW_ERR_RECOV_RC (1 << 4) + #define SBC_MP_RW_ERR_RECOV_ERR (1 << 3) + #define SBC_MP_RW_ERR_RECOV_PER (1 << 2) + #define SBC_MP_RW_ERR_RECOV_DTE (1 << 1) + #define SBC_MP_RW_ERR_RECOV_DCR (1 << 0) + uint8_t read_retry_count; + uint8_t correction_span; + uint8_t head_offset_count; + uint8_t data_strobe_offset_count; + uint8_t flags2; + uint8_t write_retry_count; + uint8_t flags3; + be16_t recovery_time_limit; }; //@} @@ -164,8 +163,8 @@ struct sbc_rdwr_error_recovery_mode_page { * \brief SBC-2 READ CAPACITY (10) parameter data */ struct sbc_read_capacity10_data { - be32_t max_lba; //!< LBA of last logical block - be32_t block_len; //!< Number of bytes in the last logical block + be32_t max_lba; //!< LBA of last logical block + be32_t block_len; //!< Number of bytes in the last logical block }; //@} diff --git a/Marlin/src/HAL/DUE/usb/spc_protocol.h b/Marlin/src/HAL/DUE/usb/spc_protocol.h index d67cc5c78803..808c388f4fc4 100644 --- a/Marlin/src/HAL/DUE/usb/spc_protocol.h +++ b/Marlin/src/HAL/DUE/usb/spc_protocol.h @@ -59,23 +59,23 @@ //! \name SCSI commands defined by SPC-2 //@{ -#define SPC_TEST_UNIT_READY 0x00 -#define SPC_REQUEST_SENSE 0x03 -#define SPC_INQUIRY 0x12 -#define SPC_MODE_SELECT6 0x15 -#define SPC_MODE_SENSE6 0x1A -#define SPC_SEND_DIAGNOSTIC 0x1D -#define SPC_PREVENT_ALLOW_MEDIUM_REMOVAL 0x1E -#define SPC_MODE_SENSE10 0x5A -#define SPC_REPORT_LUNS 0xA0 +#define SPC_TEST_UNIT_READY 0x00 +#define SPC_REQUEST_SENSE 0x03 +#define SPC_INQUIRY 0x12 +#define SPC_MODE_SELECT6 0x15 +#define SPC_MODE_SENSE6 0x1A +#define SPC_SEND_DIAGNOSTIC 0x1D +#define SPC_PREVENT_ALLOW_MEDIUM_REMOVAL 0x1E +#define SPC_MODE_SENSE10 0x5A +#define SPC_REPORT_LUNS 0xA0 //@} //! \brief May be set in byte 0 of the INQUIRY CDB //@{ //! Enable Vital Product Data -#define SCSI_INQ_REQ_EVPD 0x01 +#define SCSI_INQ_REQ_EVPD 0x01 //! Command Support Data specified by the PAGE OR OPERATION CODE field -#define SCSI_INQ_REQ_CMDT 0x02 +#define SCSI_INQ_REQ_CMDT 0x02 //@} COMPILER_PACK_SET(1) @@ -84,110 +84,110 @@ COMPILER_PACK_SET(1) * \brief SCSI Standard Inquiry data structure */ struct scsi_inquiry_data { - uint8_t pq_pdt; //!< Peripheral Qual / Peripheral Dev Type -#define SCSI_INQ_PQ_CONNECTED 0x00 //!< Peripheral connected -#define SCSI_INQ_PQ_NOT_CONN 0x20 //!< Peripheral not connected -#define SCSI_INQ_PQ_NOT_SUPP 0x60 //!< Peripheral not supported -#define SCSI_INQ_DT_DIR_ACCESS 0x00 //!< Direct Access (SBC) -#define SCSI_INQ_DT_SEQ_ACCESS 0x01 //!< Sequential Access -#define SCSI_INQ_DT_PRINTER 0x02 //!< Printer -#define SCSI_INQ_DT_PROCESSOR 0x03 //!< Processor device -#define SCSI_INQ_DT_WRITE_ONCE 0x04 //!< Write-once device -#define SCSI_INQ_DT_CD_DVD 0x05 //!< CD/DVD device -#define SCSI_INQ_DT_OPTICAL 0x07 //!< Optical Memory -#define SCSI_INQ_DT_MC 0x08 //!< Medium Changer -#define SCSI_INQ_DT_ARRAY 0x0C //!< Storage Array Controller -#define SCSI_INQ_DT_ENCLOSURE 0x0D //!< Enclosure Services -#define SCSI_INQ_DT_RBC 0x0E //!< Simplified Direct Access -#define SCSI_INQ_DT_OCRW 0x0F //!< Optical card reader/writer -#define SCSI_INQ_DT_BCC 0x10 //!< Bridge Controller Commands -#define SCSI_INQ_DT_OSD 0x11 //!< Object-based Storage -#define SCSI_INQ_DT_NONE 0x1F //!< No Peripheral - uint8_t flags1; //!< Flags (byte 1) -#define SCSI_INQ_RMB 0x80 //!< Removable Medium - uint8_t version; //!< Version -#define SCSI_INQ_VER_NONE 0x00 //!< No standards conformance -#define SCSI_INQ_VER_SPC 0x03 //!< SCSI Primary Commands (link to SBC) -#define SCSI_INQ_VER_SPC2 0x04 //!< SCSI Primary Commands - 2 (link to SBC-2) -#define SCSI_INQ_VER_SPC3 0x05 //!< SCSI Primary Commands - 3 (link to SBC-2) -#define SCSI_INQ_VER_SPC4 0x06 //!< SCSI Primary Commands - 4 (link to SBC-3) - uint8_t flags3; //!< Flags (byte 3) -#define SCSI_INQ_NORMACA 0x20 //!< Normal ACA Supported -#define SCSI_INQ_HISUP 0x10 //!< Hierarchal LUN addressing -#define SCSI_INQ_RSP_SPC2 0x02 //!< SPC-2 / SPC-3 response format - uint8_t addl_len; //!< Additional Length (n-4) -#define SCSI_INQ_ADDL_LEN(tot) ((tot)-5) //!< Total length is \a tot - uint8_t flags5; //!< Flags (byte 5) -#define SCSI_INQ_SCCS 0x80 - uint8_t flags6; //!< Flags (byte 6) -#define SCSI_INQ_BQUE 0x80 -#define SCSI_INQ_ENCSERV 0x40 -#define SCSI_INQ_MULTIP 0x10 -#define SCSI_INQ_MCHGR 0x08 -#define SCSI_INQ_ADDR16 0x01 - uint8_t flags7; //!< Flags (byte 7) -#define SCSI_INQ_WBUS16 0x20 -#define SCSI_INQ_SYNC 0x10 -#define SCSI_INQ_LINKED 0x08 -#define SCSI_INQ_CMDQUE 0x02 - uint8_t vendor_id[8]; //!< T10 Vendor Identification - uint8_t product_id[16]; //!< Product Identification - uint8_t product_rev[4]; //!< Product Revision Level + uint8_t pq_pdt; //!< Peripheral Qual / Peripheral Dev Type + #define SCSI_INQ_PQ_CONNECTED 0x00 //!< Peripheral connected + #define SCSI_INQ_PQ_NOT_CONN 0x20 //!< Peripheral not connected + #define SCSI_INQ_PQ_NOT_SUPP 0x60 //!< Peripheral not supported + #define SCSI_INQ_DT_DIR_ACCESS 0x00 //!< Direct Access (SBC) + #define SCSI_INQ_DT_SEQ_ACCESS 0x01 //!< Sequential Access + #define SCSI_INQ_DT_PRINTER 0x02 //!< Printer + #define SCSI_INQ_DT_PROCESSOR 0x03 //!< Processor device + #define SCSI_INQ_DT_WRITE_ONCE 0x04 //!< Write-once device + #define SCSI_INQ_DT_CD_DVD 0x05 //!< CD/DVD device + #define SCSI_INQ_DT_OPTICAL 0x07 //!< Optical Memory + #define SCSI_INQ_DT_MC 0x08 //!< Medium Changer + #define SCSI_INQ_DT_ARRAY 0x0C //!< Storage Array Controller + #define SCSI_INQ_DT_ENCLOSURE 0x0D //!< Enclosure Services + #define SCSI_INQ_DT_RBC 0x0E //!< Simplified Direct Access + #define SCSI_INQ_DT_OCRW 0x0F //!< Optical card reader/writer + #define SCSI_INQ_DT_BCC 0x10 //!< Bridge Controller Commands + #define SCSI_INQ_DT_OSD 0x11 //!< Object-based Storage + #define SCSI_INQ_DT_NONE 0x1F //!< No Peripheral + uint8_t flags1; //!< Flags (byte 1) + #define SCSI_INQ_RMB 0x80 //!< Removable Medium + uint8_t version; //!< Version + #define SCSI_INQ_VER_NONE 0x00 //!< No standards conformance + #define SCSI_INQ_VER_SPC 0x03 //!< SCSI Primary Commands (link to SBC) + #define SCSI_INQ_VER_SPC2 0x04 //!< SCSI Primary Commands - 2 (link to SBC-2) + #define SCSI_INQ_VER_SPC3 0x05 //!< SCSI Primary Commands - 3 (link to SBC-2) + #define SCSI_INQ_VER_SPC4 0x06 //!< SCSI Primary Commands - 4 (link to SBC-3) + uint8_t flags3; //!< Flags (byte 3) + #define SCSI_INQ_NORMACA 0x20 //!< Normal ACA Supported + #define SCSI_INQ_HISUP 0x10 //!< Hierarchal LUN addressing + #define SCSI_INQ_RSP_SPC2 0x02 //!< SPC-2 / SPC-3 response format + uint8_t addl_len; //!< Additional Length (n-4) + #define SCSI_INQ_ADDL_LEN(tot) ((tot)-5) //!< Total length is \a tot + uint8_t flags5; //!< Flags (byte 5) + #define SCSI_INQ_SCCS 0x80 + uint8_t flags6; //!< Flags (byte 6) + #define SCSI_INQ_BQUE 0x80 + #define SCSI_INQ_ENCSERV 0x40 + #define SCSI_INQ_MULTIP 0x10 + #define SCSI_INQ_MCHGR 0x08 + #define SCSI_INQ_ADDR16 0x01 + uint8_t flags7; //!< Flags (byte 7) + #define SCSI_INQ_WBUS16 0x20 + #define SCSI_INQ_SYNC 0x10 + #define SCSI_INQ_LINKED 0x08 + #define SCSI_INQ_CMDQUE 0x02 + uint8_t vendor_id[8]; //!< T10 Vendor Identification + uint8_t product_id[16]; //!< Product Identification + uint8_t product_rev[4]; //!< Product Revision Level }; /** * \brief SCSI Standard Request sense data structure */ struct scsi_request_sense_data { - /* 1st byte: REQUEST SENSE response flags*/ - uint8_t valid_reponse_code; -#define SCSI_SENSE_VALID 0x80 //!< Indicates the INFORMATION field contains valid information -#define SCSI_SENSE_RESPONSE_CODE_MASK 0x7F -#define SCSI_SENSE_CURRENT 0x70 //!< Response code 70h (current errors) -#define SCSI_SENSE_DEFERRED 0x71 - - /* 2nd byte */ - uint8_t obsolete; - - /* 3rd byte */ - uint8_t sense_flag_key; -#define SCSI_SENSE_FILEMARK 0x80 //!< Indicates that the current command has read a filemark or setmark. -#define SCSI_SENSE_EOM 0x40 //!< Indicates that an end-of-medium condition exists. -#define SCSI_SENSE_ILI 0x20 //!< Indicates that the requested logical block length did not match the logical block length of the data on the medium. -#define SCSI_SENSE_RESERVED 0x10 //!< Reserved -#define SCSI_SENSE_KEY(x) (x&0x0F) //!< Sense Key - - /* 4th to 7th bytes - INFORMATION field */ - uint8_t information[4]; - - /* 8th byte - ADDITIONAL SENSE LENGTH field */ - uint8_t AddSenseLen; -#define SCSI_SENSE_ADDL_LEN(total_len) ((total_len) - 8) - - /* 9th to 12th byte - COMMAND-SPECIFIC INFORMATION field */ - uint8_t CmdSpecINFO[4]; - - /* 13th byte - ADDITIONAL SENSE CODE field */ - uint8_t AddSenseCode; - - /* 14th byte - ADDITIONAL SENSE CODE QUALIFIER field */ - uint8_t AddSnsCodeQlfr; - - /* 15th byte - FIELD REPLACEABLE UNIT CODE field */ - uint8_t FldReplUnitCode; - - /* 16th byte */ - uint8_t SenseKeySpec[3]; -#define SCSI_SENSE_SKSV 0x80 //!< Indicates the SENSE-KEY SPECIFIC field contains valid information + /* 1st byte: REQUEST SENSE response flags*/ + uint8_t valid_reponse_code; + #define SCSI_SENSE_VALID 0x80 //!< Indicates the INFORMATION field contains valid information + #define SCSI_SENSE_RESPONSE_CODE_MASK 0x7F + #define SCSI_SENSE_CURRENT 0x70 //!< Response code 70h (current errors) + #define SCSI_SENSE_DEFERRED 0x71 + + /* 2nd byte */ + uint8_t obsolete; + + /* 3rd byte */ + uint8_t sense_flag_key; + #define SCSI_SENSE_FILEMARK 0x80 //!< Indicates that the current command has read a filemark or setmark. + #define SCSI_SENSE_EOM 0x40 //!< Indicates that an end-of-medium condition exists. + #define SCSI_SENSE_ILI 0x20 //!< Indicates that the requested logical block length did not match the logical block length of the data on the medium. + #define SCSI_SENSE_RESERVED 0x10 //!< Reserved + #define SCSI_SENSE_KEY(x) (x&0x0F) //!< Sense Key + + /* 4th to 7th bytes - INFORMATION field */ + uint8_t information[4]; + + /* 8th byte - ADDITIONAL SENSE LENGTH field */ + uint8_t AddSenseLen; + #define SCSI_SENSE_ADDL_LEN(total_len) ((total_len) - 8) + + /* 9th to 12th byte - COMMAND-SPECIFIC INFORMATION field */ + uint8_t CmdSpecINFO[4]; + + /* 13th byte - ADDITIONAL SENSE CODE field */ + uint8_t AddSenseCode; + + /* 14th byte - ADDITIONAL SENSE CODE QUALIFIER field */ + uint8_t AddSnsCodeQlfr; + + /* 15th byte - FIELD REPLACEABLE UNIT CODE field */ + uint8_t FldReplUnitCode; + + /* 16th byte */ + uint8_t SenseKeySpec[3]; + #define SCSI_SENSE_SKSV 0x80 //!< Indicates the SENSE-KEY SPECIFIC field contains valid information }; COMPILER_PACK_RESET() /* Vital Product Data page codes */ enum scsi_vpd_page_code { - SCSI_VPD_SUPPORTED_PAGES = 0x00, - SCSI_VPD_UNIT_SERIAL_NUMBER = 0x80, - SCSI_VPD_DEVICE_IDENTIFICATION = 0x83, + SCSI_VPD_SUPPORTED_PAGES = 0x00, + SCSI_VPD_UNIT_SERIAL_NUMBER = 0x80, + SCSI_VPD_DEVICE_IDENTIFICATION = 0x83, }; #define SCSI_VPD_HEADER_SIZE 4 @@ -200,37 +200,36 @@ enum scsi_vpd_page_code { #define SCSI_VPD_ID_TYPE_T10 1 - /* Sense keys */ enum scsi_sense_key { - SCSI_SK_NO_SENSE = 0x0, - SCSI_SK_RECOVERED_ERROR = 0x1, - SCSI_SK_NOT_READY = 0x2, - SCSI_SK_MEDIUM_ERROR = 0x3, - SCSI_SK_HARDWARE_ERROR = 0x4, - SCSI_SK_ILLEGAL_REQUEST = 0x5, - SCSI_SK_UNIT_ATTENTION = 0x6, - SCSI_SK_DATA_PROTECT = 0x7, - SCSI_SK_BLANK_CHECK = 0x8, - SCSI_SK_VENDOR_SPECIFIC = 0x9, - SCSI_SK_COPY_ABORTED = 0xA, - SCSI_SK_ABORTED_COMMAND = 0xB, - SCSI_SK_VOLUME_OVERFLOW = 0xD, - SCSI_SK_MISCOMPARE = 0xE, + SCSI_SK_NO_SENSE = 0x0, + SCSI_SK_RECOVERED_ERROR = 0x1, + SCSI_SK_NOT_READY = 0x2, + SCSI_SK_MEDIUM_ERROR = 0x3, + SCSI_SK_HARDWARE_ERROR = 0x4, + SCSI_SK_ILLEGAL_REQUEST = 0x5, + SCSI_SK_UNIT_ATTENTION = 0x6, + SCSI_SK_DATA_PROTECT = 0x7, + SCSI_SK_BLANK_CHECK = 0x8, + SCSI_SK_VENDOR_SPECIFIC = 0x9, + SCSI_SK_COPY_ABORTED = 0xA, + SCSI_SK_ABORTED_COMMAND = 0xB, + SCSI_SK_VOLUME_OVERFLOW = 0xD, + SCSI_SK_MISCOMPARE = 0xE, }; /* Additional Sense Code / Additional Sense Code Qualifier pairs */ enum scsi_asc_ascq { - SCSI_ASC_NO_ADDITIONAL_SENSE_INFO = 0x0000, - SCSI_ASC_LU_NOT_READY_REBUILD_IN_PROGRESS = 0x0405, - SCSI_ASC_WRITE_ERROR = 0x0C00, - SCSI_ASC_UNRECOVERED_READ_ERROR = 0x1100, - SCSI_ASC_INVALID_COMMAND_OPERATION_CODE = 0x2000, - SCSI_ASC_INVALID_FIELD_IN_CDB = 0x2400, - SCSI_ASC_WRITE_PROTECTED = 0x2700, - SCSI_ASC_NOT_READY_TO_READY_CHANGE = 0x2800, - SCSI_ASC_MEDIUM_NOT_PRESENT = 0x3A00, - SCSI_ASC_INTERNAL_TARGET_FAILURE = 0x4400, + SCSI_ASC_NO_ADDITIONAL_SENSE_INFO = 0x0000, + SCSI_ASC_LU_NOT_READY_REBUILD_IN_PROGRESS = 0x0405, + SCSI_ASC_WRITE_ERROR = 0x0C00, + SCSI_ASC_UNRECOVERED_READ_ERROR = 0x1100, + SCSI_ASC_INVALID_COMMAND_OPERATION_CODE = 0x2000, + SCSI_ASC_INVALID_FIELD_IN_CDB = 0x2400, + SCSI_ASC_WRITE_PROTECTED = 0x2700, + SCSI_ASC_NOT_READY_TO_READY_CHANGE = 0x2800, + SCSI_ASC_MEDIUM_NOT_PRESENT = 0x3A00, + SCSI_ASC_INTERNAL_TARGET_FAILURE = 0x4400, }; /** @@ -240,9 +239,9 @@ enum scsi_asc_ascq { * that are applicable to all SCSI devices. */ enum scsi_spc_mode { - SCSI_MS_MODE_VENDOR_SPEC = 0x00, - SCSI_MS_MODE_INFEXP = 0x1C, // Informational exceptions control page - SCSI_MS_MODE_ALL = 0x3F, + SCSI_MS_MODE_VENDOR_SPEC = 0x00, + SCSI_MS_MODE_INFEXP = 0x1C, // Informational exceptions control page + SCSI_MS_MODE_ALL = 0x3F, }; /** @@ -250,51 +249,45 @@ enum scsi_spc_mode { * See chapter 8.3.8 */ struct spc_control_page_info_execpt { - uint8_t page_code; - uint8_t page_length; -#define SPC_MP_INFEXP_PAGE_LENGTH 0x0A - uint8_t flags1; -#define SPC_MP_INFEXP_PERF (1<<7) //!< Initiator Control -#define SPC_MP_INFEXP_EBF (1<<5) //!< Caching Analysis Permitted -#define SPC_MP_INFEXP_EWASC (1<<4) //!< Discontinuity -#define SPC_MP_INFEXP_DEXCPT (1<<3) //!< Size enable -#define SPC_MP_INFEXP_TEST (1<<2) //!< Writeback Cache Enable -#define SPC_MP_INFEXP_LOGERR (1<<0) //!< Log errors bit - uint8_t mrie; -#define SPC_MP_INFEXP_MRIE_NO_REPORT 0x00 -#define SPC_MP_INFEXP_MRIE_ASYNC_EVENT 0x01 -#define SPC_MP_INFEXP_MRIE_GEN_UNIT 0x02 -#define SPC_MP_INFEXP_MRIE_COND_RECOV_ERROR 0x03 -#define SPC_MP_INFEXP_MRIE_UNCOND_RECOV_ERROR 0x04 -#define SPC_MP_INFEXP_MRIE_NO_SENSE 0x05 -#define SPC_MP_INFEXP_MRIE_ONLY_REPORT 0x06 - be32_t interval_timer; - be32_t report_count; + uint8_t page_code; + uint8_t page_length; + #define SPC_MP_INFEXP_PAGE_LENGTH 0x0A + uint8_t flags1; + #define SPC_MP_INFEXP_PERF (1<<7) //!< Initiator Control + #define SPC_MP_INFEXP_EBF (1<<5) //!< Caching Analysis Permitted + #define SPC_MP_INFEXP_EWASC (1<<4) //!< Discontinuity + #define SPC_MP_INFEXP_DEXCPT (1<<3) //!< Size enable + #define SPC_MP_INFEXP_TEST (1<<2) //!< Writeback Cache Enable + #define SPC_MP_INFEXP_LOGERR (1<<0) //!< Log errors bit + uint8_t mrie; + #define SPC_MP_INFEXP_MRIE_NO_REPORT 0x00 + #define SPC_MP_INFEXP_MRIE_ASYNC_EVENT 0x01 + #define SPC_MP_INFEXP_MRIE_GEN_UNIT 0x02 + #define SPC_MP_INFEXP_MRIE_COND_RECOV_ERROR 0x03 + #define SPC_MP_INFEXP_MRIE_UNCOND_RECOV_ERROR 0x04 + #define SPC_MP_INFEXP_MRIE_NO_SENSE 0x05 + #define SPC_MP_INFEXP_MRIE_ONLY_REPORT 0x06 + be32_t interval_timer; + be32_t report_count; }; - enum scsi_spc_mode_sense_pc { - SCSI_MS_SENSE_PC_CURRENT = 0, - SCSI_MS_SENSE_PC_CHANGEABLE = 1, - SCSI_MS_SENSE_PC_DEFAULT = 2, - SCSI_MS_SENSE_PC_SAVED = 3, + SCSI_MS_SENSE_PC_CURRENT = 0, + SCSI_MS_SENSE_PC_CHANGEABLE = 1, + SCSI_MS_SENSE_PC_DEFAULT = 2, + SCSI_MS_SENSE_PC_SAVED = 3, }; - - -static inline bool scsi_mode_sense_dbd_is_set(const uint8_t * cdb) -{ - return (cdb[1] >> 3) & 1; +static inline bool scsi_mode_sense_dbd_is_set(const uint8_t * cdb) { + return (cdb[1] >> 3) & 1; } -static inline uint8_t scsi_mode_sense_get_page_code(const uint8_t * cdb) -{ - return cdb[2] & 0x3F; +static inline uint8_t scsi_mode_sense_get_page_code(const uint8_t * cdb) { + return cdb[2] & 0x3F; } -static inline uint8_t scsi_mode_sense_get_pc(const uint8_t * cdb) -{ - return cdb[2] >> 6; +static inline uint8_t scsi_mode_sense_get_pc(const uint8_t * cdb) { + return cdb[2] >> 6; } /** @@ -302,10 +295,10 @@ static inline uint8_t scsi_mode_sense_get_pc(const uint8_t * cdb) * SENSE(6) */ struct scsi_mode_param_header6 { - uint8_t mode_data_length; //!< Number of bytes after this - uint8_t medium_type; //!< Medium Type - uint8_t device_specific_parameter; //!< Defined by command set - uint8_t block_descriptor_length; //!< Length of block descriptors + uint8_t mode_data_length; //!< Number of bytes after this + uint8_t medium_type; //!< Medium Type + uint8_t device_specific_parameter; //!< Defined by command set + uint8_t block_descriptor_length; //!< Length of block descriptors }; /** @@ -313,23 +306,23 @@ struct scsi_mode_param_header6 { * SENSE(10) */ struct scsi_mode_param_header10 { - be16_t mode_data_length; //!< Number of bytes after this - uint8_t medium_type; //!< Medium Type - uint8_t device_specific_parameter; //!< Defined by command set - uint8_t flags4; //!< LONGLBA in bit 0 - uint8_t reserved; - be16_t block_descriptor_length; //!< Length of block descriptors + be16_t mode_data_length; //!< Number of bytes after this + uint8_t medium_type; //!< Medium Type + uint8_t device_specific_parameter; //!< Defined by command set + uint8_t flags4; //!< LONGLBA in bit 0 + uint8_t reserved; + be16_t block_descriptor_length; //!< Length of block descriptors }; /** * \brief SCSI Page_0 Mode Page header (SPF not set) */ struct scsi_mode_page_0_header { - uint8_t page_code; -#define SCSI_PAGE_CODE_PS (1 << 7) //!< Parameters Saveable -#define SCSI_PAGE_CODE_SPF (1 << 6) //!< SubPage Format - uint8_t page_length; //!< Number of bytes after this -#define SCSI_MS_PAGE_LEN(total) ((total) - 2) + uint8_t page_code; +#define SCSI_PAGE_CODE_PS (1 << 7) //!< Parameters Saveable +#define SCSI_PAGE_CODE_SPF (1 << 6) //!< SubPage Format + uint8_t page_length; //!< Number of bytes after this +#define SCSI_MS_PAGE_LEN(total) ((total) - 2) }; //@} diff --git a/Marlin/src/HAL/DUE/usb/sysclk.h b/Marlin/src/HAL/DUE/usb/sysclk.h index 16db8c86d373..062337861502 100644 --- a/Marlin/src/HAL/DUE/usb/sysclk.h +++ b/Marlin/src/HAL/DUE/usb/sysclk.h @@ -71,7 +71,7 @@ * \subsection sysclk_quickstart_use_case_1_setup_steps Initialization code * Add to the application initialization code: * \code - sysclk_init(); + sysclk_init(); \endcode * * \subsection sysclk_quickstart_use_case_1_setup_steps_workflow Workflow @@ -82,15 +82,15 @@ * Add or uncomment the following in your conf_clock.h header file, commenting out all other * definitions of the same symbol(s): * \code - #define CONFIG_SYSCLK_SOURCE SYSCLK_SRC_PLLACK + #define CONFIG_SYSCLK_SOURCE SYSCLK_SRC_PLLACK - // Fpll0 = (Fclk * PLL_mul) / PLL_div - #define CONFIG_PLL0_SOURCE PLL_SRC_MAINCK_XTAL - #define CONFIG_PLL0_MUL (84000000UL / BOARD_FREQ_MAINCK_XTAL) - #define CONFIG_PLL0_DIV 1 + // Fpll0 = (Fclk * PLL_mul) / PLL_div + #define CONFIG_PLL0_SOURCE PLL_SRC_MAINCK_XTAL + #define CONFIG_PLL0_MUL (84000000UL / BOARD_FREQ_MAINCK_XTAL) + #define CONFIG_PLL0_DIV 1 - // Fbus = Fsys / BUS_div - #define CONFIG_SYSCLK_PRES SYSCLK_PRES_1 + // Fbus = Fsys / BUS_div + #define CONFIG_SYSCLK_PRES SYSCLK_PRES_1 \endcode * * \subsection sysclk_quickstart_use_case_1_example_workflow Workflow @@ -100,14 +100,14 @@ * \code #define CONFIG_PLL0_SOURCE PLL_SRC_MAINCK_XTAL \endcode * -# Configure the PLL module to multiply the external fast crystal oscillator frequency up to 84MHz: * \code - #define CONFIG_PLL0_MUL (84000000UL / BOARD_FREQ_MAINCK_XTAL) - #define CONFIG_PLL0_DIV 1 + #define CONFIG_PLL0_MUL (84000000UL / BOARD_FREQ_MAINCK_XTAL) + #define CONFIG_PLL0_DIV 1 \endcode * \note For user boards, \c BOARD_FREQ_MAINCK_XTAL should be defined in the board \c conf_board.h configuration * file as the frequency of the fast crystal attached to the microcontroller. * -# Configure the main clock to run at the full 84MHz, disable scaling of the main system clock speed: * \code - #define CONFIG_SYSCLK_PRES SYSCLK_PRES_1 + #define CONFIG_SYSCLK_PRES SYSCLK_PRES_1 \endcode * \note Some dividers are powers of two, while others are integer division factors. Refer to the * formulas in the conf_clock.h template commented above each division define. @@ -136,7 +136,7 @@ extern "C" { * initialization. */ #ifndef CONFIG_SYSCLK_SOURCE -# define CONFIG_SYSCLK_SOURCE SYSCLK_SRC_MAINCK_4M_RC + #define CONFIG_SYSCLK_SOURCE SYSCLK_SRC_MAINCK_4M_RC #endif /** * \def CONFIG_SYSCLK_PRES @@ -149,7 +149,7 @@ extern "C" { * after initialization. */ #ifndef CONFIG_SYSCLK_PRES -# define CONFIG_SYSCLK_PRES 0 + #define CONFIG_SYSCLK_PRES 0 #endif //@} @@ -197,7 +197,7 @@ extern "C" { * USB is not required. */ #ifdef __DOXYGEN__ -# define CONFIG_USBCLK_SOURCE + #define CONFIG_USBCLK_SOURCE #endif /** @@ -209,7 +209,7 @@ extern "C" { * defined. */ #ifdef __DOXYGEN__ -# define CONFIG_USBCLK_DIV + #define CONFIG_USBCLK_DIV #endif diff --git a/Marlin/src/HAL/DUE/usb/udc.h b/Marlin/src/HAL/DUE/usb/udc.h index 8d92eb5c038a..6230a81b359c 100644 --- a/Marlin/src/HAL/DUE/usb/udc.h +++ b/Marlin/src/HAL/DUE/usb/udc.h @@ -144,15 +144,15 @@ extern "C" { * \code #define USB_DEVICE_ATTACH_AUTO_DISABLE \endcode * User C file contains: * \code - // Authorize VBUS monitoring - if (!udc_include_vbus_monitoring()) { - // Implement custom VBUS monitoring via GPIO or other - } - Event_VBUS_present() // VBUS interrupt or GPIO interrupt or other - { - // Attach USB Device - udc_attach(); - } + // Authorize VBUS monitoring + if (!udc_include_vbus_monitoring()) { + // Implement custom VBUS monitoring via GPIO or other + } + Event_VBUS_present() // VBUS interrupt or GPIO interrupt or other + { + // Attach USB Device + udc_attach(); + } \endcode * * - Case of battery charging. conf_usb.h file contains define @@ -160,21 +160,20 @@ extern "C" { * \code #define USB_DEVICE_ATTACH_AUTO_DISABLE \endcode * User C file contains: * \code - Event VBUS present() // VBUS interrupt or GPIO interrupt or .. - { - // Authorize battery charging, but wait key press to start USB. - } - Event Key press() - { - // Stop batteries charging - // Start USB - udc_attach(); - } + Event VBUS present() // VBUS interrupt or GPIO interrupt or .. + { + // Authorize battery charging, but wait key press to start USB. + } + Event Key press() + { + // Stop batteries charging + // Start USB + udc_attach(); + } \endcode */ -static inline bool udc_include_vbus_monitoring(void) -{ - return udd_include_vbus_monitoring(); +static inline bool udc_include_vbus_monitoring(void) { + return udd_include_vbus_monitoring(); } /*! \brief Start the USB Device stack @@ -192,32 +191,26 @@ void udc_stop(void); * then it will attach device when an acceptable Vbus * level from the host is detected. */ -static inline void udc_attach(void) -{ - udd_attach(); +static inline void udc_attach(void) { + udd_attach(); } - /** * \brief Detaches the device from the bus * * The driver must remove pull-up on USB line D- or D+. */ -static inline void udc_detach(void) -{ - udd_detach(); +static inline void udc_detach(void) { + udd_detach(); } - /*! \brief The USB driver sends a resume signal called \e "Upstream Resume" * This is authorized only when the remote wakeup feature is enabled by host. */ -static inline void udc_remotewakeup(void) -{ - udd_send_remotewakeup(); +static inline void udc_remotewakeup(void) { + udd_send_remotewakeup(); } - /** * \brief Returns a pointer on the current interface descriptor * @@ -296,23 +289,23 @@ usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc(void); * * for AVR and SAM3/4 devices, add to the initialization code: * \code - sysclk_init(); - irq_initialize_vectors(); - cpu_irq_enable(); - board_init(); - sleepmgr_init(); // Optional + sysclk_init(); + irq_initialize_vectors(); + cpu_irq_enable(); + board_init(); + sleepmgr_init(); // Optional \endcode * * For SAMD devices, add to the initialization code: * \code - system_init(); - irq_initialize_vectors(); - cpu_irq_enable(); - sleepmgr_init(); // Optional + system_init(); + irq_initialize_vectors(); + cpu_irq_enable(); + sleepmgr_init(); // Optional \endcode * Add to the main IDLE loop: * \code - sleepmgr_enter_sleep(); // Optional + sleepmgr_enter_sleep(); // Optional \endcode * */ @@ -324,20 +317,20 @@ usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc(void); * * Content of conf_usb.h: * \code - #define USB_DEVICE_VENDOR_ID 0x03EB - #define USB_DEVICE_PRODUCT_ID 0xXXXX - #define USB_DEVICE_MAJOR_VERSION 1 - #define USB_DEVICE_MINOR_VERSION 0 - #define USB_DEVICE_POWER 100 - #define USB_DEVICE_ATTR USB_CONFIG_ATTR_BUS_POWERED + #define USB_DEVICE_VENDOR_ID 0x03EB + #define USB_DEVICE_PRODUCT_ID 0xXXXX + #define USB_DEVICE_MAJOR_VERSION 1 + #define USB_DEVICE_MINOR_VERSION 0 + #define USB_DEVICE_POWER 100 + #define USB_DEVICE_ATTR USB_CONFIG_ATTR_BUS_POWERED \endcode * * Add to application C-file: * \code - void usb_init(void) - { - udc_start(); - } + void usb_init(void) + { + udc_start(); + } \endcode */ @@ -349,17 +342,17 @@ usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc(void); * -# Ensure that conf_usb.h is available and contains the following configuration * which is the main USB device configuration: * - \code // Vendor ID provided by USB org (ATMEL 0x03EB) - #define USB_DEVICE_VENDOR_ID 0x03EB // Type Word - // Product ID (Atmel PID referenced in usb_atmel.h) - #define USB_DEVICE_PRODUCT_ID 0xXXXX // Type Word - // Major version of the device - #define USB_DEVICE_MAJOR_VERSION 1 // Type Byte - // Minor version of the device - #define USB_DEVICE_MINOR_VERSION 0 // Type Byte - // Maximum device power (mA) - #define USB_DEVICE_POWER 100 // Type 9-bits - // USB attributes to enable features - #define USB_DEVICE_ATTR USB_CONFIG_ATTR_BUS_POWERED // Flags \endcode + #define USB_DEVICE_VENDOR_ID 0x03EB // Type Word + // Product ID (Atmel PID referenced in usb_atmel.h) + #define USB_DEVICE_PRODUCT_ID 0xXXXX // Type Word + // Major version of the device + #define USB_DEVICE_MAJOR_VERSION 1 // Type Byte + // Minor version of the device + #define USB_DEVICE_MINOR_VERSION 0 // Type Byte + // Maximum device power (mA) + #define USB_DEVICE_POWER 100 // Type 9-bits + // USB attributes to enable features + #define USB_DEVICE_ATTR USB_CONFIG_ATTR_BUS_POWERED // Flags \endcode * -# Call the USB device stack start function to enable stack and start USB: * - \code udc_start(); \endcode * \note In case of USB dual roles (Device and Host) managed through USB OTG connector @@ -372,90 +365,90 @@ usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc(void); * * Content of XMEGA conf_clock.h: * \code - // Configuration based on internal RC: - // USB clock need of 48Mhz - #define CONFIG_USBCLK_SOURCE USBCLK_SRC_RCOSC - #define CONFIG_OSC_RC32_CAL 48000000UL - #define CONFIG_OSC_AUTOCAL_RC32MHZ_REF_OSC OSC_ID_USBSOF - // CPU clock need of clock > 12MHz to run with USB (Here 24MHz) - #define CONFIG_SYSCLK_SOURCE SYSCLK_SRC_RC32MHZ - #define CONFIG_SYSCLK_PSADIV SYSCLK_PSADIV_2 - #define CONFIG_SYSCLK_PSBCDIV SYSCLK_PSBCDIV_1_1 + // Configuration based on internal RC: + // USB clock need of 48Mhz + #define CONFIG_USBCLK_SOURCE USBCLK_SRC_RCOSC + #define CONFIG_OSC_RC32_CAL 48000000UL + #define CONFIG_OSC_AUTOCAL_RC32MHZ_REF_OSC OSC_ID_USBSOF + // CPU clock need of clock > 12MHz to run with USB (Here 24MHz) + #define CONFIG_SYSCLK_SOURCE SYSCLK_SRC_RC32MHZ + #define CONFIG_SYSCLK_PSADIV SYSCLK_PSADIV_2 + #define CONFIG_SYSCLK_PSBCDIV SYSCLK_PSBCDIV_1_1 \endcode * * Content of conf_clock.h for AT32UC3A0, AT32UC3A1, AT32UC3B devices (USBB): * \code - // Configuration based on 12MHz external OSC: - #define CONFIG_PLL1_SOURCE PLL_SRC_OSC0 - #define CONFIG_PLL1_MUL 8 - #define CONFIG_PLL1_DIV 2 - #define CONFIG_USBCLK_SOURCE USBCLK_SRC_PLL1 - #define CONFIG_USBCLK_DIV 1 // Fusb = Fsys/(2 ^ USB_div) + // Configuration based on 12MHz external OSC: + #define CONFIG_PLL1_SOURCE PLL_SRC_OSC0 + #define CONFIG_PLL1_MUL 8 + #define CONFIG_PLL1_DIV 2 + #define CONFIG_USBCLK_SOURCE USBCLK_SRC_PLL1 + #define CONFIG_USBCLK_DIV 1 // Fusb = Fsys/(2 ^ USB_div) \endcode * * Content of conf_clock.h for AT32UC3A3, AT32UC3A4 devices (USBB with high speed support): * \code - // Configuration based on 12MHz external OSC: - #define CONFIG_USBCLK_SOURCE USBCLK_SRC_OSC0 - #define CONFIG_USBCLK_DIV 1 // Fusb = Fsys/(2 ^ USB_div) + // Configuration based on 12MHz external OSC: + #define CONFIG_USBCLK_SOURCE USBCLK_SRC_OSC0 + #define CONFIG_USBCLK_DIV 1 // Fusb = Fsys/(2 ^ USB_div) \endcode * * Content of conf_clock.h for AT32UC3C, ATUCXXD, ATUCXXL3U, ATUCXXL4U devices (USBC): * \code - // Configuration based on 12MHz external OSC: - #define CONFIG_PLL1_SOURCE PLL_SRC_OSC0 - #define CONFIG_PLL1_MUL 8 - #define CONFIG_PLL1_DIV 2 - #define CONFIG_USBCLK_SOURCE USBCLK_SRC_PLL1 - #define CONFIG_USBCLK_DIV 1 // Fusb = Fsys/(2 ^ USB_div) - // CPU clock need of clock > 25MHz to run with USBC - #define CONFIG_SYSCLK_SOURCE SYSCLK_SRC_PLL1 + // Configuration based on 12MHz external OSC: + #define CONFIG_PLL1_SOURCE PLL_SRC_OSC0 + #define CONFIG_PLL1_MUL 8 + #define CONFIG_PLL1_DIV 2 + #define CONFIG_USBCLK_SOURCE USBCLK_SRC_PLL1 + #define CONFIG_USBCLK_DIV 1 // Fusb = Fsys/(2 ^ USB_div) + // CPU clock need of clock > 25MHz to run with USBC + #define CONFIG_SYSCLK_SOURCE SYSCLK_SRC_PLL1 \endcode * * Content of conf_clock.h for SAM3S, SAM3SD, SAM4S devices (UPD: USB Peripheral Device): * \code - // PLL1 (B) Options (Fpll = (Fclk * PLL_mul) / PLL_div) - #define CONFIG_PLL1_SOURCE PLL_SRC_MAINCK_XTAL - #define CONFIG_PLL1_MUL 16 - #define CONFIG_PLL1_DIV 2 - // USB Clock Source Options (Fusb = FpllX / USB_div) - #define CONFIG_USBCLK_SOURCE USBCLK_SRC_PLL1 - #define CONFIG_USBCLK_DIV 2 + // PLL1 (B) Options (Fpll = (Fclk * PLL_mul) / PLL_div) + #define CONFIG_PLL1_SOURCE PLL_SRC_MAINCK_XTAL + #define CONFIG_PLL1_MUL 16 + #define CONFIG_PLL1_DIV 2 + // USB Clock Source Options (Fusb = FpllX / USB_div) + #define CONFIG_USBCLK_SOURCE USBCLK_SRC_PLL1 + #define CONFIG_USBCLK_DIV 2 \endcode * * Content of conf_clock.h for SAM3U device (UPDHS: USB Peripheral Device High Speed): * \code - // USB Clock Source fixed at UPLL. + // USB Clock Source fixed at UPLL. \endcode * * Content of conf_clock.h for SAM3X, SAM3A devices (UOTGHS: USB OTG High Speed): * \code - // USB Clock Source fixed at UPLL. - #define CONFIG_USBCLK_SOURCE USBCLK_SRC_UPLL - #define CONFIG_USBCLK_DIV 1 + // USB Clock Source fixed at UPLL. + #define CONFIG_USBCLK_SOURCE USBCLK_SRC_UPLL + #define CONFIG_USBCLK_DIV 1 \endcode * * Content of conf_clocks.h for SAMD devices (USB): * \code - // System clock bus configuration - # define CONF_CLOCK_FLASH_WAIT_STATES 2 - - // USB Clock Source fixed at DFLL. - // SYSTEM_CLOCK_SOURCE_DFLL configuration - Digital Frequency Locked Loop - # define CONF_CLOCK_DFLL_ENABLE true - # define CONF_CLOCK_DFLL_LOOP_MODE SYSTEM_CLOCK_DFLL_LOOP_MODE_USB_RECOVERY - # define CONF_CLOCK_DFLL_ON_DEMAND true - - // Set this to true to configure the GCLK when running clocks_init. - // If set to false, none of the GCLK generators will be configured in clocks_init(). - # define CONF_CLOCK_CONFIGURE_GCLK true - - // Configure GCLK generator 0 (Main Clock) - # define CONF_CLOCK_GCLK_0_ENABLE true - # define CONF_CLOCK_GCLK_0_RUN_IN_STANDBY true - # define CONF_CLOCK_GCLK_0_CLOCK_SOURCE SYSTEM_CLOCK_SOURCE_DFLL - # define CONF_CLOCK_GCLK_0_PRESCALER 1 - # define CONF_CLOCK_GCLK_0_OUTPUT_ENABLE false + // System clock bus configuration + # define CONF_CLOCK_FLASH_WAIT_STATES 2 + + // USB Clock Source fixed at DFLL. + // SYSTEM_CLOCK_SOURCE_DFLL configuration - Digital Frequency Locked Loop + # define CONF_CLOCK_DFLL_ENABLE true + # define CONF_CLOCK_DFLL_LOOP_MODE SYSTEM_CLOCK_DFLL_LOOP_MODE_USB_RECOVERY + # define CONF_CLOCK_DFLL_ON_DEMAND true + + // Set this to true to configure the GCLK when running clocks_init. + // If set to false, none of the GCLK generators will be configured in clocks_init(). + # define CONF_CLOCK_CONFIGURE_GCLK true + + // Configure GCLK generator 0 (Main Clock) + # define CONF_CLOCK_GCLK_0_ENABLE true + # define CONF_CLOCK_GCLK_0_RUN_IN_STANDBY true + # define CONF_CLOCK_GCLK_0_CLOCK_SOURCE SYSTEM_CLOCK_SOURCE_DFLL + # define CONF_CLOCK_GCLK_0_PRESCALER 1 + # define CONF_CLOCK_GCLK_0_OUTPUT_ENABLE false \endcode */ @@ -474,34 +467,34 @@ usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc(void); * \subsection udc_use_case_1_usage_code Example code * Content of conf_usb.h: * \code - #if // Low speed - #define USB_DEVICE_LOW_SPEED - // #define USB_DEVICE_HS_SUPPORT + #if // Low speed + #define USB_DEVICE_LOW_SPEED + // #define USB_DEVICE_HS_SUPPORT - #elif // Full speed - // #define USB_DEVICE_LOW_SPEED - // #define USB_DEVICE_HS_SUPPORT + #elif // Full speed + // #define USB_DEVICE_LOW_SPEED + // #define USB_DEVICE_HS_SUPPORT - #elif // High speed - // #define USB_DEVICE_LOW_SPEED - #define USB_DEVICE_HS_SUPPORT + #elif // High speed + // #define USB_DEVICE_LOW_SPEED + #define USB_DEVICE_HS_SUPPORT - #endif + #endif \endcode * * \subsection udc_use_case_1_usage_flow Workflow * -# Ensure that conf_usb.h is available and contains the following parameters * required for a USB device low speed (1.5Mbit/s): * - \code #define USB_DEVICE_LOW_SPEED - //#define USB_DEVICE_HS_SUPPORT \endcode + //#define USB_DEVICE_HS_SUPPORT \endcode * -# Ensure that conf_usb.h contains the following parameters * required for a USB device full speed (12Mbit/s): * - \code //#define USB_DEVICE_LOW_SPEED - //#define USB_DEVICE_HS_SUPPORT \endcode + //#define USB_DEVICE_HS_SUPPORT \endcode * -# Ensure that conf_usb.h contains the following parameters * required for a USB device high speed (480Mbit/s): * - \code //#define USB_DEVICE_LOW_SPEED - #define USB_DEVICE_HS_SUPPORT \endcode + #define USB_DEVICE_HS_SUPPORT \endcode */ /** @@ -518,20 +511,20 @@ usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc(void); * \subsection udc_use_case_2_usage_code Example code * Content of conf_usb.h: * \code - #define USB_DEVICE_MANUFACTURE_NAME "Manufacture name" - #define USB_DEVICE_PRODUCT_NAME "Product name" - #define USB_DEVICE_SERIAL_NAME "12...EF" + #define USB_DEVICE_MANUFACTURE_NAME "Manufacture name" + #define USB_DEVICE_PRODUCT_NAME "Product name" + #define USB_DEVICE_SERIAL_NAME "12...EF" \endcode * * \subsection udc_use_case_2_usage_flow Workflow * -# Ensure that conf_usb.h is available and contains the following parameters * required to enable different USB strings: * - \code // Static ASCII name for the manufacture - #define USB_DEVICE_MANUFACTURE_NAME "Manufacture name" \endcode + #define USB_DEVICE_MANUFACTURE_NAME "Manufacture name" \endcode * - \code // Static ASCII name for the product - #define USB_DEVICE_PRODUCT_NAME "Product name" \endcode + #define USB_DEVICE_PRODUCT_NAME "Product name" \endcode * - \code // Static ASCII name to enable and set a serial number - #define USB_DEVICE_SERIAL_NAME "12...EF" \endcode + #define USB_DEVICE_SERIAL_NAME "12...EF" \endcode */ /** @@ -548,42 +541,42 @@ usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc(void); * \subsection udc_use_case_3_usage_code Example code * Content of conf_usb.h: * \code - #define USB_DEVICE_ATTR \ - (USB_CONFIG_ATTR_REMOTE_WAKEUP | USB_CONFIG_ATTR_..._POWERED) - #define UDC_REMOTEWAKEUP_ENABLE() my_callback_remotewakeup_enable() - extern void my_callback_remotewakeup_enable(void); - #define UDC_REMOTEWAKEUP_DISABLE() my_callback_remotewakeup_disable() - extern void my_callback_remotewakeup_disable(void); + #define USB_DEVICE_ATTR \ + (USB_CONFIG_ATTR_REMOTE_WAKEUP | USB_CONFIG_ATTR_..._POWERED) + #define UDC_REMOTEWAKEUP_ENABLE() my_callback_remotewakeup_enable() + extern void my_callback_remotewakeup_enable(void); + #define UDC_REMOTEWAKEUP_DISABLE() my_callback_remotewakeup_disable() + extern void my_callback_remotewakeup_disable(void); \endcode * * Add to application C-file: * \code - void my_callback_remotewakeup_enable(void) - { - // Enable application wakeup events (e.g. enable GPIO interrupt) - } - void my_callback_remotewakeup_disable(void) - { - // Disable application wakeup events (e.g. disable GPIO interrupt) - } - - void my_interrupt_event(void) - { - udc_remotewakeup(); - } + void my_callback_remotewakeup_enable(void) + { + // Enable application wakeup events (e.g. enable GPIO interrupt) + } + void my_callback_remotewakeup_disable(void) + { + // Disable application wakeup events (e.g. disable GPIO interrupt) + } + + void my_interrupt_event(void) + { + udc_remotewakeup(); + } \endcode * * \subsection udc_use_case_3_usage_flow Workflow * -# Ensure that conf_usb.h is available and contains the following parameters * required to enable remote wakeup feature: * - \code // Authorizes the remote wakeup feature - #define USB_DEVICE_ATTR (USB_CONFIG_ATTR_REMOTE_WAKEUP | USB_CONFIG_ATTR_..._POWERED) \endcode + #define USB_DEVICE_ATTR (USB_CONFIG_ATTR_REMOTE_WAKEUP | USB_CONFIG_ATTR_..._POWERED) \endcode * - \code // Define callback called when the host enables the remotewakeup feature - #define UDC_REMOTEWAKEUP_ENABLE() my_callback_remotewakeup_enable() - extern void my_callback_remotewakeup_enable(void); \endcode + #define UDC_REMOTEWAKEUP_ENABLE() my_callback_remotewakeup_enable() + extern void my_callback_remotewakeup_enable(void); \endcode * - \code // Define callback called when the host disables the remotewakeup feature - #define UDC_REMOTEWAKEUP_DISABLE() my_callback_remotewakeup_disable() - extern void my_callback_remotewakeup_disable(void); \endcode + #define UDC_REMOTEWAKEUP_DISABLE() my_callback_remotewakeup_disable() + extern void my_callback_remotewakeup_disable(void); \endcode * -# Send a remote wakeup (USB upstream): * - \code udc_remotewakeup(); \endcode */ @@ -603,40 +596,40 @@ usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc(void); * \subsection udc_use_case_5_usage_code Example code * Content of conf_usb.h: * \code - #define USB_DEVICE_ATTR (USB_CONFIG_ATTR_BUS_POWERED) - #define UDC_SUSPEND_EVENT() user_callback_suspend_action() - extern void user_callback_suspend_action(void) - #define UDC_RESUME_EVENT() user_callback_resume_action() - extern void user_callback_resume_action(void) + #define USB_DEVICE_ATTR (USB_CONFIG_ATTR_BUS_POWERED) + #define UDC_SUSPEND_EVENT() user_callback_suspend_action() + extern void user_callback_suspend_action(void) + #define UDC_RESUME_EVENT() user_callback_resume_action() + extern void user_callback_resume_action(void) \endcode * * Add to application C-file: * \code - void user_callback_suspend_action(void) - { - // Disable hardware component to reduce power consumption - } - void user_callback_resume_action(void) - { - // Re-enable hardware component - } + void user_callback_suspend_action(void) + { + // Disable hardware component to reduce power consumption + } + void user_callback_resume_action(void) + { + // Re-enable hardware component + } \endcode * * \subsection udc_use_case_5_usage_flow Workflow * -# Ensure that conf_usb.h is available and contains the following parameters: * - \code // Authorizes the BUS power feature - #define USB_DEVICE_ATTR (USB_CONFIG_ATTR_BUS_POWERED) \endcode + #define USB_DEVICE_ATTR (USB_CONFIG_ATTR_BUS_POWERED) \endcode * - \code // Define callback called when the host suspend the USB line - #define UDC_SUSPEND_EVENT() user_callback_suspend_action() - extern void user_callback_suspend_action(void); \endcode + #define UDC_SUSPEND_EVENT() user_callback_suspend_action() + extern void user_callback_suspend_action(void); \endcode * - \code // Define callback called when the host or device resume the USB line - #define UDC_RESUME_EVENT() user_callback_resume_action() - extern void user_callback_resume_action(void); \endcode + #define UDC_RESUME_EVENT() user_callback_resume_action() + extern void user_callback_resume_action(void); \endcode * -# Reduce power consumption in suspend mode (max. 2.5mA on Vbus): * - \code void user_callback_suspend_action(void) - { - turn_off_components(); - } \endcode + { + turn_off_components(); + } \endcode */ /** @@ -654,42 +647,42 @@ usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc(void); * \subsection udc_use_case_6_usage_code Example code * Content of conf_usb.h: * \code - #define USB_DEVICE_SERIAL_NAME - #define USB_DEVICE_GET_SERIAL_NAME_POINTER serial_number - #define USB_DEVICE_GET_SERIAL_NAME_LENGTH 12 - extern uint8_t serial_number[]; + #define USB_DEVICE_SERIAL_NAME + #define USB_DEVICE_GET_SERIAL_NAME_POINTER serial_number + #define USB_DEVICE_GET_SERIAL_NAME_LENGTH 12 + extern uint8_t serial_number[]; \endcode * * Add to application C-file: * \code - uint8_t serial_number[USB_DEVICE_GET_SERIAL_NAME_LENGTH]; + uint8_t serial_number[USB_DEVICE_GET_SERIAL_NAME_LENGTH]; - void init_build_usb_serial_number(void) - { - serial_number[0] = 'A'; - serial_number[1] = 'B'; - ... - serial_number[USB_DEVICE_GET_SERIAL_NAME_LENGTH-1] = 'C'; - } \endcode + void init_build_usb_serial_number(void) + { + serial_number[0] = 'A'; + serial_number[1] = 'B'; + ... + serial_number[USB_DEVICE_GET_SERIAL_NAME_LENGTH-1] = 'C'; + } \endcode * * \subsection udc_use_case_6_usage_flow Workflow * -# Ensure that conf_usb.h is available and contains the following parameters * required to enable a USB serial number strings dynamically: * - \code #define USB_DEVICE_SERIAL_NAME // Define this empty - #define USB_DEVICE_GET_SERIAL_NAME_POINTER serial_number // Give serial array pointer - #define USB_DEVICE_GET_SERIAL_NAME_LENGTH 12 // Give size of serial array - extern uint8_t serial_number[]; // Declare external serial array \endcode + #define USB_DEVICE_GET_SERIAL_NAME_POINTER serial_number // Give serial array pointer + #define USB_DEVICE_GET_SERIAL_NAME_LENGTH 12 // Give size of serial array + extern uint8_t serial_number[]; // Declare external serial array \endcode * -# Before start USB stack, initialize the serial array * - \code - uint8_t serial_number[USB_DEVICE_GET_SERIAL_NAME_LENGTH]; - - void init_build_usb_serial_number(void) - { - serial_number[0] = 'A'; - serial_number[1] = 'B'; - ... - serial_number[USB_DEVICE_GET_SERIAL_NAME_LENGTH-1] = 'C'; - } \endcode + uint8_t serial_number[USB_DEVICE_GET_SERIAL_NAME_LENGTH]; + + void init_build_usb_serial_number(void) + { + serial_number[0] = 'A'; + serial_number[1] = 'B'; + ... + serial_number[USB_DEVICE_GET_SERIAL_NAME_LENGTH-1] = 'C'; + } \endcode */ diff --git a/Marlin/src/HAL/DUE/usb/udc_desc.h b/Marlin/src/HAL/DUE/usb/udc_desc.h index 052ca08eca78..f1f328d035c3 100644 --- a/Marlin/src/HAL/DUE/usb/udc_desc.h +++ b/Marlin/src/HAL/DUE/usb/udc_desc.h @@ -78,50 +78,47 @@ extern "C" { * For Mega application used "code". */ #define UDC_DESC_STORAGE - // Descriptor storage in internal RAM + // Descriptor storage in internal RAM #if (defined UDC_DATA_USE_HRAM_SUPPORT) -# if defined(__GNUC__) -# define UDC_DATA(x) COMPILER_WORD_ALIGNED __attribute__((__section__(".data_hram0"))) -# define UDC_BSS(x) COMPILER_ALIGNED(x) __attribute__((__section__(".bss_hram0"))) -# elif defined(__ICCAVR32__) -# define UDC_DATA(x) COMPILER_ALIGNED(x) __data32 -# define UDC_BSS(x) COMPILER_ALIGNED(x) __data32 -# endif + #if defined(__GNUC__) + #define UDC_DATA(x) COMPILER_WORD_ALIGNED __attribute__((__section__(".data_hram0"))) + #define UDC_BSS(x) COMPILER_ALIGNED(x) __attribute__((__section__(".bss_hram0"))) +#elif defined(__ICCAVR32__) + #define UDC_DATA(x) COMPILER_ALIGNED(x) __data32 + #define UDC_BSS(x) COMPILER_ALIGNED(x) __data32 +#endif #else -# define UDC_DATA(x) COMPILER_ALIGNED(x) -# define UDC_BSS(x) COMPILER_ALIGNED(x) + #define UDC_DATA(x) COMPILER_ALIGNED(x) + #define UDC_BSS(x) COMPILER_ALIGNED(x) #endif - - /** * \brief Configuration descriptor and UDI link for one USB speed */ typedef struct { - //! USB configuration descriptor - usb_conf_desc_t UDC_DESC_STORAGE *desc; - //! Array of UDI API pointer - udi_api_t UDC_DESC_STORAGE *UDC_DESC_STORAGE * udi_apis; + //! USB configuration descriptor + usb_conf_desc_t UDC_DESC_STORAGE *desc; + //! Array of UDI API pointer + udi_api_t UDC_DESC_STORAGE *UDC_DESC_STORAGE * udi_apis; } udc_config_speed_t; - /** * \brief All information about the USB Device */ typedef struct { - //! USB device descriptor for low or full speed - usb_dev_desc_t UDC_DESC_STORAGE *confdev_lsfs; - //! USB configuration descriptor and UDI API pointers for low or full speed - udc_config_speed_t UDC_DESC_STORAGE *conf_lsfs; -#ifdef USB_DEVICE_HS_SUPPORT - //! USB device descriptor for high speed - usb_dev_desc_t UDC_DESC_STORAGE *confdev_hs; - //! USB device qualifier, only use in high speed mode - usb_dev_qual_desc_t UDC_DESC_STORAGE *qualifier; - //! USB configuration descriptor and UDI API pointers for high speed - udc_config_speed_t UDC_DESC_STORAGE *conf_hs; -#endif - usb_dev_bos_desc_t UDC_DESC_STORAGE *conf_bos; + //! USB device descriptor for low or full speed + usb_dev_desc_t UDC_DESC_STORAGE *confdev_lsfs; + //! USB configuration descriptor and UDI API pointers for low or full speed + udc_config_speed_t UDC_DESC_STORAGE *conf_lsfs; + #ifdef USB_DEVICE_HS_SUPPORT + //! USB device descriptor for high speed + usb_dev_desc_t UDC_DESC_STORAGE *confdev_hs; + //! USB device qualifier, only use in high speed mode + usb_dev_qual_desc_t UDC_DESC_STORAGE *qualifier; + //! USB configuration descriptor and UDI API pointers for high speed + udc_config_speed_t UDC_DESC_STORAGE *conf_hs; + #endif + usb_dev_bos_desc_t UDC_DESC_STORAGE *conf_bos; } udc_config_t; //! Global variables of USB Device Descriptor and UDI links diff --git a/Marlin/src/HAL/DUE/usb/udd.h b/Marlin/src/HAL/DUE/usb/udd.h index 319d8842f744..6eda465e54a4 100644 --- a/Marlin/src/HAL/DUE/usb/udd.h +++ b/Marlin/src/HAL/DUE/usb/udd.h @@ -71,8 +71,8 @@ typedef uint8_t udd_ep_id_t; //! \brief Endpoint transfer status //! Returned in parameters of callback register via udd_ep_run routine. typedef enum { - UDD_EP_TRANSFER_OK = 0, - UDD_EP_TRANSFER_ABORT = 1, + UDD_EP_TRANSFER_OK = 0, + UDD_EP_TRANSFER_ABORT = 1, } udd_ep_status_t; /** @@ -82,41 +82,37 @@ typedef enum { * It can be updated by udc_process_setup() from UDC or *setup() from UDIs. */ typedef struct { - //! Data received in USB SETUP packet - //! Note: The swap of "req.wValues" from uin16_t to le16_t is done by UDD. - usb_setup_req_t req; + //! Data received in USB SETUP packet + //! Note: The swap of "req.wValues" from uin16_t to le16_t is done by UDD. + usb_setup_req_t req; - //! Point to buffer to send or fill with data following SETUP packet - //! This buffer must be word align for DATA IN phase (use prefix COMPILER_WORD_ALIGNED for buffer) - uint8_t *payload; + //! Point to buffer to send or fill with data following SETUP packet + //! This buffer must be word align for DATA IN phase (use prefix COMPILER_WORD_ALIGNED for buffer) + uint8_t *payload; - //! Size of buffer to send or fill, and content the number of byte transferred - uint16_t payload_size; + //! Size of buffer to send or fill, and content the number of byte transferred + uint16_t payload_size; - //! Callback called after reception of ZLP from setup request - void (*callback)(void); + //! Callback called after reception of ZLP from setup request + void (*callback)(void); - //! Callback called when the buffer given (.payload) is full or empty. - //! This one return false to abort data transfer, or true with a new buffer in .payload. - bool (*over_under_run)(void); + //! Callback called when the buffer given (.payload) is full or empty. + //! This one return false to abort data transfer, or true with a new buffer in .payload. + bool (*over_under_run)(void); } udd_ctrl_request_t; extern udd_ctrl_request_t udd_g_ctrlreq; //! Return true if the setup request \a udd_g_ctrlreq indicates IN data transfer -#define Udd_setup_is_in() \ - (USB_REQ_DIR_IN == (udd_g_ctrlreq.req.bmRequestType & USB_REQ_DIR_MASK)) +#define Udd_setup_is_in() (USB_REQ_DIR_IN == (udd_g_ctrlreq.req.bmRequestType & USB_REQ_DIR_MASK)) //! Return true if the setup request \a udd_g_ctrlreq indicates OUT data transfer -#define Udd_setup_is_out() \ - (USB_REQ_DIR_OUT == (udd_g_ctrlreq.req.bmRequestType & USB_REQ_DIR_MASK)) +#define Udd_setup_is_out() (USB_REQ_DIR_OUT == (udd_g_ctrlreq.req.bmRequestType & USB_REQ_DIR_MASK)) //! Return the type of the SETUP request \a udd_g_ctrlreq. \see usb_reqtype. -#define Udd_setup_type() \ - (udd_g_ctrlreq.req.bmRequestType & USB_REQ_TYPE_MASK) +#define Udd_setup_type() (udd_g_ctrlreq.req.bmRequestType & USB_REQ_TYPE_MASK) //! Return the recipient of the SETUP request \a udd_g_ctrlreq. \see usb_recipient -#define Udd_setup_recipient() \ - (udd_g_ctrlreq.req.bmRequestType & USB_REQ_RECIP_MASK) +#define Udd_setup_recipient() (udd_g_ctrlreq.req.bmRequestType & USB_REQ_RECIP_MASK) /** * \brief End of halt callback function type. @@ -134,8 +130,7 @@ typedef void (*udd_callback_halt_cleared_t)(void); * \param status UDD_EP_TRANSFER_ABORT, if transfer is aborted * \param n number of data transferred */ -typedef void (*udd_callback_trans_t) (udd_ep_status_t status, - iram_size_t nb_transferred, udd_ep_id_t ep); +typedef void (*udd_callback_trans_t) (udd_ep_status_t status, iram_size_t nb_transferred, udd_ep_id_t ep); /** * \brief Authorizes the VBUS event @@ -239,8 +234,7 @@ void udd_set_setup_payload( uint8_t *payload, uint16_t payload_size ); * * \return \c 1 if the endpoint is enabled, otherwise \c 0. */ -bool udd_ep_alloc(udd_ep_id_t ep, uint8_t bmAttributes, - uint16_t MaxEndpointSize); +bool udd_ep_alloc(udd_ep_id_t ep, uint8_t bmAttributes, uint16_t MaxEndpointSize); /** * \brief Disables an endpoint @@ -294,8 +288,7 @@ bool udd_ep_clear_halt(udd_ep_id_t ep); * * \return \c 1 if the register is accepted, otherwise \c 0. */ -bool udd_ep_wait_stall_clear(udd_ep_id_t ep, - udd_callback_halt_cleared_t callback); +bool udd_ep_wait_stall_clear(udd_ep_id_t ep, udd_callback_halt_cleared_t callback); /** * \brief Allows to receive or send data on an endpoint @@ -321,9 +314,8 @@ bool udd_ep_wait_stall_clear(udd_ep_id_t ep, * * \return \c 1 if function was successfully done, otherwise \c 0. */ -bool udd_ep_run(udd_ep_id_t ep, bool b_shortpacket, - uint8_t * buf, iram_size_t buf_size, - udd_callback_trans_t callback); +bool udd_ep_run(udd_ep_id_t ep, bool b_shortpacket, uint8_t * buf, iram_size_t buf_size, udd_callback_trans_t callback); + /** * \brief Aborts transfer on going on endpoint * @@ -339,7 +331,6 @@ void udd_ep_abort(udd_ep_id_t ep); //@} - /** * \name High speed test mode management * @@ -352,7 +343,6 @@ void udd_test_mode_se0_nak(void); void udd_test_mode_packet(void); //@} - /** * \name UDC callbacks to provide for UDD * diff --git a/Marlin/src/HAL/DUE/usb/udi.h b/Marlin/src/HAL/DUE/usb/udi.h index febf03b7181e..bc5de086f3ce 100644 --- a/Marlin/src/HAL/DUE/usb/udi.h +++ b/Marlin/src/HAL/DUE/usb/udi.h @@ -72,57 +72,57 @@ extern "C" { * selected by UDC. */ typedef struct { - /** - * \brief Enable the interface. - * - * This function is called when the host selects a configuration - * to which this interface belongs through a Set Configuration - * request, and when the host selects an alternate setting of - * this interface through a Set Interface request. - * - * \return \c 1 if function was successfully done, otherwise \c 0. - */ - bool (*enable)(void); + /** + * \brief Enable the interface. + * + * This function is called when the host selects a configuration + * to which this interface belongs through a Set Configuration + * request, and when the host selects an alternate setting of + * this interface through a Set Interface request. + * + * \return \c 1 if function was successfully done, otherwise \c 0. + */ + bool (*enable)(void); - /** - * \brief Disable the interface. - * - * This function is called when this interface is currently - * active, and - * - the host selects any configuration through a Set - * Configuration request, or - * - the host issues a USB reset, or - * - the device is detached from the host (i.e. Vbus is no - * longer present) - */ - void (*disable)(void); + /** + * \brief Disable the interface. + * + * This function is called when this interface is currently + * active, and + * - the host selects any configuration through a Set + * Configuration request, or + * - the host issues a USB reset, or + * - the device is detached from the host (i.e. Vbus is no + * longer present) + */ + void (*disable)(void); - /** - * \brief Handle a control request directed at an interface. - * - * This function is called when this interface is currently - * active and the host sends a SETUP request - * with this interface as the recipient. - * - * Use udd_g_ctrlreq to decode and response to SETUP request. - * - * \return \c 1 if this interface supports the SETUP request, otherwise \c 0. - */ - bool (*setup)(void); + /** + * \brief Handle a control request directed at an interface. + * + * This function is called when this interface is currently + * active and the host sends a SETUP request + * with this interface as the recipient. + * + * Use udd_g_ctrlreq to decode and response to SETUP request. + * + * \return \c 1 if this interface supports the SETUP request, otherwise \c 0. + */ + bool (*setup)(void); - /** - * \brief Returns the current setting of the selected interface. - * - * This function is called when UDC when know alternate setting of selected interface. - * - * \return alternate setting of selected interface - */ - uint8_t (*getsetting)(void); + /** + * \brief Returns the current setting of the selected interface. + * + * This function is called when UDC when know alternate setting of selected interface. + * + * \return alternate setting of selected interface + */ + uint8_t (*getsetting)(void); - /** - * \brief To signal that a SOF is occurred - */ - void (*sof_notify)(void); + /** + * \brief To signal that a SOF is occurred + */ + void (*sof_notify)(void); } udi_api_t; //@} diff --git a/Marlin/src/HAL/DUE/usb/udi_cdc.h b/Marlin/src/HAL/DUE/usb/udi_cdc.h index b61845011aa2..2bc5fff18716 100644 --- a/Marlin/src/HAL/DUE/usb/udi_cdc.h +++ b/Marlin/src/HAL/DUE/usb/udi_cdc.h @@ -92,18 +92,18 @@ extern UDC_DESC_STORAGE udi_api_t udi_api_cdc_data; * descriptors for the CDC Communication Class interface. */ typedef struct { - //! Standard interface descriptor - usb_iface_desc_t iface; - //! CDC Header functional descriptor - usb_cdc_hdr_desc_t header; - //! CDC Abstract Control Model functional descriptor - usb_cdc_acm_desc_t acm; - //! CDC Union functional descriptor - usb_cdc_union_desc_t union_desc; - //! CDC Call Management functional descriptor - usb_cdc_call_mgmt_desc_t call_mgmt; - //! Notification endpoint descriptor - usb_ep_desc_t ep_notify; + //! Standard interface descriptor + usb_iface_desc_t iface; + //! CDC Header functional descriptor + usb_cdc_hdr_desc_t header; + //! CDC Abstract Control Model functional descriptor + usb_cdc_acm_desc_t acm; + //! CDC Union functional descriptor + usb_cdc_union_desc_t union_desc; + //! CDC Call Management functional descriptor + usb_cdc_call_mgmt_desc_t call_mgmt; + //! Notification endpoint descriptor + usb_ep_desc_t ep_notify; } udi_cdc_comm_desc_t; @@ -114,11 +114,11 @@ typedef struct { * CDC Data Class interface. */ typedef struct { - //! Standard interface descriptor - usb_iface_desc_t iface; - //! Data IN/OUT endpoint descriptors - usb_ep_desc_t ep_in; - usb_ep_desc_t ep_out; + //! Standard interface descriptor + usb_iface_desc_t iface; + //! Data IN/OUT endpoint descriptors + usb_ep_desc_t ep_in; + usb_ep_desc_t ep_out; } udi_cdc_data_desc_t; @@ -136,13 +136,13 @@ typedef struct { //@{ //! By default no string associated to these interfaces #ifndef UDI_CDC_IAD_STRING_ID_0 -#define UDI_CDC_IAD_STRING_ID_0 0 + #define UDI_CDC_IAD_STRING_ID_0 0 #endif #ifndef UDI_CDC_COMM_STRING_ID_0 -#define UDI_CDC_COMM_STRING_ID_0 0 + #define UDI_CDC_COMM_STRING_ID_0 0 #endif #ifndef UDI_CDC_DATA_STRING_ID_0 -#define UDI_CDC_DATA_STRING_ID_0 0 + #define UDI_CDC_DATA_STRING_ID_0 0 #endif #define UDI_CDC_IAD_DESC_0 UDI_CDC_IAD_DESC(0) #define UDI_CDC_COMM_DESC_0 UDI_CDC_COMM_DESC(0) @@ -151,13 +151,13 @@ typedef struct { //! By default no string associated to these interfaces #ifndef UDI_CDC_IAD_STRING_ID_1 -#define UDI_CDC_IAD_STRING_ID_1 0 + #define UDI_CDC_IAD_STRING_ID_1 0 #endif #ifndef UDI_CDC_COMM_STRING_ID_1 -#define UDI_CDC_COMM_STRING_ID_1 0 + #define UDI_CDC_COMM_STRING_ID_1 0 #endif #ifndef UDI_CDC_DATA_STRING_ID_1 -#define UDI_CDC_DATA_STRING_ID_1 0 + #define UDI_CDC_DATA_STRING_ID_1 0 #endif #define UDI_CDC_IAD_DESC_1 UDI_CDC_IAD_DESC(1) #define UDI_CDC_COMM_DESC_1 UDI_CDC_COMM_DESC(1) @@ -166,13 +166,13 @@ typedef struct { //! By default no string associated to these interfaces #ifndef UDI_CDC_IAD_STRING_ID_2 -#define UDI_CDC_IAD_STRING_ID_2 0 + #define UDI_CDC_IAD_STRING_ID_2 0 #endif #ifndef UDI_CDC_COMM_STRING_ID_2 -#define UDI_CDC_COMM_STRING_ID_2 0 + #define UDI_CDC_COMM_STRING_ID_2 0 #endif #ifndef UDI_CDC_DATA_STRING_ID_2 -#define UDI_CDC_DATA_STRING_ID_2 0 + #define UDI_CDC_DATA_STRING_ID_2 0 #endif #define UDI_CDC_IAD_DESC_2 UDI_CDC_IAD_DESC(2) #define UDI_CDC_COMM_DESC_2 UDI_CDC_COMM_DESC(2) @@ -181,13 +181,13 @@ typedef struct { //! By default no string associated to these interfaces #ifndef UDI_CDC_IAD_STRING_ID_3 -#define UDI_CDC_IAD_STRING_ID_3 0 + #define UDI_CDC_IAD_STRING_ID_3 0 #endif #ifndef UDI_CDC_COMM_STRING_ID_3 -#define UDI_CDC_COMM_STRING_ID_3 0 + #define UDI_CDC_COMM_STRING_ID_3 0 #endif #ifndef UDI_CDC_DATA_STRING_ID_3 -#define UDI_CDC_DATA_STRING_ID_3 0 + #define UDI_CDC_DATA_STRING_ID_3 0 #endif #define UDI_CDC_IAD_DESC_3 UDI_CDC_IAD_DESC(3) #define UDI_CDC_COMM_DESC_3 UDI_CDC_COMM_DESC(3) @@ -196,13 +196,13 @@ typedef struct { //! By default no string associated to these interfaces #ifndef UDI_CDC_IAD_STRING_ID_4 -#define UDI_CDC_IAD_STRING_ID_4 0 + #define UDI_CDC_IAD_STRING_ID_4 0 #endif #ifndef UDI_CDC_COMM_STRING_ID_4 -#define UDI_CDC_COMM_STRING_ID_4 0 + #define UDI_CDC_COMM_STRING_ID_4 0 #endif #ifndef UDI_CDC_DATA_STRING_ID_4 -#define UDI_CDC_DATA_STRING_ID_4 0 + #define UDI_CDC_DATA_STRING_ID_4 0 #endif #define UDI_CDC_IAD_DESC_4 UDI_CDC_IAD_DESC(4) #define UDI_CDC_COMM_DESC_4 UDI_CDC_COMM_DESC(4) @@ -211,13 +211,13 @@ typedef struct { //! By default no string associated to these interfaces #ifndef UDI_CDC_IAD_STRING_ID_5 -#define UDI_CDC_IAD_STRING_ID_5 0 + #define UDI_CDC_IAD_STRING_ID_5 0 #endif #ifndef UDI_CDC_COMM_STRING_ID_5 -#define UDI_CDC_COMM_STRING_ID_5 0 + #define UDI_CDC_COMM_STRING_ID_5 0 #endif #ifndef UDI_CDC_DATA_STRING_ID_5 -#define UDI_CDC_DATA_STRING_ID_5 0 + #define UDI_CDC_DATA_STRING_ID_5 0 #endif #define UDI_CDC_IAD_DESC_5 UDI_CDC_IAD_DESC(5) #define UDI_CDC_COMM_DESC_5 UDI_CDC_COMM_DESC(5) @@ -226,13 +226,13 @@ typedef struct { //! By default no string associated to these interfaces #ifndef UDI_CDC_IAD_STRING_ID_6 -#define UDI_CDC_IAD_STRING_ID_6 0 + #define UDI_CDC_IAD_STRING_ID_6 0 #endif #ifndef UDI_CDC_COMM_STRING_ID_6 -#define UDI_CDC_COMM_STRING_ID_6 0 + #define UDI_CDC_COMM_STRING_ID_6 0 #endif #ifndef UDI_CDC_DATA_STRING_ID_6 -#define UDI_CDC_DATA_STRING_ID_6 0 + #define UDI_CDC_DATA_STRING_ID_6 0 #endif #define UDI_CDC_IAD_DESC_6 UDI_CDC_IAD_DESC(6) #define UDI_CDC_COMM_DESC_6 UDI_CDC_COMM_DESC(6) @@ -240,7 +240,6 @@ typedef struct { #define UDI_CDC_DATA_DESC_6_HS UDI_CDC_DATA_DESC_HS(6) //@} - //! Content of CDC IAD interface descriptor for all speeds #define UDI_CDC_IAD_DESC(port) { \ .bLength = sizeof(usb_iad_desc_t),\ @@ -270,7 +269,7 @@ typedef struct { .call_mgmt.bDescriptorType = CDC_CS_INTERFACE,\ .call_mgmt.bDescriptorSubtype = CDC_SCS_CALL_MGMT,\ .call_mgmt.bmCapabilities = \ - CDC_CALL_MGMT_SUPPORTED | CDC_CALL_MGMT_OVER_DCI,\ + CDC_CALL_MGMT_SUPPORTED | CDC_CALL_MGMT_OVER_DCI,\ .acm.bFunctionLength = sizeof(usb_cdc_acm_desc_t),\ .acm.bDescriptorType = CDC_CS_INTERFACE,\ .acm.bDescriptorSubtype = CDC_SCS_ACM,\ @@ -610,40 +609,37 @@ iram_size_t udi_cdc_multi_write_buf(uint8_t port, const void* buf, iram_size_t s * \subsection udi_cdc_basic_use_case_usage_code Example code * Content of conf_usb.h: * \code - #define UDI_CDC_ENABLE_EXT(port) my_callback_cdc_enable() - extern bool my_callback_cdc_enable(void); - #define UDI_CDC_DISABLE_EXT(port) my_callback_cdc_disable() - extern void my_callback_cdc_disable(void); - #define UDI_CDC_LOW_RATE - - #define UDI_CDC_DEFAULT_RATE 115200 - #define UDI_CDC_DEFAULT_STOPBITS CDC_STOP_BITS_1 - #define UDI_CDC_DEFAULT_PARITY CDC_PAR_NONE - #define UDI_CDC_DEFAULT_DATABITS 8 - - #include "udi_cdc_conf.h" // At the end of conf_usb.h file + #define UDI_CDC_ENABLE_EXT(port) my_callback_cdc_enable() + extern bool my_callback_cdc_enable(void); + #define UDI_CDC_DISABLE_EXT(port) my_callback_cdc_disable() + extern void my_callback_cdc_disable(void); + #define UDI_CDC_LOW_RATE + + #define UDI_CDC_DEFAULT_RATE 115200 + #define UDI_CDC_DEFAULT_STOPBITS CDC_STOP_BITS_1 + #define UDI_CDC_DEFAULT_PARITY CDC_PAR_NONE + #define UDI_CDC_DEFAULT_DATABITS 8 + + #include "udi_cdc_conf.h" // At the end of conf_usb.h file \endcode * * Add to application C-file: * \code - static bool my_flag_autorize_cdc_transfert = false; - bool my_callback_cdc_enable(void) - { - my_flag_autorize_cdc_transfert = true; - return true; - } - void my_callback_cdc_disable(void) - { - my_flag_autorize_cdc_transfert = false; - } - - void task(void) - { - if (my_flag_autorize_cdc_transfert) { - udi_cdc_putc('A'); - udi_cdc_getc(); - } - } + static bool my_flag_autorize_cdc_transfert = false; + bool my_callback_cdc_enable(void) { + my_flag_autorize_cdc_transfert = true; + return true; + } + void my_callback_cdc_disable(void) { + my_flag_autorize_cdc_transfert = false; + } + + void task(void) { + if (my_flag_autorize_cdc_transfert) { + udi_cdc_putc('A'); + udi_cdc_getc(); + } + } \endcode * * \subsection udi_cdc_basic_use_case_setup_flow Workflow @@ -652,14 +648,14 @@ iram_size_t udi_cdc_multi_write_buf(uint8_t port, const void* buf, iram_size_t s * - \code #define USB_DEVICE_SERIAL_NAME "12...EF" // Disk SN for CDC \endcode * \note The USB serial number is mandatory when a CDC interface is used. * - \code #define UDI_CDC_ENABLE_EXT(port) my_callback_cdc_enable() - extern bool my_callback_cdc_enable(void); \endcode + extern bool my_callback_cdc_enable(void); \endcode * \note After the device enumeration (detecting and identifying USB devices), * the USB host starts the device configuration. When the USB CDC interface * from the device is accepted by the host, the USB host enables this interface and the * UDI_CDC_ENABLE_EXT() callback function is called and return true. * Thus, when this event is received, the data transfer on CDC interface are authorized. * - \code #define UDI_CDC_DISABLE_EXT(port) my_callback_cdc_disable() - extern void my_callback_cdc_disable(void); \endcode + extern void my_callback_cdc_disable(void); \endcode * \note When the USB device is unplugged or is reset by the USB host, the USB * interface is disabled and the UDI_CDC_DISABLE_EXT() callback function * is called. Thus, the data transfer must be stopped on CDC interface. @@ -667,19 +663,19 @@ iram_size_t udi_cdc_multi_write_buf(uint8_t port, const void* buf, iram_size_t s * \note Define it when the transfer CDC Device to Host is a low rate * (<512000 bauds) to reduce CDC buffers size. * - \code #define UDI_CDC_DEFAULT_RATE 115200 - #define UDI_CDC_DEFAULT_STOPBITS CDC_STOP_BITS_1 - #define UDI_CDC_DEFAULT_PARITY CDC_PAR_NONE - #define UDI_CDC_DEFAULT_DATABITS 8 \endcode + #define UDI_CDC_DEFAULT_STOPBITS CDC_STOP_BITS_1 + #define UDI_CDC_DEFAULT_PARITY CDC_PAR_NONE + #define UDI_CDC_DEFAULT_DATABITS 8 \endcode * \note Default configuration of communication port at startup. * -# Send or wait data on CDC line: * - \code // Waits and gets a value on CDC line - int udi_cdc_getc(void); - // Reads a RAM buffer on CDC line - iram_size_t udi_cdc_read_buf(int *buf, iram_size_t size); - // Puts a byte on CDC line - int udi_cdc_putc(int value); - // Writes a RAM buffer on CDC line - iram_size_t udi_cdc_write_buf(const int *buf, iram_size_t size); \endcode + int udi_cdc_getc(void); + // Reads a RAM buffer on CDC line + iram_size_t udi_cdc_read_buf(int *buf, iram_size_t size); + // Puts a byte on CDC line + int udi_cdc_putc(int value); + // Writes a RAM buffer on CDC line + iram_size_t udi_cdc_write_buf(const int *buf, iram_size_t size); \endcode * * \section udi_cdc_use_cases Advanced use cases * For more advanced use of the UDI CDC module, see the following use cases: @@ -713,90 +709,90 @@ iram_size_t udi_cdc_multi_write_buf(uint8_t port, const void* buf, iram_size_t s * \subsection udi_cdc_use_case_composite_usage_code Example code * Content of conf_usb.h: * \code - #define USB_DEVICE_EP_CTRL_SIZE 64 - #define USB_DEVICE_NB_INTERFACE (X+2) - #define USB_DEVICE_MAX_EP (X+3) - - #define UDI_CDC_DATA_EP_IN_0 (1 | USB_EP_DIR_IN) // TX - #define UDI_CDC_DATA_EP_OUT_0 (2 | USB_EP_DIR_OUT) // RX - #define UDI_CDC_COMM_EP_0 (3 | USB_EP_DIR_IN) // Notify endpoint - #define UDI_CDC_COMM_IFACE_NUMBER_0 X+0 - #define UDI_CDC_DATA_IFACE_NUMBER_0 X+1 - - #define UDI_COMPOSITE_DESC_T \ - usb_iad_desc_t udi_cdc_iad; \ - udi_cdc_comm_desc_t udi_cdc_comm; \ - udi_cdc_data_desc_t udi_cdc_data; \ - ... - #define UDI_COMPOSITE_DESC_FS \ - .udi_cdc_iad = UDI_CDC_IAD_DESC_0, \ - .udi_cdc_comm = UDI_CDC_COMM_DESC_0, \ - .udi_cdc_data = UDI_CDC_DATA_DESC_0_FS, \ - ... - #define UDI_COMPOSITE_DESC_HS \ - .udi_cdc_iad = UDI_CDC_IAD_DESC_0, \ - .udi_cdc_comm = UDI_CDC_COMM_DESC_0, \ - .udi_cdc_data = UDI_CDC_DATA_DESC_0_HS, \ - ... - #define UDI_COMPOSITE_API \ - &udi_api_cdc_comm, \ - &udi_api_cdc_data, \ - ... + #define USB_DEVICE_EP_CTRL_SIZE 64 + #define USB_DEVICE_NB_INTERFACE (X+2) + #define USB_DEVICE_MAX_EP (X+3) + + #define UDI_CDC_DATA_EP_IN_0 (1 | USB_EP_DIR_IN) // TX + #define UDI_CDC_DATA_EP_OUT_0 (2 | USB_EP_DIR_OUT) // RX + #define UDI_CDC_COMM_EP_0 (3 | USB_EP_DIR_IN) // Notify endpoint + #define UDI_CDC_COMM_IFACE_NUMBER_0 X+0 + #define UDI_CDC_DATA_IFACE_NUMBER_0 X+1 + + #define UDI_COMPOSITE_DESC_T \ + usb_iad_desc_t udi_cdc_iad; \ + udi_cdc_comm_desc_t udi_cdc_comm; \ + udi_cdc_data_desc_t udi_cdc_data; \ + ... + #define UDI_COMPOSITE_DESC_FS \ + .udi_cdc_iad = UDI_CDC_IAD_DESC_0, \ + .udi_cdc_comm = UDI_CDC_COMM_DESC_0, \ + .udi_cdc_data = UDI_CDC_DATA_DESC_0_FS, \ + ... + #define UDI_COMPOSITE_DESC_HS \ + .udi_cdc_iad = UDI_CDC_IAD_DESC_0, \ + .udi_cdc_comm = UDI_CDC_COMM_DESC_0, \ + .udi_cdc_data = UDI_CDC_DATA_DESC_0_HS, \ + ... + #define UDI_COMPOSITE_API \ + &udi_api_cdc_comm, \ + &udi_api_cdc_data, \ + ... \endcode * * \subsection udi_cdc_use_case_composite_usage_flow Workflow * -# Ensure that conf_usb.h is available and contains the following parameters * required for a USB composite device configuration: * - \code // Endpoint control size, This must be: - // - 8, 16, 32 or 64 for full speed device (8 is recommended to save RAM) - // - 64 for a high speed device - #define USB_DEVICE_EP_CTRL_SIZE 64 - // Total Number of interfaces on this USB device. - // Add 2 for CDC. - #define USB_DEVICE_NB_INTERFACE (X+2) - // Total number of endpoints on this USB device. - // This must include each endpoint for each interface. - // Add 3 for CDC. - #define USB_DEVICE_MAX_EP (X+3) \endcode + // - 8, 16, 32 or 64 for full speed device (8 is recommended to save RAM) + // - 64 for a high speed device + #define USB_DEVICE_EP_CTRL_SIZE 64 + // Total Number of interfaces on this USB device. + // Add 2 for CDC. + #define USB_DEVICE_NB_INTERFACE (X+2) + // Total number of endpoints on this USB device. + // This must include each endpoint for each interface. + // Add 3 for CDC. + #define USB_DEVICE_MAX_EP (X+3) \endcode * -# Ensure that conf_usb.h contains the description of * composite device: * - \code // The endpoint numbers chosen by you for the CDC. - // The endpoint numbers starting from 1. - #define UDI_CDC_DATA_EP_IN_0 (1 | USB_EP_DIR_IN) // TX - #define UDI_CDC_DATA_EP_OUT_0 (2 | USB_EP_DIR_OUT) // RX - #define UDI_CDC_COMM_EP_0 (3 | USB_EP_DIR_IN) // Notify endpoint - // The interface index of an interface starting from 0 - #define UDI_CDC_COMM_IFACE_NUMBER_0 X+0 - #define UDI_CDC_DATA_IFACE_NUMBER_0 X+1 \endcode + // The endpoint numbers starting from 1. + #define UDI_CDC_DATA_EP_IN_0 (1 | USB_EP_DIR_IN) // TX + #define UDI_CDC_DATA_EP_OUT_0 (2 | USB_EP_DIR_OUT) // RX + #define UDI_CDC_COMM_EP_0 (3 | USB_EP_DIR_IN) // Notify endpoint + // The interface index of an interface starting from 0 + #define UDI_CDC_COMM_IFACE_NUMBER_0 X+0 + #define UDI_CDC_DATA_IFACE_NUMBER_0 X+1 \endcode * -# Ensure that conf_usb.h contains the following parameters * required for a USB composite device configuration: * - \code // USB Interfaces descriptor structure - #define UDI_COMPOSITE_DESC_T \ - ... - usb_iad_desc_t udi_cdc_iad; \ - udi_cdc_comm_desc_t udi_cdc_comm; \ - udi_cdc_data_desc_t udi_cdc_data; \ - ... - // USB Interfaces descriptor value for Full Speed - #define UDI_COMPOSITE_DESC_FS \ - ... - .udi_cdc_iad = UDI_CDC_IAD_DESC_0, \ - .udi_cdc_comm = UDI_CDC_COMM_DESC_0, \ - .udi_cdc_data = UDI_CDC_DATA_DESC_0_FS, \ - ... - // USB Interfaces descriptor value for High Speed - #define UDI_COMPOSITE_DESC_HS \ - ... - .udi_cdc_iad = UDI_CDC_IAD_DESC_0, \ - .udi_cdc_comm = UDI_CDC_COMM_DESC_0, \ - .udi_cdc_data = UDI_CDC_DATA_DESC_0_HS, \ - ... - // USB Interface APIs - #define UDI_COMPOSITE_API \ - ... - &udi_api_cdc_comm, \ - &udi_api_cdc_data, \ - ... \endcode + #define UDI_COMPOSITE_DESC_T \ + ... + usb_iad_desc_t udi_cdc_iad; \ + udi_cdc_comm_desc_t udi_cdc_comm; \ + udi_cdc_data_desc_t udi_cdc_data; \ + ... + // USB Interfaces descriptor value for Full Speed + #define UDI_COMPOSITE_DESC_FS \ + ... + .udi_cdc_iad = UDI_CDC_IAD_DESC_0, \ + .udi_cdc_comm = UDI_CDC_COMM_DESC_0, \ + .udi_cdc_data = UDI_CDC_DATA_DESC_0_FS, \ + ... + // USB Interfaces descriptor value for High Speed + #define UDI_COMPOSITE_DESC_HS \ + ... + .udi_cdc_iad = UDI_CDC_IAD_DESC_0, \ + .udi_cdc_comm = UDI_CDC_COMM_DESC_0, \ + .udi_cdc_data = UDI_CDC_DATA_DESC_0_HS, \ + ... + // USB Interface APIs + #define UDI_COMPOSITE_API \ + ... + &udi_api_cdc_comm, \ + &udi_api_cdc_data, \ + ... \endcode * - \note The descriptors order given in the four lists above must be the * same as the order defined by all interface indexes. The interface index * orders are defined through UDI_X_IFACE_NUMBER defines.\n diff --git a/Marlin/src/HAL/DUE/usb/udi_msc.c b/Marlin/src/HAL/DUE/usb/udi_msc.c index a75b5936b338..3f70a8fb18bc 100644 --- a/Marlin/src/HAL/DUE/usb/udi_msc.c +++ b/Marlin/src/HAL/DUE/usb/udi_msc.c @@ -372,9 +372,7 @@ static void udi_msc_sbc_trans(bool b_read); //@} - -bool udi_msc_enable(void) -{ +bool udi_msc_enable(void) { uint8_t lun; udi_msc_b_trans_req = false; udi_msc_b_cbw_invalid = false; @@ -397,18 +395,14 @@ bool udi_msc_enable(void) return true; } - -void udi_msc_disable(void) -{ +void udi_msc_disable(void) { udi_msc_b_trans_req = false; udi_msc_b_ack_trans = true; udi_msc_b_reset_trans = true; UDI_MSC_DISABLE_EXT(); } - -bool udi_msc_setup(void) -{ +bool udi_msc_setup(void) { if (Udd_setup_is_in()) { // Requests Interface GET if (Udd_setup_type() == USB_REQ_TYPE_CLASS) { @@ -451,17 +445,14 @@ bool udi_msc_setup(void) return false; // Not supported request } -uint8_t udi_msc_getsetting(void) -{ +uint8_t udi_msc_getsetting(void) { return 0; // MSC don't have multiple alternate setting } - // ------------------------ //------- Routines to process CBW packet -static void udi_msc_cbw_invalid(void) -{ +static void udi_msc_cbw_invalid(void) { if (!udi_msc_b_cbw_invalid) return; // Don't re-stall endpoint if error reset by setup udd_ep_set_halt(UDI_MSC_EP_OUT); @@ -469,8 +460,7 @@ static void udi_msc_cbw_invalid(void) udd_ep_wait_stall_clear(UDI_MSC_EP_OUT, udi_msc_cbw_invalid); } -static void udi_msc_csw_invalid(void) -{ +static void udi_msc_csw_invalid(void) { if (!udi_msc_b_cbw_invalid) return; // Don't re-stall endpoint if error reset by setup udd_ep_set_halt(UDI_MSC_EP_IN); @@ -478,8 +468,7 @@ static void udi_msc_csw_invalid(void) udd_ep_wait_stall_clear(UDI_MSC_EP_IN, udi_msc_csw_invalid); } -static void udi_msc_cbw_wait(void) -{ +static void udi_msc_cbw_wait(void) { // Register buffer and callback on OUT endpoint if (!udd_ep_run(UDI_MSC_EP_OUT, true, (uint8_t *) & udi_msc_cbw, @@ -490,10 +479,8 @@ static void udi_msc_cbw_wait(void) } } - static void udi_msc_cbw_received(udd_ep_status_t status, - iram_size_t nb_received, udd_ep_id_t ep) -{ + iram_size_t nb_received, udd_ep_id_t ep) { UNUSED(ep); // Check status of transfer if (UDD_EP_TRANSFER_OK != status) { @@ -582,9 +569,7 @@ static void udi_msc_cbw_received(udd_ep_status_t status, } } - -static bool udi_msc_cbw_validate(uint32_t alloc_len, uint8_t dir_flag) -{ +static bool udi_msc_cbw_validate(uint32_t alloc_len, uint8_t dir_flag) { /* * The following cases should result in a phase error: * - Case 2: Hn < Di @@ -612,12 +597,10 @@ static bool udi_msc_cbw_validate(uint32_t alloc_len, uint8_t dir_flag) return true; } - // ------------------------ //------- Routines to process small data packet -static void udi_msc_data_send(uint8_t * buffer, uint8_t buf_size) -{ +static void udi_msc_data_send(uint8_t * buffer, uint8_t buf_size) { // Sends data on IN endpoint if (!udd_ep_run(UDI_MSC_EP_IN, true, buffer, buf_size, udi_msc_data_sent)) { @@ -627,10 +610,8 @@ static void udi_msc_data_send(uint8_t * buffer, uint8_t buf_size) } } - static void udi_msc_data_sent(udd_ep_status_t status, iram_size_t nb_sent, - udd_ep_id_t ep) -{ + udd_ep_id_t ep) { UNUSED(ep); if (UDD_EP_TRANSFER_OK != status) { // Error protocol @@ -644,12 +625,10 @@ static void udi_msc_data_sent(udd_ep_status_t status, iram_size_t nb_sent, udi_msc_csw_process(); } - // ------------------------ //------- Routines to process CSW packet -static void udi_msc_csw_process(void) -{ +static void udi_msc_csw_process(void) { if (0 != udi_msc_csw.dCSWDataResidue) { // Residue not NULL // then STALL next request from USB host on corresponding endpoint @@ -664,9 +643,7 @@ static void udi_msc_csw_process(void) udi_msc_csw_send(); } - -void udi_msc_csw_send(void) -{ +void udi_msc_csw_send(void) { // Sends CSW on IN endpoint if (!udd_ep_run(UDI_MSC_EP_IN, false, (uint8_t *) & udi_msc_csw, @@ -678,10 +655,8 @@ void udi_msc_csw_send(void) } } - static void udi_msc_csw_sent(udd_ep_status_t status, iram_size_t nb_sent, - udd_ep_id_t ep) -{ + udd_ep_id_t ep) { UNUSED(ep); UNUSED(status); UNUSED(nb_sent); @@ -690,20 +665,17 @@ static void udi_msc_csw_sent(udd_ep_status_t status, iram_size_t nb_sent, udi_msc_cbw_wait(); } - // ------------------------ //------- Routines manage sense data -static void udi_msc_clear_sense(void) -{ +static void udi_msc_clear_sense(void) { memset((uint8_t*)&udi_msc_sense, 0, sizeof(struct scsi_request_sense_data)); udi_msc_sense.valid_reponse_code = SCSI_SENSE_VALID | SCSI_SENSE_CURRENT; udi_msc_sense.AddSenseLen = SCSI_SENSE_ADDL_LEN(sizeof(udi_msc_sense)); } static void udi_msc_sense_fail(uint8_t sense_key, uint16_t add_sense, - uint32_t lba) -{ + uint32_t lba) { udi_msc_clear_sense(); udi_msc_csw.bCSWStatus = USB_CSW_STATUS_FAIL; udi_msc_sense.sense_flag_key = sense_key; @@ -715,53 +687,39 @@ static void udi_msc_sense_fail(uint8_t sense_key, uint16_t add_sense, udi_msc_sense.AddSnsCodeQlfr = add_sense; } -static void udi_msc_sense_pass(void) -{ +static void udi_msc_sense_pass(void) { udi_msc_clear_sense(); udi_msc_csw.bCSWStatus = USB_CSW_STATUS_PASS; } - -static void udi_msc_sense_fail_not_present(void) -{ +static void udi_msc_sense_fail_not_present(void) { udi_msc_sense_fail(SCSI_SK_NOT_READY, SCSI_ASC_MEDIUM_NOT_PRESENT, 0); } -static void udi_msc_sense_fail_busy_or_change(void) -{ - udi_msc_sense_fail(SCSI_SK_UNIT_ATTENTION, - SCSI_ASC_NOT_READY_TO_READY_CHANGE, 0); +static void udi_msc_sense_fail_busy_or_change(void) { + udi_msc_sense_fail(SCSI_SK_UNIT_ATTENTION, SCSI_ASC_NOT_READY_TO_READY_CHANGE, 0); } -static void udi_msc_sense_fail_hardware(void) -{ - udi_msc_sense_fail(SCSI_SK_HARDWARE_ERROR, - SCSI_ASC_NO_ADDITIONAL_SENSE_INFO, 0); +static void udi_msc_sense_fail_hardware(void) { + udi_msc_sense_fail(SCSI_SK_HARDWARE_ERROR, SCSI_ASC_NO_ADDITIONAL_SENSE_INFO, 0); } -static void udi_msc_sense_fail_protected(void) -{ +static void udi_msc_sense_fail_protected(void) { udi_msc_sense_fail(SCSI_SK_DATA_PROTECT, SCSI_ASC_WRITE_PROTECTED, 0); } -static void udi_msc_sense_fail_cdb_invalid(void) -{ - udi_msc_sense_fail(SCSI_SK_ILLEGAL_REQUEST, - SCSI_ASC_INVALID_FIELD_IN_CDB, 0); +static void udi_msc_sense_fail_cdb_invalid(void) { + udi_msc_sense_fail(SCSI_SK_ILLEGAL_REQUEST, SCSI_ASC_INVALID_FIELD_IN_CDB, 0); } -static void udi_msc_sense_command_invalid(void) -{ - udi_msc_sense_fail(SCSI_SK_ILLEGAL_REQUEST, - SCSI_ASC_INVALID_COMMAND_OPERATION_CODE, 0); +static void udi_msc_sense_command_invalid(void) { + udi_msc_sense_fail(SCSI_SK_ILLEGAL_REQUEST, SCSI_ASC_INVALID_COMMAND_OPERATION_CODE, 0); } - // ------------------------ //------- Routines manage SCSI Commands -static void udi_msc_spc_requestsense(void) -{ +static void udi_msc_spc_requestsense(void) { uint8_t length = udi_msc_cbw.CDB[4]; // Can't send more than sense data length @@ -774,9 +732,7 @@ static void udi_msc_spc_requestsense(void) udi_msc_data_send((uint8_t*)&udi_msc_sense, length); } - -static void udi_msc_spc_inquiry(void) -{ +static void udi_msc_spc_inquiry(void) { uint8_t length, i; UDC_DATA(4) // Constant inquiry data for all LUNs @@ -835,9 +791,7 @@ static void udi_msc_spc_inquiry(void) udi_msc_data_send((uint8_t *) & udi_msc_inquiry_data, length); } - -static bool udi_msc_spc_testunitready_global(void) -{ +static bool udi_msc_spc_testunitready_global(void) { switch (mem_test_unit_ready(udi_msc_cbw.bCBWLUN)) { case CTRL_GOOD: return true; // Don't change sense data @@ -855,9 +809,7 @@ static bool udi_msc_spc_testunitready_global(void) return false; } - -static void udi_msc_spc_testunitready(void) -{ +static void udi_msc_spc_testunitready(void) { if (udi_msc_spc_testunitready_global()) { // LUN ready, then update sense data with status pass udi_msc_sense_pass(); @@ -866,9 +818,7 @@ static void udi_msc_spc_testunitready(void) udi_msc_csw_process(); } - -static void udi_msc_spc_mode_sense(bool b_sense10) -{ +static void udi_msc_spc_mode_sense(bool b_sense10) { // Union of all mode sense structures union sense_6_10 { struct { @@ -943,9 +893,7 @@ static void udi_msc_spc_mode_sense(bool b_sense10) udi_msc_data_send((uint8_t *) & sense, request_lgt); } - -static void udi_msc_spc_prevent_allow_medium_removal(void) -{ +static void udi_msc_spc_prevent_allow_medium_removal(void) { uint8_t prevent = udi_msc_cbw.CDB[4]; if (0 == prevent) { udi_msc_sense_pass(); @@ -955,9 +903,7 @@ static void udi_msc_spc_prevent_allow_medium_removal(void) udi_msc_csw_process(); } - -static void udi_msc_sbc_start_stop(void) -{ +static void udi_msc_sbc_start_stop(void) { bool start = 0x1 & udi_msc_cbw.CDB[4]; bool loej = 0x2 & udi_msc_cbw.CDB[4]; if (loej) { @@ -967,9 +913,7 @@ static void udi_msc_sbc_start_stop(void) udi_msc_csw_process(); } - -static void udi_msc_sbc_read_capacity(void) -{ +static void udi_msc_sbc_read_capacity(void) { UDC_BSS(4) static struct sbc_read_capacity10_data udi_msc_capacity; if (!udi_msc_cbw_validate(sizeof(udi_msc_capacity), @@ -1003,9 +947,7 @@ static void udi_msc_sbc_read_capacity(void) sizeof(udi_msc_capacity)); } - -static void udi_msc_sbc_trans(bool b_read) -{ +static void udi_msc_sbc_trans(bool b_read) { uint32_t trans_size; if (!b_read) { @@ -1038,9 +980,7 @@ static void udi_msc_sbc_trans(bool b_read) UDI_MSC_NOTIFY_TRANS_EXT(); } - -bool udi_msc_process_trans(void) -{ +bool udi_msc_process_trans(void) { Ctrl_status status; if (!udi_msc_b_trans_req) @@ -1084,10 +1024,8 @@ bool udi_msc_process_trans(void) return true; } - static void udi_msc_trans_ack(udd_ep_status_t status, iram_size_t n, - udd_ep_id_t ep) -{ + udd_ep_id_t ep) { UNUSED(ep); UNUSED(n); // Update variable to signal the end of transfer @@ -1095,10 +1033,8 @@ static void udi_msc_trans_ack(udd_ep_status_t status, iram_size_t n, udi_msc_b_ack_trans = true; } - bool udi_msc_trans_block(bool b_read, uint8_t * block, iram_size_t block_size, - void (*callback) (udd_ep_status_t status, iram_size_t n, udd_ep_id_t ep)) -{ + void (*callback) (udd_ep_status_t status, iram_size_t n, udd_ep_id_t ep)) { if (!udi_msc_b_ack_trans) return false; // No possible, transfer on going diff --git a/Marlin/src/HAL/DUE/usb/udi_msc.h b/Marlin/src/HAL/DUE/usb/udi_msc.h index 730dbc8eec56..0ede4d6a8346 100644 --- a/Marlin/src/HAL/DUE/usb/udi_msc.h +++ b/Marlin/src/HAL/DUE/usb/udi_msc.h @@ -77,9 +77,9 @@ extern UDC_DESC_STORAGE udi_api_t udi_api_msc; //! Interface descriptor structure for MSC typedef struct { - usb_iface_desc_t iface; - usb_ep_desc_t ep_in; - usb_ep_desc_t ep_out; + usb_iface_desc_t iface; + usb_ep_desc_t ep_in; + usb_ep_desc_t ep_out; } udi_msc_desc_t; //! By default no string associated to this interface @@ -94,32 +94,32 @@ typedef struct { //! Content of MSC interface descriptor for all speeds #define UDI_MSC_DESC \ - .iface.bLength = sizeof(usb_iface_desc_t),\ - .iface.bDescriptorType = USB_DT_INTERFACE,\ - .iface.bInterfaceNumber = UDI_MSC_IFACE_NUMBER,\ - .iface.bAlternateSetting = 0,\ - .iface.bNumEndpoints = 2,\ - .iface.bInterfaceClass = MSC_CLASS,\ - .iface.bInterfaceSubClass = MSC_SUBCLASS_TRANSPARENT,\ - .iface.bInterfaceProtocol = MSC_PROTOCOL_BULK,\ - .iface.iInterface = UDI_MSC_STRING_ID,\ - .ep_in.bLength = sizeof(usb_ep_desc_t),\ - .ep_in.bDescriptorType = USB_DT_ENDPOINT,\ - .ep_in.bEndpointAddress = UDI_MSC_EP_IN,\ - .ep_in.bmAttributes = USB_EP_TYPE_BULK,\ - .ep_in.bInterval = 0,\ - .ep_out.bLength = sizeof(usb_ep_desc_t),\ - .ep_out.bDescriptorType = USB_DT_ENDPOINT,\ - .ep_out.bEndpointAddress = UDI_MSC_EP_OUT,\ - .ep_out.bmAttributes = USB_EP_TYPE_BULK,\ - .ep_out.bInterval = 0, + .iface.bLength = sizeof(usb_iface_desc_t),\ + .iface.bDescriptorType = USB_DT_INTERFACE,\ + .iface.bInterfaceNumber = UDI_MSC_IFACE_NUMBER,\ + .iface.bAlternateSetting = 0,\ + .iface.bNumEndpoints = 2,\ + .iface.bInterfaceClass = MSC_CLASS,\ + .iface.bInterfaceSubClass = MSC_SUBCLASS_TRANSPARENT,\ + .iface.bInterfaceProtocol = MSC_PROTOCOL_BULK,\ + .iface.iInterface = UDI_MSC_STRING_ID,\ + .ep_in.bLength = sizeof(usb_ep_desc_t),\ + .ep_in.bDescriptorType = USB_DT_ENDPOINT,\ + .ep_in.bEndpointAddress = UDI_MSC_EP_IN,\ + .ep_in.bmAttributes = USB_EP_TYPE_BULK,\ + .ep_in.bInterval = 0,\ + .ep_out.bLength = sizeof(usb_ep_desc_t),\ + .ep_out.bDescriptorType = USB_DT_ENDPOINT,\ + .ep_out.bEndpointAddress = UDI_MSC_EP_OUT,\ + .ep_out.bmAttributes = USB_EP_TYPE_BULK,\ + .ep_out.bInterval = 0, //! Content of MSC interface descriptor for full speed only #define UDI_MSC_DESC_FS {\ - UDI_MSC_DESC \ - .ep_in.wMaxPacketSize = LE16(UDI_MSC_EPS_SIZE_FS),\ - .ep_out.wMaxPacketSize = LE16(UDI_MSC_EPS_SIZE_FS),\ - } + UDI_MSC_DESC \ + .ep_in.wMaxPacketSize = LE16(UDI_MSC_EPS_SIZE_FS),\ + .ep_out.wMaxPacketSize = LE16(UDI_MSC_EPS_SIZE_FS),\ + } //! Content of MSC interface descriptor for high speed only #define UDI_MSC_DESC_HS {\ @@ -129,7 +129,6 @@ typedef struct { } //@} - /** * \ingroup udi_group * \defgroup udi_msc_group USB Device Interface (UDI) for Mass Storage Class (MSC) @@ -163,14 +162,13 @@ bool udi_msc_process_trans(void); * \return \c 1 if function was successfully done, otherwise \c 0. */ bool udi_msc_trans_block(bool b_read, uint8_t * block, iram_size_t block_size, - void (*callback) (udd_ep_status_t status, iram_size_t n, udd_ep_id_t ep)); + void (*callback) (udd_ep_status_t status, iram_size_t n, udd_ep_id_t ep)); //@} #ifdef __cplusplus } #endif - /** * \page udi_msc_quickstart Quick start guide for USB device Mass Storage module (UDI MSC) * @@ -200,35 +198,32 @@ bool udi_msc_trans_block(bool b_read, uint8_t * block, iram_size_t block_size, * \subsection udi_msc_basic_use_case_usage_code Example code * Content of conf_usb.h: * \code - #define USB_DEVICE_SERIAL_NAME "12...EF" // Disk SN for MSC - #define UDI_MSC_GLOBAL_VENDOR_ID \ - 'A', 'T', 'M', 'E', 'L', ' ', ' ', ' ' - #define UDI_MSC_GLOBAL_PRODUCT_VERSION \ - '1', '.', '0', '0' - #define UDI_MSC_ENABLE_EXT() my_callback_msc_enable() - extern bool my_callback_msc_enable(void); - #define UDI_MSC_DISABLE_EXT() my_callback_msc_disable() - extern void my_callback_msc_disable(void); - #include "udi_msc_conf.h" // At the end of conf_usb.h file + #define USB_DEVICE_SERIAL_NAME "12...EF" // Disk SN for MSC + #define UDI_MSC_GLOBAL_VENDOR_ID \ + 'A', 'T', 'M', 'E', 'L', ' ', ' ', ' ' + #define UDI_MSC_GLOBAL_PRODUCT_VERSION \ + '1', '.', '0', '0' + #define UDI_MSC_ENABLE_EXT() my_callback_msc_enable() + extern bool my_callback_msc_enable(void); + #define UDI_MSC_DISABLE_EXT() my_callback_msc_disable() + extern void my_callback_msc_disable(void); + #include "udi_msc_conf.h" // At the end of conf_usb.h file \endcode * * Add to application C-file: * \code - static bool my_flag_autorize_msc_transfert = false; - bool my_callback_msc_enable(void) - { - my_flag_autorize_msc_transfert = true; - return true; - } - void my_callback_msc_disable(void) - { - my_flag_autorize_msc_transfert = false; - } + static bool my_flag_autorize_msc_transfert = false; + bool my_callback_msc_enable(void) { + my_flag_autorize_msc_transfert = true; + return true; + } + void my_callback_msc_disable(void) { + my_flag_autorize_msc_transfert = false; + } - void task(void) - { - udi_msc_process_trans(); - } + void task(void) { + udi_msc_process_trans(); + } \endcode * * \subsection udi_msc_basic_use_case_setup_flow Workflow @@ -237,14 +232,14 @@ bool udi_msc_trans_block(bool b_read, uint8_t * block, iram_size_t block_size, * - \code #define USB_DEVICE_SERIAL_NAME "12...EF" // Disk SN for MSC \endcode * \note The USB serial number is mandatory when a MSC interface is used. * - \code //! Vendor name and Product version of MSC interface - #define UDI_MSC_GLOBAL_VENDOR_ID \ - 'A', 'T', 'M', 'E', 'L', ' ', ' ', ' ' - #define UDI_MSC_GLOBAL_PRODUCT_VERSION \ - '1', '.', '0', '0' \endcode + #define UDI_MSC_GLOBAL_VENDOR_ID \ + 'A', 'T', 'M', 'E', 'L', ' ', ' ', ' ' + #define UDI_MSC_GLOBAL_PRODUCT_VERSION \ + '1', '.', '0', '0' \endcode * \note The USB MSC interface requires a vendor ID (8 ASCII characters) * and a product version (4 ASCII characters). * - \code #define UDI_MSC_ENABLE_EXT() my_callback_msc_enable() - extern bool my_callback_msc_enable(void); \endcode + extern bool my_callback_msc_enable(void); \endcode * \note After the device enumeration (detecting and identifying USB devices), * the USB host starts the device configuration. When the USB MSC interface * from the device is accepted by the host, the USB host enables this interface and the @@ -252,7 +247,7 @@ bool udi_msc_trans_block(bool b_read, uint8_t * block, iram_size_t block_size, * Thus, when this event is received, the tasks which call * udi_msc_process_trans() must be enabled. * - \code #define UDI_MSC_DISABLE_EXT() my_callback_msc_disable() - extern void my_callback_msc_disable(void); \endcode + extern void my_callback_msc_disable(void); \endcode * \note When the USB device is unplugged or is reset by the USB host, the USB * interface is disabled and the UDI_MSC_DISABLE_EXT() callback function * is called. Thus, it is recommended to disable the task which is called udi_msc_process_trans(). @@ -261,15 +256,15 @@ bool udi_msc_trans_block(bool b_read, uint8_t * block, iram_size_t block_size, * must be done outside USB interrupt routine. This is done in the MSC process * ("udi_msc_process_trans()") called by main loop: * - \code * void task(void) { - udi_msc_process_trans(); - } \endcode + udi_msc_process_trans(); + } \endcode * -# The MSC speed depends on task periodicity. To get the best speed * the notification callback "UDI_MSC_NOTIFY_TRANS_EXT" can be used to wakeup * this task (Example, through a mutex): * - \code #define UDI_MSC_NOTIFY_TRANS_EXT() msc_notify_trans() - void msc_notify_trans(void) { - wakeup_my_task(); - } \endcode + void msc_notify_trans(void) { + wakeup_my_task(); + } \endcode * * \section udi_msc_use_cases Advanced use cases * For more advanced use of the UDI MSC module, see the following use cases: @@ -302,72 +297,72 @@ bool udi_msc_trans_block(bool b_read, uint8_t * block, iram_size_t block_size, * \subsection udi_msc_use_case_composite_usage_code Example code * Content of conf_usb.h: * \code - #define USB_DEVICE_EP_CTRL_SIZE 64 - #define USB_DEVICE_NB_INTERFACE (X+1) - #define USB_DEVICE_MAX_EP (X+2) + #define USB_DEVICE_EP_CTRL_SIZE 64 + #define USB_DEVICE_NB_INTERFACE (X+1) + #define USB_DEVICE_MAX_EP (X+2) - #define UDI_MSC_EP_IN (X | USB_EP_DIR_IN) - #define UDI_MSC_EP_OUT (Y | USB_EP_DIR_OUT) - #define UDI_MSC_IFACE_NUMBER X + #define UDI_MSC_EP_IN (X | USB_EP_DIR_IN) + #define UDI_MSC_EP_OUT (Y | USB_EP_DIR_OUT) + #define UDI_MSC_IFACE_NUMBER X - #define UDI_COMPOSITE_DESC_T \ - udi_msc_desc_t udi_msc; \ - ... - #define UDI_COMPOSITE_DESC_FS \ - .udi_msc = UDI_MSC_DESC, \ - ... - #define UDI_COMPOSITE_DESC_HS \ - .udi_msc = UDI_MSC_DESC, \ - ... - #define UDI_COMPOSITE_API \ - &udi_api_msc, \ - ... + #define UDI_COMPOSITE_DESC_T \ + udi_msc_desc_t udi_msc; \ + ... + #define UDI_COMPOSITE_DESC_FS \ + .udi_msc = UDI_MSC_DESC, \ + ... + #define UDI_COMPOSITE_DESC_HS \ + .udi_msc = UDI_MSC_DESC, \ + ... + #define UDI_COMPOSITE_API \ + &udi_api_msc, \ + ... \endcode * * \subsection udi_msc_use_case_composite_usage_flow Workflow * -# Ensure that conf_usb.h is available and contains the following parameters * required for a USB composite device configuration: * - \code // Endpoint control size, This must be: - // - 8, 16, 32 or 64 for full speed device (8 is recommended to save RAM) - // - 64 for a high speed device - #define USB_DEVICE_EP_CTRL_SIZE 64 - // Total Number of interfaces on this USB device. - // Add 1 for MSC. - #define USB_DEVICE_NB_INTERFACE (X+1) - // Total number of endpoints on this USB device. - // This must include each endpoint for each interface. - // Add 2 for MSC. - #define USB_DEVICE_MAX_EP (X+2) \endcode + // - 8, 16, 32 or 64 for full speed device (8 is recommended to save RAM) + // - 64 for a high speed device + #define USB_DEVICE_EP_CTRL_SIZE 64 + // Total Number of interfaces on this USB device. + // Add 1 for MSC. + #define USB_DEVICE_NB_INTERFACE (X+1) + // Total number of endpoints on this USB device. + // This must include each endpoint for each interface. + // Add 2 for MSC. + #define USB_DEVICE_MAX_EP (X+2) \endcode * -# Ensure that conf_usb.h contains the description of * composite device: * - \code // The endpoint numbers chosen by you for the MSC. - // The endpoint numbers starting from 1. - #define UDI_MSC_EP_IN (X | USB_EP_DIR_IN) - #define UDI_MSC_EP_OUT (Y | USB_EP_DIR_OUT) - // The interface index of an interface starting from 0 - #define UDI_MSC_IFACE_NUMBER X \endcode + // The endpoint numbers starting from 1. + #define UDI_MSC_EP_IN (X | USB_EP_DIR_IN) + #define UDI_MSC_EP_OUT (Y | USB_EP_DIR_OUT) + // The interface index of an interface starting from 0 + #define UDI_MSC_IFACE_NUMBER X \endcode * -# Ensure that conf_usb.h contains the following parameters * required for a USB composite device configuration: * - \code // USB Interfaces descriptor structure - #define UDI_COMPOSITE_DESC_T \ - ... - udi_msc_desc_t udi_msc; \ - ... - // USB Interfaces descriptor value for Full Speed - #define UDI_COMPOSITE_DESC_FS \ - ... - .udi_msc = UDI_MSC_DESC_FS, \ - ... - // USB Interfaces descriptor value for High Speed - #define UDI_COMPOSITE_DESC_HS \ - ... - .udi_msc = UDI_MSC_DESC_HS, \ - ... - // USB Interface APIs - #define UDI_COMPOSITE_API \ - ... - &udi_api_msc, \ - ... \endcode + #define UDI_COMPOSITE_DESC_T \ + ... + udi_msc_desc_t udi_msc; \ + ... + // USB Interfaces descriptor value for Full Speed + #define UDI_COMPOSITE_DESC_FS \ + ... + .udi_msc = UDI_MSC_DESC_FS, \ + ... + // USB Interfaces descriptor value for High Speed + #define UDI_COMPOSITE_DESC_HS \ + ... + .udi_msc = UDI_MSC_DESC_HS, \ + ... + // USB Interface APIs + #define UDI_COMPOSITE_API \ + ... + &udi_api_msc, \ + ... \endcode * - \note The descriptors order given in the four lists above must be the * same as the order defined by all interface indexes. The interface index * orders are defined through UDI_X_IFACE_NUMBER defines. diff --git a/Marlin/src/HAL/DUE/usb/uotghs_otg.h b/Marlin/src/HAL/DUE/usb/uotghs_otg.h index eca5e938bbe1..f0e55c896fac 100644 --- a/Marlin/src/HAL/DUE/usb/uotghs_otg.h +++ b/Marlin/src/HAL/DUE/usb/uotghs_otg.h @@ -127,13 +127,13 @@ void otg_dual_disable(void); //! These macros allows to enable/disable pad and UOTGHS hardware //! @{ //! Reset USB macro -#define otg_reset() \ - do { \ - UOTGHS->UOTGHS_CTRL = 0; \ - while( UOTGHS->UOTGHS_SR & 0x3FFF) {\ - UOTGHS->UOTGHS_SCR = 0xFFFFFFFF;\ - } \ - } while (0) +#define otg_reset() \ + do { \ + UOTGHS->UOTGHS_CTRL = 0; \ + while( UOTGHS->UOTGHS_SR & 0x3FFF) { \ + UOTGHS->UOTGHS_SCR = 0xFFFFFFFF; \ + } \ + } while (0) //! Enable USB macro #define otg_enable() (Set_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_USBE)) //! Disable USB macro @@ -157,15 +157,14 @@ void otg_dual_disable(void); //! Configure time-out of specified OTG timer #define otg_configure_timeout(timer, timeout) (Set_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_UNLOCK),\ - Wr_bitfield(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_TIMPAGE_Msk, timer),\ - Wr_bitfield(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_TIMVALUE_Msk, timeout),\ - Clr_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_UNLOCK)) + Wr_bitfield(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_TIMPAGE_Msk, timer),\ + Wr_bitfield(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_TIMVALUE_Msk, timeout),\ + Clr_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_UNLOCK)) //! Get configured time-out of specified OTG timer #define otg_get_timeout(timer) (Set_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_UNLOCK),\ - Wr_bitfield(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_TIMPAGE_Msk, timer),\ - Clr_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_UNLOCK),\ - Rd_bitfield(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_TIMVALUE_Msk)) - + Wr_bitfield(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_TIMPAGE_Msk, timer),\ + Clr_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_UNLOCK),\ + Rd_bitfield(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_TIMVALUE_Msk)) //! Get the dual-role device state of the internal USB finite state machine of the UOTGHS controller #define otg_get_fsm_drd_state() (Rd_bitfield(UOTGHS->UOTGHS_FSM, UOTGHS_FSM_DRDSTATE_Msk)) diff --git a/Marlin/src/HAL/DUE/usb/usb_protocol.h b/Marlin/src/HAL/DUE/usb/usb_protocol.h index ea51a8689649..4540247df826 100644 --- a/Marlin/src/HAL/DUE/usb/usb_protocol.h +++ b/Marlin/src/HAL/DUE/usb/usb_protocol.h @@ -108,17 +108,17 @@ * \brief Standard USB requests (bRequest) */ enum usb_reqid { - USB_REQ_GET_STATUS = 0, - USB_REQ_CLEAR_FEATURE = 1, - USB_REQ_SET_FEATURE = 3, - USB_REQ_SET_ADDRESS = 5, - USB_REQ_GET_DESCRIPTOR = 6, - USB_REQ_SET_DESCRIPTOR = 7, - USB_REQ_GET_CONFIGURATION = 8, - USB_REQ_SET_CONFIGURATION = 9, - USB_REQ_GET_INTERFACE = 10, - USB_REQ_SET_INTERFACE = 11, - USB_REQ_SYNCH_FRAME = 12, + USB_REQ_GET_STATUS = 0, + USB_REQ_CLEAR_FEATURE = 1, + USB_REQ_SET_FEATURE = 3, + USB_REQ_SET_ADDRESS = 5, + USB_REQ_GET_DESCRIPTOR = 6, + USB_REQ_SET_DESCRIPTOR = 7, + USB_REQ_GET_CONFIGURATION = 8, + USB_REQ_SET_CONFIGURATION = 9, + USB_REQ_GET_INTERFACE = 10, + USB_REQ_SET_INTERFACE = 11, + USB_REQ_SYNCH_FRAME = 12, }; /** @@ -126,9 +126,9 @@ enum usb_reqid { * */ enum usb_device_status { - USB_DEV_STATUS_BUS_POWERED = 0, - USB_DEV_STATUS_SELF_POWERED = 1, - USB_DEV_STATUS_REMOTEWAKEUP = 2 + USB_DEV_STATUS_BUS_POWERED = 0, + USB_DEV_STATUS_SELF_POWERED = 1, + USB_DEV_STATUS_REMOTEWAKEUP = 2 }; /** @@ -136,7 +136,7 @@ enum usb_device_status { * */ enum usb_interface_status { - USB_IFACE_STATUS_RESERVED = 0 + USB_IFACE_STATUS_RESERVED = 0 }; /** @@ -144,7 +144,7 @@ enum usb_interface_status { * */ enum usb_endpoint_status { - USB_EP_STATUS_HALTED = 1, + USB_EP_STATUS_HALTED = 1, }; /** @@ -153,11 +153,11 @@ enum usb_endpoint_status { * \note valid for SetFeature request. */ enum usb_device_feature { - USB_DEV_FEATURE_REMOTE_WAKEUP = 1, //!< Remote wakeup enabled - USB_DEV_FEATURE_TEST_MODE = 2, //!< USB test mode - USB_DEV_FEATURE_OTG_B_HNP_ENABLE = 3, - USB_DEV_FEATURE_OTG_A_HNP_SUPPORT = 4, - USB_DEV_FEATURE_OTG_A_ALT_HNP_SUPPORT = 5 + USB_DEV_FEATURE_REMOTE_WAKEUP = 1, //!< Remote wakeup enabled + USB_DEV_FEATURE_TEST_MODE = 2, //!< USB test mode + USB_DEV_FEATURE_OTG_B_HNP_ENABLE = 3, + USB_DEV_FEATURE_OTG_A_HNP_SUPPORT = 4, + USB_DEV_FEATURE_OTG_A_ALT_HNP_SUPPORT = 5 }; /** @@ -166,54 +166,54 @@ enum usb_device_feature { * \note valid for USB_DEV_FEATURE_TEST_MODE request. */ enum usb_device_hs_test_mode { - USB_DEV_TEST_MODE_J = 1, - USB_DEV_TEST_MODE_K = 2, - USB_DEV_TEST_MODE_SE0_NAK = 3, - USB_DEV_TEST_MODE_PACKET = 4, - USB_DEV_TEST_MODE_FORCE_ENABLE = 5, + USB_DEV_TEST_MODE_J = 1, + USB_DEV_TEST_MODE_K = 2, + USB_DEV_TEST_MODE_SE0_NAK = 3, + USB_DEV_TEST_MODE_PACKET = 4, + USB_DEV_TEST_MODE_FORCE_ENABLE = 5, }; /** * \brief Standard USB endpoint feature/status flags */ enum usb_endpoint_feature { - USB_EP_FEATURE_HALT = 0, + USB_EP_FEATURE_HALT = 0, }; /** * \brief Standard USB Test Mode Selectors */ enum usb_test_mode_selector { - USB_TEST_J = 0x01, - USB_TEST_K = 0x02, - USB_TEST_SE0_NAK = 0x03, - USB_TEST_PACKET = 0x04, - USB_TEST_FORCE_ENABLE = 0x05, + USB_TEST_J = 0x01, + USB_TEST_K = 0x02, + USB_TEST_SE0_NAK = 0x03, + USB_TEST_PACKET = 0x04, + USB_TEST_FORCE_ENABLE = 0x05, }; /** * \brief Standard USB descriptor types */ enum usb_descriptor_type { - USB_DT_DEVICE = 1, - USB_DT_CONFIGURATION = 2, - USB_DT_STRING = 3, - USB_DT_INTERFACE = 4, - USB_DT_ENDPOINT = 5, - USB_DT_DEVICE_QUALIFIER = 6, - USB_DT_OTHER_SPEED_CONFIGURATION = 7, - USB_DT_INTERFACE_POWER = 8, - USB_DT_OTG = 9, - USB_DT_IAD = 0x0B, - USB_DT_BOS = 0x0F, - USB_DT_DEVICE_CAPABILITY = 0x10, + USB_DT_DEVICE = 1, + USB_DT_CONFIGURATION = 2, + USB_DT_STRING = 3, + USB_DT_INTERFACE = 4, + USB_DT_ENDPOINT = 5, + USB_DT_DEVICE_QUALIFIER = 6, + USB_DT_OTHER_SPEED_CONFIGURATION = 7, + USB_DT_INTERFACE_POWER = 8, + USB_DT_OTG = 9, + USB_DT_IAD = 0x0B, + USB_DT_BOS = 0x0F, + USB_DT_DEVICE_CAPABILITY = 0x10, }; /** * \brief USB Device Capability types */ enum usb_capability_type { - USB_DC_USB20_EXTENSION = 0x02, + USB_DC_USB20_EXTENSION = 0x02, }; /** @@ -221,7 +221,7 @@ enum usb_capability_type { * To fill bmAttributes field of usb_capa_ext_desc_t structure. */ enum usb_capability_extension_attr { - USB_DC_EXT_LPM = 0x00000002, + USB_DC_EXT_LPM = 0x00000002, }; #define HIRD_50_US 0 @@ -254,18 +254,18 @@ enum usb_capability_extension_attr { * \brief Standard USB endpoint transfer types */ enum usb_ep_type { - USB_EP_TYPE_CONTROL = 0x00, - USB_EP_TYPE_ISOCHRONOUS = 0x01, - USB_EP_TYPE_BULK = 0x02, - USB_EP_TYPE_INTERRUPT = 0x03, - USB_EP_TYPE_MASK = 0x03, + USB_EP_TYPE_CONTROL = 0x00, + USB_EP_TYPE_ISOCHRONOUS = 0x01, + USB_EP_TYPE_BULK = 0x02, + USB_EP_TYPE_INTERRUPT = 0x03, + USB_EP_TYPE_MASK = 0x03, }; /** * \brief Standard USB language IDs for string descriptors */ enum usb_langid { - USB_LANGID_EN_US = 0x0409, //!< English (United States) + USB_LANGID_EN_US = 0x0409, //!< English (United States) }; /** @@ -308,31 +308,31 @@ COMPILER_PACK_SET(1) * The data payload of SETUP packets always follows this structure. */ typedef struct { - uint8_t bmRequestType; - uint8_t bRequest; - le16_t wValue; - le16_t wIndex; - le16_t wLength; + uint8_t bmRequestType; + uint8_t bRequest; + le16_t wValue; + le16_t wIndex; + le16_t wLength; } usb_setup_req_t; /** * \brief Standard USB device descriptor structure */ typedef struct { - uint8_t bLength; - uint8_t bDescriptorType; - le16_t bcdUSB; - uint8_t bDeviceClass; - uint8_t bDeviceSubClass; - uint8_t bDeviceProtocol; - uint8_t bMaxPacketSize0; - le16_t idVendor; - le16_t idProduct; - le16_t bcdDevice; - uint8_t iManufacturer; - uint8_t iProduct; - uint8_t iSerialNumber; - uint8_t bNumConfigurations; + uint8_t bLength; + uint8_t bDescriptorType; + le16_t bcdUSB; + uint8_t bDeviceClass; + uint8_t bDeviceSubClass; + uint8_t bDeviceProtocol; + uint8_t bMaxPacketSize0; + le16_t idVendor; + le16_t idProduct; + le16_t bcdDevice; + uint8_t iManufacturer; + uint8_t iProduct; + uint8_t iSerialNumber; + uint8_t bNumConfigurations; } usb_dev_desc_t; /** @@ -344,15 +344,15 @@ typedef struct { * the device was operating at full speed.) */ typedef struct { - uint8_t bLength; - uint8_t bDescriptorType; - le16_t bcdUSB; - uint8_t bDeviceClass; - uint8_t bDeviceSubClass; - uint8_t bDeviceProtocol; - uint8_t bMaxPacketSize0; - uint8_t bNumConfigurations; - uint8_t bReserved; + uint8_t bLength; + uint8_t bDescriptorType; + le16_t bcdUSB; + uint8_t bDeviceClass; + uint8_t bDeviceSubClass; + uint8_t bDeviceProtocol; + uint8_t bMaxPacketSize0; + uint8_t bNumConfigurations; + uint8_t bReserved; } usb_dev_qual_desc_t; /** @@ -368,10 +368,10 @@ typedef struct { * The descriptor type in the GetDescriptor() request is set to BOS. */ typedef struct { - uint8_t bLength; - uint8_t bDescriptorType; - le16_t wTotalLength; - uint8_t bNumDeviceCaps; + uint8_t bLength; + uint8_t bDescriptorType; + le16_t wTotalLength; + uint8_t bNumDeviceCaps; } usb_dev_bos_desc_t; @@ -381,10 +381,10 @@ typedef struct { * Defines the set of USB 1.1-specific device level capabilities. */ typedef struct { - uint8_t bLength; - uint8_t bDescriptorType; - uint8_t bDevCapabilityType; - le32_t bmAttributes; + uint8_t bLength; + uint8_t bDescriptorType; + uint8_t bDevCapabilityType; + le32_t bmAttributes; } usb_dev_capa_ext_desc_t; /** @@ -393,22 +393,22 @@ typedef struct { * The BOS descriptor and capabilities descriptors for LPM. */ typedef struct { - usb_dev_bos_desc_t bos; - usb_dev_capa_ext_desc_t capa_ext; + usb_dev_bos_desc_t bos; + usb_dev_capa_ext_desc_t capa_ext; } usb_dev_lpm_desc_t; /** * \brief Standard USB Interface Association Descriptor structure */ typedef struct { - uint8_t bLength; //!< size of this descriptor in bytes - uint8_t bDescriptorType; //!< INTERFACE descriptor type - uint8_t bFirstInterface; //!< Number of interface - uint8_t bInterfaceCount; //!< value to select alternate setting - uint8_t bFunctionClass; //!< Class code assigned by the USB - uint8_t bFunctionSubClass;//!< Sub-class code assigned by the USB - uint8_t bFunctionProtocol;//!< Protocol code assigned by the USB - uint8_t iFunction; //!< Index of string descriptor + uint8_t bLength; //!< size of this descriptor in bytes + uint8_t bDescriptorType; //!< INTERFACE descriptor type + uint8_t bFirstInterface; //!< Number of interface + uint8_t bInterfaceCount; //!< value to select alternate setting + uint8_t bFunctionClass; //!< Class code assigned by the USB + uint8_t bFunctionSubClass;//!< Sub-class code assigned by the USB + uint8_t bFunctionProtocol;//!< Protocol code assigned by the USB + uint8_t iFunction; //!< Index of string descriptor } usb_association_desc_t; @@ -416,14 +416,14 @@ typedef struct { * \brief Standard USB configuration descriptor structure */ typedef struct { - uint8_t bLength; - uint8_t bDescriptorType; - le16_t wTotalLength; - uint8_t bNumInterfaces; - uint8_t bConfigurationValue; - uint8_t iConfiguration; - uint8_t bmAttributes; - uint8_t bMaxPower; + uint8_t bLength; + uint8_t bDescriptorType; + le16_t wTotalLength; + uint8_t bNumInterfaces; + uint8_t bConfigurationValue; + uint8_t iConfiguration; + uint8_t bmAttributes; + uint8_t bMaxPower; } usb_conf_desc_t; @@ -438,41 +438,41 @@ typedef struct { * \brief Standard USB association descriptor structure */ typedef struct { - uint8_t bLength; //!< Size of this descriptor in bytes - uint8_t bDescriptorType; //!< Interface descriptor type - uint8_t bFirstInterface; //!< Number of interface - uint8_t bInterfaceCount; //!< value to select alternate setting - uint8_t bFunctionClass; //!< Class code assigned by the USB - uint8_t bFunctionSubClass; //!< Sub-class code assigned by the USB - uint8_t bFunctionProtocol; //!< Protocol code assigned by the USB - uint8_t iFunction; //!< Index of string descriptor + uint8_t bLength; //!< Size of this descriptor in bytes + uint8_t bDescriptorType; //!< Interface descriptor type + uint8_t bFirstInterface; //!< Number of interface + uint8_t bInterfaceCount; //!< value to select alternate setting + uint8_t bFunctionClass; //!< Class code assigned by the USB + uint8_t bFunctionSubClass; //!< Sub-class code assigned by the USB + uint8_t bFunctionProtocol; //!< Protocol code assigned by the USB + uint8_t iFunction; //!< Index of string descriptor } usb_iad_desc_t; /** * \brief Standard USB interface descriptor structure */ typedef struct { - uint8_t bLength; - uint8_t bDescriptorType; - uint8_t bInterfaceNumber; - uint8_t bAlternateSetting; - uint8_t bNumEndpoints; - uint8_t bInterfaceClass; - uint8_t bInterfaceSubClass; - uint8_t bInterfaceProtocol; - uint8_t iInterface; + uint8_t bLength; + uint8_t bDescriptorType; + uint8_t bInterfaceNumber; + uint8_t bAlternateSetting; + uint8_t bNumEndpoints; + uint8_t bInterfaceClass; + uint8_t bInterfaceSubClass; + uint8_t bInterfaceProtocol; + uint8_t iInterface; } usb_iface_desc_t; /** * \brief Standard USB endpoint descriptor structure */ typedef struct { - uint8_t bLength; - uint8_t bDescriptorType; - uint8_t bEndpointAddress; - uint8_t bmAttributes; - le16_t wMaxPacketSize; - uint8_t bInterval; + uint8_t bLength; + uint8_t bDescriptorType; + uint8_t bEndpointAddress; + uint8_t bmAttributes; + le16_t wMaxPacketSize; + uint8_t bInterval; } usb_ep_desc_t; @@ -480,13 +480,13 @@ typedef struct { * \brief A standard USB string descriptor structure */ typedef struct { - uint8_t bLength; - uint8_t bDescriptorType; + uint8_t bLength; + uint8_t bDescriptorType; } usb_str_desc_t; typedef struct { - usb_str_desc_t desc; - le16_t string[1]; + usb_str_desc_t desc; + le16_t string[1]; } usb_str_lgid_desc_t; COMPILER_PACK_RESET() diff --git a/Marlin/src/HAL/DUE/usb/usb_protocol_cdc.h b/Marlin/src/HAL/DUE/usb/usb_protocol_cdc.h index d594db52e33b..9b82afc6242b 100644 --- a/Marlin/src/HAL/DUE/usb/usb_protocol_cdc.h +++ b/Marlin/src/HAL/DUE/usb/usb_protocol_cdc.h @@ -58,42 +58,42 @@ * \name Possible values of class */ //@{ -#define CDC_CLASS_DEVICE 0x02 //!< USB Communication Device Class -#define CDC_CLASS_COMM 0x02 //!< CDC Communication Class Interface -#define CDC_CLASS_DATA 0x0A //!< CDC Data Class Interface +#define CDC_CLASS_DEVICE 0x02 //!< USB Communication Device Class +#define CDC_CLASS_COMM 0x02 //!< CDC Communication Class Interface +#define CDC_CLASS_DATA 0x0A //!< CDC Data Class Interface #define CDC_CLASS_MULTI 0xEF //!< CDC Multi-interface Function //@} //! \name USB CDC Subclass IDs //@{ -#define CDC_SUBCLASS_DLCM 0x01 //!< Direct Line Control Model -#define CDC_SUBCLASS_ACM 0x02 //!< Abstract Control Model -#define CDC_SUBCLASS_TCM 0x03 //!< Telephone Control Model -#define CDC_SUBCLASS_MCCM 0x04 //!< Multi-Channel Control Model -#define CDC_SUBCLASS_CCM 0x05 //!< CAPI Control Model -#define CDC_SUBCLASS_ETH 0x06 //!< Ethernet Networking Control Model -#define CDC_SUBCLASS_ATM 0x07 //!< ATM Networking Control Model +#define CDC_SUBCLASS_DLCM 0x01 //!< Direct Line Control Model +#define CDC_SUBCLASS_ACM 0x02 //!< Abstract Control Model +#define CDC_SUBCLASS_TCM 0x03 //!< Telephone Control Model +#define CDC_SUBCLASS_MCCM 0x04 //!< Multi-Channel Control Model +#define CDC_SUBCLASS_CCM 0x05 //!< CAPI Control Model +#define CDC_SUBCLASS_ETH 0x06 //!< Ethernet Networking Control Model +#define CDC_SUBCLASS_ATM 0x07 //!< ATM Networking Control Model //@} //! \name USB CDC Communication Interface Protocol IDs //@{ -#define CDC_PROTOCOL_V25TER 0x01 //!< Common AT commands +#define CDC_PROTOCOL_V25TER 0x01 //!< Common AT commands //@} //! \name USB CDC Data Interface Protocol IDs //@{ -#define CDC_PROTOCOL_I430 0x30 //!< ISDN BRI -#define CDC_PROTOCOL_HDLC 0x31 //!< HDLC -#define CDC_PROTOCOL_TRANS 0x32 //!< Transparent -#define CDC_PROTOCOL_Q921M 0x50 //!< Q.921 management protocol -#define CDC_PROTOCOL_Q921 0x51 //!< Q.931 [sic] Data link protocol -#define CDC_PROTOCOL_Q921TM 0x52 //!< Q.921 TEI-multiplexor -#define CDC_PROTOCOL_V42BIS 0x90 //!< Data compression procedures -#define CDC_PROTOCOL_Q931 0x91 //!< Euro-ISDN protocol control -#define CDC_PROTOCOL_V120 0x92 //!< V.24 rate adaption to ISDN -#define CDC_PROTOCOL_CAPI20 0x93 //!< CAPI Commands -#define CDC_PROTOCOL_HOST 0xFD //!< Host based driver +#define CDC_PROTOCOL_I430 0x30 //!< ISDN BRI +#define CDC_PROTOCOL_HDLC 0x31 //!< HDLC +#define CDC_PROTOCOL_TRANS 0x32 //!< Transparent +#define CDC_PROTOCOL_Q921M 0x50 //!< Q.921 management protocol +#define CDC_PROTOCOL_Q921 0x51 //!< Q.931 [sic] Data link protocol +#define CDC_PROTOCOL_Q921TM 0x52 //!< Q.921 TEI-multiplexor +#define CDC_PROTOCOL_V42BIS 0x90 //!< Data compression procedures +#define CDC_PROTOCOL_Q931 0x91 //!< Euro-ISDN protocol control +#define CDC_PROTOCOL_V120 0x92 //!< V.24 rate adaption to ISDN +#define CDC_PROTOCOL_CAPI20 0x93 //!< CAPI Commands +#define CDC_PROTOCOL_HOST 0xFD //!< Host based driver /** * \brief Describes the Protocol Unit Functional Descriptors [sic] * on Communication Class Interface @@ -103,16 +103,16 @@ //! \name USB CDC Functional Descriptor Types //@{ -#define CDC_CS_INTERFACE 0x24 //!< Interface Functional Descriptor -#define CDC_CS_ENDPOINT 0x25 //!< Endpoint Functional Descriptor +#define CDC_CS_INTERFACE 0x24 //!< Interface Functional Descriptor +#define CDC_CS_ENDPOINT 0x25 //!< Endpoint Functional Descriptor //@} //! \name USB CDC Functional Descriptor Subtypes //@{ -#define CDC_SCS_HEADER 0x00 //!< Header Functional Descriptor -#define CDC_SCS_CALL_MGMT 0x01 //!< Call Management -#define CDC_SCS_ACM 0x02 //!< Abstract Control Management -#define CDC_SCS_UNION 0x06 //!< Union Functional Descriptor +#define CDC_SCS_HEADER 0x00 //!< Header Functional Descriptor +#define CDC_SCS_CALL_MGMT 0x01 //!< Call Management +#define CDC_SCS_ACM 0x02 //!< Abstract Control Management +#define CDC_SCS_UNION 0x06 //!< Union Functional Descriptor //@} //! \name USB CDC Request IDs @@ -171,36 +171,36 @@ COMPILER_PACK_SET(1) //! CDC Header Functional Descriptor typedef struct { - uint8_t bFunctionLength; - uint8_t bDescriptorType; - uint8_t bDescriptorSubtype; - le16_t bcdCDC; + uint8_t bFunctionLength; + uint8_t bDescriptorType; + uint8_t bDescriptorSubtype; + le16_t bcdCDC; } usb_cdc_hdr_desc_t; //! CDC Call Management Functional Descriptor typedef struct { - uint8_t bFunctionLength; - uint8_t bDescriptorType; - uint8_t bDescriptorSubtype; - uint8_t bmCapabilities; - uint8_t bDataInterface; + uint8_t bFunctionLength; + uint8_t bDescriptorType; + uint8_t bDescriptorSubtype; + uint8_t bmCapabilities; + uint8_t bDataInterface; } usb_cdc_call_mgmt_desc_t; //! CDC ACM Functional Descriptor typedef struct { - uint8_t bFunctionLength; - uint8_t bDescriptorType; - uint8_t bDescriptorSubtype; - uint8_t bmCapabilities; + uint8_t bFunctionLength; + uint8_t bDescriptorType; + uint8_t bDescriptorSubtype; + uint8_t bmCapabilities; } usb_cdc_acm_desc_t; //! CDC Union Functional Descriptor typedef struct { - uint8_t bFunctionLength; - uint8_t bDescriptorType; - uint8_t bDescriptorSubtype; - uint8_t bMasterInterface; - uint8_t bSlaveInterface0; + uint8_t bFunctionLength; + uint8_t bDescriptorType; + uint8_t bDescriptorSubtype; + uint8_t bMasterInterface; + uint8_t bSlaveInterface0; } usb_cdc_union_desc_t; @@ -235,24 +235,24 @@ typedef struct { //@{ //! Line Coding structure typedef struct { - le32_t dwDTERate; - uint8_t bCharFormat; - uint8_t bParityType; - uint8_t bDataBits; + le32_t dwDTERate; + uint8_t bCharFormat; + uint8_t bParityType; + uint8_t bDataBits; } usb_cdc_line_coding_t; //! Possible values of bCharFormat enum cdc_char_format { - CDC_STOP_BITS_1 = 0, //!< 1 stop bit - CDC_STOP_BITS_1_5 = 1, //!< 1.5 stop bits - CDC_STOP_BITS_2 = 2, //!< 2 stop bits + CDC_STOP_BITS_1 = 0, //!< 1 stop bit + CDC_STOP_BITS_1_5 = 1, //!< 1.5 stop bits + CDC_STOP_BITS_2 = 2, //!< 2 stop bits }; //! Possible values of bParityType enum cdc_parity { - CDC_PAR_NONE = 0, //!< No parity - CDC_PAR_ODD = 1, //!< Odd parity - CDC_PAR_EVEN = 2, //!< Even parity - CDC_PAR_MARK = 3, //!< Parity forced to 0 (space) - CDC_PAR_SPACE = 4, //!< Parity forced to 1 (mark) + CDC_PAR_NONE = 0, //!< No parity + CDC_PAR_ODD = 1, //!< Odd parity + CDC_PAR_EVEN = 2, //!< Even parity + CDC_PAR_MARK = 3, //!< Parity forced to 0 (space) + CDC_PAR_SPACE = 4, //!< Parity forced to 1 (mark) }; //@} @@ -262,7 +262,7 @@ enum cdc_parity { //! Control signal structure typedef struct { - uint16_t value; + uint16_t value; } usb_cdc_control_signal_t; //! \name Possible values in usb_cdc_control_signal_t @@ -283,11 +283,11 @@ typedef struct { //@{ typedef struct { - uint8_t bmRequestType; - uint8_t bNotification; - le16_t wValue; - le16_t wIndex; - le16_t wLength; + uint8_t bmRequestType; + uint8_t bNotification; + le16_t wValue; + le16_t wIndex; + le16_t wLength; } usb_cdc_notify_msg_t; //! \name USB CDC serial state @@ -295,8 +295,8 @@ typedef struct { //! Hardware handshake support (cdc spec 1.1 chapter 6.3.5) typedef struct { - usb_cdc_notify_msg_t header; - le16_t value; + usb_cdc_notify_msg_t header; + le16_t value; } usb_cdc_notify_serial_state_t; //! \name Possible values in usb_cdc_notify_serial_state_t diff --git a/Marlin/src/HAL/DUE/usb/usb_protocol_msc.h b/Marlin/src/HAL/DUE/usb/usb_protocol_msc.h index e1e59237d823..cc30a94e4fc8 100644 --- a/Marlin/src/HAL/DUE/usb/usb_protocol_msc.h +++ b/Marlin/src/HAL/DUE/usb/usb_protocol_msc.h @@ -59,7 +59,7 @@ * \name Possible Class value */ //@{ -#define MSC_CLASS 0x08 +#define MSC_CLASS 0x08 //@} /** @@ -71,12 +71,12 @@ * operating systems like Windows XP. */ //@{ -#define MSC_SUBCLASS_RBC 0x01 //!< Reduced Block Commands -#define MSC_SUBCLASS_ATAPI 0x02 //!< CD/DVD devices -#define MSC_SUBCLASS_QIC_157 0x03 //!< Tape devices -#define MSC_SUBCLASS_UFI 0x04 //!< Floppy disk drives -#define MSC_SUBCLASS_SFF_8070I 0x05 //!< Floppy disk drives -#define MSC_SUBCLASS_TRANSPARENT 0x06 //!< Determined by INQUIRY +#define MSC_SUBCLASS_RBC 0x01 //!< Reduced Block Commands +#define MSC_SUBCLASS_ATAPI 0x02 //!< CD/DVD devices +#define MSC_SUBCLASS_QIC_157 0x03 //!< Tape devices +#define MSC_SUBCLASS_UFI 0x04 //!< Floppy disk drives +#define MSC_SUBCLASS_SFF_8070I 0x05 //!< Floppy disk drives +#define MSC_SUBCLASS_TRANSPARENT 0x06 //!< Determined by INQUIRY //@} /** @@ -84,9 +84,9 @@ * \note Only the BULK protocol should be used in new designs. */ //@{ -#define MSC_PROTOCOL_CBI 0x00 //!< Command/Bulk/Interrupt -#define MSC_PROTOCOL_CBI_ALT 0x01 //!< W/o command completion -#define MSC_PROTOCOL_BULK 0x50 //!< Bulk-only +#define MSC_PROTOCOL_CBI 0x00 //!< Command/Bulk/Interrupt +#define MSC_PROTOCOL_CBI_ALT 0x01 //!< W/o command completion +#define MSC_PROTOCOL_BULK 0x50 //!< Bulk-only //@} @@ -94,8 +94,8 @@ * \brief MSC USB requests (bRequest) */ enum usb_reqid_msc { - USB_REQ_MSC_BULK_RESET = 0xFF, //!< Mass Storage Reset - USB_REQ_MSC_GET_MAX_LUN = 0xFE //!< Get Max LUN + USB_REQ_MSC_BULK_RESET = 0xFF, //!< Mass Storage Reset + USB_REQ_MSC_GET_MAX_LUN = 0xFE //!< Get Max LUN }; @@ -106,20 +106,20 @@ COMPILER_PACK_SET(1) */ //@{ struct usb_msc_cbw { - le32_t dCBWSignature; //!< Must contain 'USBC' - le32_t dCBWTag; //!< Unique command ID - le32_t dCBWDataTransferLength; //!< Number of bytes to transfer - uint8_t bmCBWFlags; //!< Direction in bit 7 - uint8_t bCBWLUN; //!< Logical Unit Number - uint8_t bCBWCBLength; //!< Number of valid CDB bytes - uint8_t CDB[16]; //!< SCSI Command Descriptor Block + le32_t dCBWSignature; //!< Must contain 'USBC' + le32_t dCBWTag; //!< Unique command ID + le32_t dCBWDataTransferLength; //!< Number of bytes to transfer + uint8_t bmCBWFlags; //!< Direction in bit 7 + uint8_t bCBWLUN; //!< Logical Unit Number + uint8_t bCBWCBLength; //!< Number of valid CDB bytes + uint8_t CDB[16]; //!< SCSI Command Descriptor Block }; -#define USB_CBW_SIGNATURE 0x55534243 //!< dCBWSignature value -#define USB_CBW_DIRECTION_IN (1<<7) //!< Data from device to host -#define USB_CBW_DIRECTION_OUT (0<<7) //!< Data from host to device -#define USB_CBW_LUN_MASK 0x0F //!< Valid bits in bCBWLUN -#define USB_CBW_LEN_MASK 0x1F //!< Valid bits in bCBWCBLength +#define USB_CBW_SIGNATURE 0x55534243 //!< dCBWSignature value +#define USB_CBW_DIRECTION_IN (1<<7) //!< Data from device to host +#define USB_CBW_DIRECTION_OUT (0<<7) //!< Data from host to device +#define USB_CBW_LUN_MASK 0x0F //!< Valid bits in bCBWLUN +#define USB_CBW_LEN_MASK 0x1F //!< Valid bits in bCBWCBLength //@} @@ -128,16 +128,16 @@ struct usb_msc_cbw { */ //@{ struct usb_msc_csw { - le32_t dCSWSignature; //!< Must contain 'USBS' - le32_t dCSWTag; //!< Same as dCBWTag - le32_t dCSWDataResidue; //!< Number of bytes not transferred - uint8_t bCSWStatus; //!< Status code + le32_t dCSWSignature; //!< Must contain 'USBS' + le32_t dCSWTag; //!< Same as dCBWTag + le32_t dCSWDataResidue; //!< Number of bytes not transferred + uint8_t bCSWStatus; //!< Status code }; -#define USB_CSW_SIGNATURE 0x55534253 //!< dCSWSignature value -#define USB_CSW_STATUS_PASS 0x00 //!< Command Passed -#define USB_CSW_STATUS_FAIL 0x01 //!< Command Failed -#define USB_CSW_STATUS_PE 0x02 //!< Phase Error +#define USB_CSW_SIGNATURE 0x55534253 //!< dCSWSignature value +#define USB_CSW_STATUS_PASS 0x00 //!< Command Passed +#define USB_CSW_STATUS_FAIL 0x01 //!< Command Failed +#define USB_CSW_STATUS_PE 0x02 //!< Phase Error //@} COMPILER_PACK_RESET() diff --git a/Marlin/src/HAL/ESP32/HAL.cpp b/Marlin/src/HAL/ESP32/HAL.cpp index 46dd4e761b8c..27f6516f9ae8 100644 --- a/Marlin/src/HAL/ESP32/HAL.cpp +++ b/Marlin/src/HAL/ESP32/HAL.cpp @@ -165,7 +165,7 @@ void MarlinHAL::init_board() { } void MarlinHAL::idletask() { - #if BOTH(WIFISUPPORT, OTASUPPORT) + #if ALL(WIFISUPPORT, OTASUPPORT) OTA_handle(); #endif TERN_(ESP3D_WIFISUPPORT, esp3dlib.idletask()); diff --git a/Marlin/src/HAL/ESP32/i2s.cpp b/Marlin/src/HAL/ESP32/i2s.cpp index 63ceed4c9dcd..69f8ca98458a 100644 --- a/Marlin/src/HAL/ESP32/i2s.cpp +++ b/Marlin/src/HAL/ESP32/i2s.cpp @@ -356,7 +356,7 @@ void i2s_push_sample() { // Every 4Β΅s (when space in DMA buffer) toggle each expander PWM output using // the current duty cycle/frequency so they sync with any steps (once // through the DMA/FIFO buffers). PWM signal inversion handled by other functions - LOOP_L_N(p, MAX_EXPANDER_BITS) { + for (uint8_t p = 0; p < MAX_EXPANDER_BITS; ++p) { if (hal.pwm_pin_data[p].pwm_duty_ticks > 0) { // pin has active pwm? if (hal.pwm_pin_data[p].pwm_tick_count == 0) { if (TEST32(i2s_port_data, p)) { // hi->lo diff --git a/Marlin/src/HAL/ESP32/inc/SanityCheck.h b/Marlin/src/HAL/ESP32/inc/SanityCheck.h index 910918b9ea47..e6c364a6fe4c 100644 --- a/Marlin/src/HAL/ESP32/inc/SanityCheck.h +++ b/Marlin/src/HAL/ESP32/inc/SanityCheck.h @@ -40,7 +40,7 @@ #error "TMC220x Software Serial is not supported on ESP32." #endif -#if BOTH(WIFISUPPORT, ESP3D_WIFISUPPORT) +#if ALL(WIFISUPPORT, ESP3D_WIFISUPPORT) #error "Only enable one WiFi option, either WIFISUPPORT or ESP3D_WIFISUPPORT." #endif @@ -52,7 +52,7 @@ #error "FAST_PWM_FAN is not available on TinyBee." #endif -#if BOTH(I2S_STEPPER_STREAM, BABYSTEPPING) && DISABLED(INTEGRATED_BABYSTEPPING) +#if ALL(I2S_STEPPER_STREAM, BABYSTEPPING) && DISABLED(INTEGRATED_BABYSTEPPING) #error "BABYSTEPPING on I2S stream requires INTEGRATED_BABYSTEPPING." #endif @@ -60,10 +60,10 @@ #error "PULLDOWN pin mode is not available on ESP32 boards." #endif -#if BOTH(I2S_STEPPER_STREAM, LIN_ADVANCE) && DISABLED(EXPERIMENTAL_I2S_LA) +#if ALL(I2S_STEPPER_STREAM, LIN_ADVANCE) && DISABLED(EXPERIMENTAL_I2S_LA) #error "I2S stream is currently incompatible with LIN_ADVANCE." #endif -#if BOTH(I2S_STEPPER_STREAM, PRINTCOUNTER) && PRINTCOUNTER_SAVE_INTERVAL > 0 && DISABLED(PRINTCOUNTER_SYNC) +#if ALL(I2S_STEPPER_STREAM, PRINTCOUNTER) && PRINTCOUNTER_SAVE_INTERVAL > 0 && DISABLED(PRINTCOUNTER_SYNC) #error "PRINTCOUNTER_SAVE_INTERVAL may cause issues on ESP32 with an I2S expander. Define PRINTCOUNTER_SYNC in Configuration.h for an imperfect solution." #endif diff --git a/Marlin/src/HAL/ESP32/ota.cpp b/Marlin/src/HAL/ESP32/ota.cpp index f31a78c2c519..c5c3082c30cb 100644 --- a/Marlin/src/HAL/ESP32/ota.cpp +++ b/Marlin/src/HAL/ESP32/ota.cpp @@ -22,7 +22,7 @@ #include "../../inc/MarlinConfigPre.h" -#if BOTH(WIFISUPPORT, OTASUPPORT) +#if ALL(WIFISUPPORT, OTASUPPORT) #include #include diff --git a/Marlin/src/HAL/ESP32/spiffs.cpp b/Marlin/src/HAL/ESP32/spiffs.cpp index a0e713bff0bb..043ad7849adb 100644 --- a/Marlin/src/HAL/ESP32/spiffs.cpp +++ b/Marlin/src/HAL/ESP32/spiffs.cpp @@ -23,7 +23,7 @@ #include "../../inc/MarlinConfigPre.h" -#if BOTH(WIFISUPPORT, WEBSUPPORT) +#if ALL(WIFISUPPORT, WEBSUPPORT) #include "../../core/serial.h" diff --git a/Marlin/src/HAL/ESP32/u8g_esp32_spi.cpp b/Marlin/src/HAL/ESP32/u8g_esp32_spi.cpp index 955c751e4869..012604dbfb8b 100644 --- a/Marlin/src/HAL/ESP32/u8g_esp32_spi.cpp +++ b/Marlin/src/HAL/ESP32/u8g_esp32_spi.cpp @@ -25,7 +25,7 @@ #include "../../inc/MarlinConfig.h" -#if EITHER(MKS_MINI_12864, FYSETC_MINI_12864_2_1) +#if ANY(MKS_MINI_12864, FYSETC_MINI_12864_2_1) #include #include "../shared/HAL_SPI.h" @@ -101,6 +101,6 @@ uint8_t u8g_eps_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_pt return 1; } -#endif // EITHER(MKS_MINI_12864, FYSETC_MINI_12864_2_1) +#endif // MKS_MINI_12864 || FYSETC_MINI_12864_2_1 #endif // ARDUINO_ARCH_ESP32 diff --git a/Marlin/src/HAL/ESP32/web.cpp b/Marlin/src/HAL/ESP32/web.cpp index 7a27707a3e14..63a101595ff7 100644 --- a/Marlin/src/HAL/ESP32/web.cpp +++ b/Marlin/src/HAL/ESP32/web.cpp @@ -23,7 +23,7 @@ #include "../../inc/MarlinConfigPre.h" -#if BOTH(WIFISUPPORT, WEBSUPPORT) +#if ALL(WIFISUPPORT, WEBSUPPORT) #include "../../inc/MarlinConfig.h" diff --git a/Marlin/src/HAL/LINUX/spi_pins.h b/Marlin/src/HAL/LINUX/spi_pins.h index f09d1decb8eb..7bd2498be748 100644 --- a/Marlin/src/HAL/LINUX/spi_pins.h +++ b/Marlin/src/HAL/LINUX/spi_pins.h @@ -24,7 +24,7 @@ #include "../../core/macros.h" #include "../../inc/MarlinConfigPre.h" -#if BOTH(HAS_MARLINUI_U8GLIB, HAS_MEDIA) && (LCD_PINS_D4 == SD_SCK_PIN || LCD_PINS_EN == SD_MOSI_PIN || DOGLCD_SCK == SD_SCK_PIN || DOGLCD_MOSI == SD_MOSI_PIN) +#if ALL(HAS_MARLINUI_U8GLIB, HAS_MEDIA) && (LCD_PINS_D4 == SD_SCK_PIN || LCD_PINS_EN == SD_MOSI_PIN || DOGLCD_SCK == SD_SCK_PIN || DOGLCD_MOSI == SD_MOSI_PIN) #define SOFTWARE_SPI // If the SD card and LCD adapter share the same SPI pins, then software SPI is currently // needed due to the speed and mode required for communicating with each device being different. // This requirement can be removed if the SPI access to these devices is updated to use diff --git a/Marlin/src/HAL/LPC1768/inc/Conditionals_post.h b/Marlin/src/HAL/LPC1768/inc/Conditionals_post.h index a0bf4215383e..0b03cb2aea63 100644 --- a/Marlin/src/HAL/LPC1768/inc/Conditionals_post.h +++ b/Marlin/src/HAL/LPC1768/inc/Conditionals_post.h @@ -23,7 +23,7 @@ #if USE_FALLBACK_EEPROM #define FLASH_EEPROM_EMULATION -#elif EITHER(I2C_EEPROM, SPI_EEPROM) +#elif ANY(I2C_EEPROM, SPI_EEPROM) #define USE_SHARED_EEPROM 1 #endif diff --git a/Marlin/src/HAL/LPC1768/main.cpp b/Marlin/src/HAL/LPC1768/main.cpp index 419c99793fb8..15518c3d8654 100644 --- a/Marlin/src/HAL/LPC1768/main.cpp +++ b/Marlin/src/HAL/LPC1768/main.cpp @@ -68,7 +68,7 @@ void MarlinHAL::init() { #endif // Flash status LED 3 times to indicate Marlin has started booting - LOOP_L_N(i, 6) { + for (uint8_t i = 0; i < 6; ++i) { TOGGLE(LED_PIN); delay(100); } diff --git a/Marlin/src/HAL/LPC1768/spi_pins.h b/Marlin/src/HAL/LPC1768/spi_pins.h index 33a5b369adab..babe8a11d719 100644 --- a/Marlin/src/HAL/LPC1768/spi_pins.h +++ b/Marlin/src/HAL/LPC1768/spi_pins.h @@ -23,7 +23,7 @@ #include "../../core/macros.h" -#if BOTH(HAS_MEDIA, HAS_MARLINUI_U8GLIB) && (LCD_PINS_D4 == SD_SCK_PIN || LCD_PINS_EN == SD_MOSI_PIN || DOGLCD_SCK == SD_SCK_PIN || DOGLCD_MOSI == SD_MOSI_PIN) +#if ALL(HAS_MEDIA, HAS_MARLINUI_U8GLIB) && (LCD_PINS_D4 == SD_SCK_PIN || LCD_PINS_EN == SD_MOSI_PIN || DOGLCD_SCK == SD_SCK_PIN || DOGLCD_MOSI == SD_MOSI_PIN) #define SOFTWARE_SPI // If the SD card and LCD adapter share the same SPI pins, then software SPI is currently // needed due to the speed and mode required for communicating with each device being different. // This requirement can be removed if the SPI access to these devices is updated to use diff --git a/Marlin/src/HAL/LPC1768/tft/tft_spi.cpp b/Marlin/src/HAL/LPC1768/tft/tft_spi.cpp index 10555762b1a0..c148617785cc 100644 --- a/Marlin/src/HAL/LPC1768/tft/tft_spi.cpp +++ b/Marlin/src/HAL/LPC1768/tft/tft_spi.cpp @@ -74,7 +74,7 @@ uint32_t TFT_SPI::ReadID(uint16_t Reg) { WRITE(TFT_CS_PIN, LOW); WriteReg(Reg); - LOOP_L_N(i, 4) { + for (uint8_t i = 0; i < 4; ++i) { SPIx.read((uint8_t*)&d, 1); data = (data << 8) | d; } diff --git a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_sw_spi.cpp b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_sw_spi.cpp index f116a9b80aa6..f6ed7b0e7e8a 100644 --- a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_sw_spi.cpp +++ b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_sw_spi.cpp @@ -75,7 +75,7 @@ uint8_t swSpiTransfer_mode_0(uint8_t b, const uint8_t spi_speed, const pin_t sck_pin, const pin_t miso_pin, const pin_t mosi_pin ) { - LOOP_L_N(i, 8) { + for (uint8_t i = 0; i < 8; ++i) { if (spi_speed == 0) { LPC176x::gpio_set(mosi_pin, !!(b & 0x80)); LPC176x::gpio_set(sck_pin, HIGH); @@ -85,16 +85,16 @@ uint8_t swSpiTransfer_mode_0(uint8_t b, const uint8_t spi_speed, const pin_t sck } else { const uint8_t state = (b & 0x80) ? HIGH : LOW; - LOOP_L_N(j, spi_speed) + for (uint8_t j = 0; j < spi_speed; ++j) LPC176x::gpio_set(mosi_pin, state); - LOOP_L_N(j, spi_speed + (miso_pin >= 0 ? 0 : 1)) + for (uint8_t j = 0; j < spi_speed + (miso_pin >= 0 ? 0 : 1); ++j) LPC176x::gpio_set(sck_pin, HIGH); b <<= 1; if (miso_pin >= 0 && LPC176x::gpio_get(miso_pin)) b |= 1; - LOOP_L_N(j, spi_speed) + for (uint8_t j = 0; j < spi_speed; ++j) LPC176x::gpio_set(sck_pin, LOW); } } @@ -104,7 +104,7 @@ uint8_t swSpiTransfer_mode_0(uint8_t b, const uint8_t spi_speed, const pin_t sck uint8_t swSpiTransfer_mode_3(uint8_t b, const uint8_t spi_speed, const pin_t sck_pin, const pin_t miso_pin, const pin_t mosi_pin ) { - LOOP_L_N(i, 8) { + for (uint8_t i = 0; i < 8; ++i) { const uint8_t state = (b & 0x80) ? HIGH : LOW; if (spi_speed == 0) { LPC176x::gpio_set(sck_pin, LOW); @@ -113,13 +113,13 @@ uint8_t swSpiTransfer_mode_3(uint8_t b, const uint8_t spi_speed, const pin_t sck LPC176x::gpio_set(sck_pin, HIGH); } else { - LOOP_L_N(j, spi_speed + (miso_pin >= 0 ? 0 : 1)) + for (uint8_t j = 0; j < spi_speed + (miso_pin >= 0 ? 0 : 1); ++j) LPC176x::gpio_set(sck_pin, LOW); - LOOP_L_N(j, spi_speed) + for (uint8_t j = 0; j < spi_speed; ++j) LPC176x::gpio_set(mosi_pin, state); - LOOP_L_N(j, spi_speed) + for (uint8_t j = 0; j < spi_speed; ++j) LPC176x::gpio_set(sck_pin, HIGH); } b <<= 1; @@ -132,7 +132,7 @@ uint8_t swSpiTransfer_mode_3(uint8_t b, const uint8_t spi_speed, const pin_t sck static uint8_t SPI_speed = 0; static void u8g_sw_spi_HAL_LPC1768_shift_out(uint8_t dataPin, uint8_t clockPin, uint8_t val) { - #if EITHER(FYSETC_MINI_12864, MKS_MINI_12864) + #if ANY(FYSETC_MINI_12864, MKS_MINI_12864) swSpiTransfer_mode_3(val, SPI_speed, clockPin, -1, dataPin); #else swSpiTransfer_mode_0(val, SPI_speed, clockPin, -1, dataPin); @@ -160,10 +160,10 @@ uint8_t u8g_com_HAL_LPC1768_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, break; case U8G_COM_MSG_CHIP_SELECT: - #if EITHER(FYSETC_MINI_12864, MKS_MINI_12864) // LCD SPI is running mode 3 while SD card is running mode 0 - if (arg_val) { // SCK idle state needs to be set to the proper idle state before - // the next chip select goes active - u8g_SetPILevel(u8g, U8G_PI_SCK, 1); // Set SCK to mode 3 idle state before CS goes active + #if ANY(FYSETC_MINI_12864, MKS_MINI_12864) // LCD SPI is running mode 3 while SD card is running mode 0 + if (arg_val) { // SCK idle state needs to be set to the proper idle state before + // the next chip select goes active + u8g_SetPILevel(u8g, U8G_PI_SCK, 1); // Set SCK to mode 3 idle state before CS goes active u8g_SetPILevel(u8g, U8G_PI_CS, LOW); } else { diff --git a/Marlin/src/HAL/NATIVE_SIM/pinsDebug.cpp b/Marlin/src/HAL/NATIVE_SIM/pinsDebug.cpp new file mode 100644 index 000000000000..e75826c58a8c --- /dev/null +++ b/Marlin/src/HAL/NATIVE_SIM/pinsDebug.cpp @@ -0,0 +1,45 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#ifdef __PLAT_NATIVE_SIM__ + +#include "../../inc/MarlinConfig.h" +#include "pinsDebug.h" + +int8_t ADC_pin_mode(pin_t pin) { return -1; } + +int8_t get_pin_mode(const pin_t pin) { return VALID_PIN(pin) ? 0 : -1; } + +bool GET_PINMODE(const pin_t pin) { + const int8_t pin_mode = get_pin_mode(pin); + if (pin_mode == -1 || pin_mode == ADC_pin_mode(pin)) // Invalid pin or active analog pin + return false; + + return (Gpio::getMode(pin) != 0); // Input/output state +} + +bool GET_ARRAY_IS_DIGITAL(const pin_t pin) { + return !IS_ANALOG(pin) || get_pin_mode(pin) != ADC_pin_mode(pin); +} + +void print_port(const pin_t) {} +void pwm_details(const pin_t) {} +bool pwm_status(const pin_t) { return false; } + +#endif diff --git a/Marlin/src/HAL/NATIVE_SIM/pinsDebug.h b/Marlin/src/HAL/NATIVE_SIM/pinsDebug.h index 9c53b4b0d9c9..28821acbd07c 100644 --- a/Marlin/src/HAL/NATIVE_SIM/pinsDebug.h +++ b/Marlin/src/HAL/NATIVE_SIM/pinsDebug.h @@ -36,22 +36,10 @@ #define MULTI_NAME_PAD 16 // space needed to be pretty if not first name assigned to a pin // Active ADC function/mode/code values for PINSEL registers -constexpr int8_t ADC_pin_mode(pin_t pin) { return -1; } - -int8_t get_pin_mode(const pin_t pin) { return VALID_PIN(pin) ? 0 : -1; } - -bool GET_PINMODE(const pin_t pin) { - const int8_t pin_mode = get_pin_mode(pin); - if (pin_mode == -1 || pin_mode == ADC_pin_mode(pin)) // Invalid pin or active analog pin - return false; - - return (Gpio::getMode(pin) != 0); // Input/output state -} - -bool GET_ARRAY_IS_DIGITAL(const pin_t pin) { - return !IS_ANALOG(pin) || get_pin_mode(pin) != ADC_pin_mode(pin); -} - -void print_port(const pin_t) {} -void pwm_details(const pin_t) {} -bool pwm_status(const pin_t) { return false; } +int8_t ADC_pin_mode(pin_t pin); +int8_t get_pin_mode(const pin_t pin); +bool GET_PINMODE(const pin_t pin); +bool GET_ARRAY_IS_DIGITAL(const pin_t pin); +void print_port(const pin_t); +void pwm_details(const pin_t); +bool pwm_status(const pin_t); diff --git a/Marlin/src/HAL/NATIVE_SIM/spi_pins.h b/Marlin/src/HAL/NATIVE_SIM/spi_pins.h index 02fb3592382c..9b1bae9a5836 100644 --- a/Marlin/src/HAL/NATIVE_SIM/spi_pins.h +++ b/Marlin/src/HAL/NATIVE_SIM/spi_pins.h @@ -24,7 +24,7 @@ #include "../../core/macros.h" #include "../../inc/MarlinConfigPre.h" -#if BOTH(HAS_MARLINUI_U8GLIB, HAS_MEDIA) && (LCD_PINS_D4 == SD_SCK_PIN || LCD_PINS_EN == SD_MOSI_PIN || DOGLCD_SCK == SD_SCK_PIN || DOGLCD_MOSI == SD_MOSI_PIN) +#if ALL(HAS_MARLINUI_U8GLIB, HAS_MEDIA) && (LCD_PINS_D4 == SD_SCK_PIN || LCD_PINS_EN == SD_MOSI_PIN || DOGLCD_SCK == SD_SCK_PIN || DOGLCD_MOSI == SD_MOSI_PIN) #define SOFTWARE_SPI // If the SD card and LCD adapter share the same SPI pins, then software SPI is currently // needed due to the speed and mode required for communicating with each device being different. // This requirement can be removed if the SPI access to these devices is updated to use diff --git a/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_sw_spi.cpp b/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_sw_spi.cpp index 7be84580b133..9184e2f6188c 100644 --- a/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_sw_spi.cpp +++ b/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_sw_spi.cpp @@ -70,7 +70,7 @@ #endif uint8_t swSpiTransfer_mode_0(uint8_t b, const uint8_t spi_speed, const pin_t sck_pin, const pin_t miso_pin, const pin_t mosi_pin ) { - LOOP_L_N(i, 8) { + for (uint8_t i = 0; i < 8; ++i) { if (spi_speed == 0) { WRITE_PIN(mosi_pin, !!(b & 0x80)); WRITE_PIN(sck_pin, HIGH); @@ -80,16 +80,16 @@ uint8_t swSpiTransfer_mode_0(uint8_t b, const uint8_t spi_speed, const pin_t sck } else { const uint8_t state = (b & 0x80) ? HIGH : LOW; - LOOP_L_N(j, spi_speed) + for (uint8_t j = 0; j < spi_speed; ++j) WRITE_PIN(mosi_pin, state); - LOOP_L_N(j, spi_speed + (miso_pin >= 0 ? 0 : 1)) + for (uint8_t j = 0; j < spi_speed + (miso_pin >= 0 ? 0 : 1); ++j) WRITE_PIN(sck_pin, HIGH); b <<= 1; if (miso_pin >= 0 && READ_PIN(miso_pin)) b |= 1; - LOOP_L_N(j, spi_speed) + for (uint8_t j = 0; j < spi_speed; ++j) WRITE_PIN(sck_pin, LOW); } } @@ -99,7 +99,7 @@ uint8_t swSpiTransfer_mode_0(uint8_t b, const uint8_t spi_speed, const pin_t sck uint8_t swSpiTransfer_mode_3(uint8_t b, const uint8_t spi_speed, const pin_t sck_pin, const pin_t miso_pin, const pin_t mosi_pin ) { - LOOP_L_N(i, 8) { + for (uint8_t i = 0; i < 8; ++i) { const uint8_t state = (b & 0x80) ? HIGH : LOW; if (spi_speed == 0) { WRITE_PIN(sck_pin, LOW); @@ -108,13 +108,13 @@ uint8_t swSpiTransfer_mode_3(uint8_t b, const uint8_t spi_speed, const pin_t sck WRITE_PIN(sck_pin, HIGH); } else { - LOOP_L_N(j, spi_speed + (miso_pin >= 0 ? 0 : 1)) + for (uint8_t j = 0; j < spi_speed + (miso_pin >= 0 ? 0 : 1); ++j) WRITE_PIN(sck_pin, LOW); - LOOP_L_N(j, spi_speed) + for (uint8_t j = 0; j < spi_speed; ++j) WRITE_PIN(mosi_pin, state); - LOOP_L_N(j, spi_speed) + for (uint8_t j = 0; j < spi_speed; ++j) WRITE_PIN(sck_pin, HIGH); } b <<= 1; @@ -131,7 +131,7 @@ static uint8_t swSpiInit(const uint8_t spi_speed, const uint8_t clk_pin, const u } static void u8g_sw_spi_shift_out(uint8_t dataPin, uint8_t clockPin, uint8_t val) { - #if EITHER(FYSETC_MINI_12864, MKS_MINI_12864) + #if ANY(FYSETC_MINI_12864, MKS_MINI_12864) swSpiTransfer_mode_3(val, SPI_speed, clockPin, -1, dataPin); #else swSpiTransfer_mode_0(val, SPI_speed, clockPin, -1, dataPin); @@ -159,10 +159,10 @@ uint8_t u8g_com_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_pt break; case U8G_COM_MSG_CHIP_SELECT: - #if EITHER(FYSETC_MINI_12864, MKS_MINI_12864) // LCD SPI is running mode 3 while SD card is running mode 0 - if (arg_val) { // SCK idle state needs to be set to the proper idle state before - // the next chip select goes active - u8g_SetPILevel(u8g, U8G_PI_SCK, 1); // Set SCK to mode 3 idle state before CS goes active + #if ANY(FYSETC_MINI_12864, MKS_MINI_12864) // LCD SPI is running mode 3 while SD card is running mode 0 + if (arg_val) { // SCK idle state needs to be set to the proper idle state before + // the next chip select goes active + u8g_SetPILevel(u8g, U8G_PI_SCK, 1); // Set SCK to mode 3 idle state before CS goes active u8g_SetPILevel(u8g, U8G_PI_CS, LOW); } else { diff --git a/Marlin/src/HAL/SAMD21/HAL_SPI.cpp b/Marlin/src/HAL/SAMD21/HAL_SPI.cpp index 69c6a43af835..e01f540cf8a1 100644 --- a/Marlin/src/HAL/SAMD21/HAL_SPI.cpp +++ b/Marlin/src/HAL/SAMD21/HAL_SPI.cpp @@ -45,7 +45,7 @@ // Public functions // -------------------------------------------------------------------------- -#if EITHER(SOFTWARE_SPI, FORCE_SOFT_SPI) +#if ANY(SOFTWARE_SPI, FORCE_SOFT_SPI) // ------------------------ // Software SPI diff --git a/Marlin/src/HAL/SAMD21/inc/Conditionals_post.h b/Marlin/src/HAL/SAMD21/inc/Conditionals_post.h index 7315dc12a779..87d3350c9450 100644 --- a/Marlin/src/HAL/SAMD21/inc/Conditionals_post.h +++ b/Marlin/src/HAL/SAMD21/inc/Conditionals_post.h @@ -28,6 +28,6 @@ #if USE_FALLBACK_EEPROM #define FLASH_EEPROM_EMULATION -#elif EITHER(I2C_EEPROM, SPI_EEPROM) +#elif ANY(I2C_EEPROM, SPI_EEPROM) #define USE_SHARED_EEPROM 1 #endif diff --git a/Marlin/src/HAL/SAMD51/HAL.cpp b/Marlin/src/HAL/SAMD51/HAL.cpp index bc7a9b6d913a..8ec5d5a86c4b 100644 --- a/Marlin/src/HAL/SAMD51/HAL.cpp +++ b/Marlin/src/HAL/SAMD51/HAL.cpp @@ -650,10 +650,10 @@ void MarlinHAL::adc_init() { #if ADC_IS_REQUIRED memset(adc_results, 0xFF, sizeof(adc_results)); // Fill result with invalid values - LOOP_L_N(pi, COUNT(adc_pins)) + for (uint8_t pi = 0; pi < COUNT(adc_pins); ++pi) pinPeripheral(adc_pins[pi], PIO_ANALOG); - LOOP_S_LE_N(ai, FIRST_ADC, LAST_ADC) { + for (uint8_t ai = FIRST_ADC; ai <= LAST_ADC; ++ai) { Adc* adc = ((Adc*[])ADC_INSTS)[ai]; // ADC clock setup @@ -685,7 +685,7 @@ void MarlinHAL::adc_init() { void MarlinHAL::adc_start(const pin_t pin) { #if ADC_IS_REQUIRED - LOOP_L_N(pi, COUNT(adc_pins)) + for (uint8_t pi = 0; pi < COUNT(adc_pins); ++pi) if (pin == adc_pins[pi]) { adc_result = adc_results[pi]; return; } #endif diff --git a/Marlin/src/HAL/SAMD51/HAL_SPI.cpp b/Marlin/src/HAL/SAMD51/HAL_SPI.cpp index 58fdfe9499a1..63d3971965c9 100644 --- a/Marlin/src/HAL/SAMD51/HAL_SPI.cpp +++ b/Marlin/src/HAL/SAMD51/HAL_SPI.cpp @@ -44,7 +44,7 @@ // Public functions // -------------------------------------------------------------------------- -#if EITHER(SOFTWARE_SPI, FORCE_SOFT_SPI) +#if ANY(SOFTWARE_SPI, FORCE_SOFT_SPI) // ------------------------ // Software SPI diff --git a/Marlin/src/HAL/SAMD51/inc/Conditionals_post.h b/Marlin/src/HAL/SAMD51/inc/Conditionals_post.h index ce6d3fdde27f..295596b78b19 100644 --- a/Marlin/src/HAL/SAMD51/inc/Conditionals_post.h +++ b/Marlin/src/HAL/SAMD51/inc/Conditionals_post.h @@ -23,6 +23,6 @@ #if USE_FALLBACK_EEPROM #define FLASH_EEPROM_EMULATION -#elif EITHER(I2C_EEPROM, SPI_EEPROM) +#elif ANY(I2C_EEPROM, SPI_EEPROM) #define USE_SHARED_EEPROM 1 #endif diff --git a/Marlin/src/HAL/STM32/fastio.cpp b/Marlin/src/HAL/STM32/fastio.cpp index b34555b8c841..a4b3ba70c923 100644 --- a/Marlin/src/HAL/STM32/fastio.cpp +++ b/Marlin/src/HAL/STM32/fastio.cpp @@ -29,7 +29,7 @@ GPIO_TypeDef* FastIOPortMap[LastPort + 1] = { 0 }; void FastIO_init() { - LOOP_L_N(i, NUM_DIGITAL_PINS) + for (uint8_t i = 0; i < NUM_DIGITAL_PINS; ++i) FastIOPortMap[STM_PORT(digitalPin[i])] = get_GPIO_Port(STM_PORT(digitalPin[i])); } diff --git a/Marlin/src/HAL/STM32/inc/Conditionals_adv.h b/Marlin/src/HAL/STM32/inc/Conditionals_adv.h index ee8c49e4e055..032716a294ce 100644 --- a/Marlin/src/HAL/STM32/inc/Conditionals_adv.h +++ b/Marlin/src/HAL/STM32/inc/Conditionals_adv.h @@ -21,7 +21,7 @@ */ #pragma once -#if BOTH(HAS_MEDIA, USBD_USE_CDC_MSC) && DISABLED(NO_SD_HOST_DRIVE) +#if ALL(HAS_MEDIA, USBD_USE_CDC_MSC) && DISABLED(NO_SD_HOST_DRIVE) #define HAS_SD_HOST_DRIVE 1 #endif diff --git a/Marlin/src/HAL/STM32/inc/Conditionals_post.h b/Marlin/src/HAL/STM32/inc/Conditionals_post.h index 83ce077c754d..6c97a635b3cc 100644 --- a/Marlin/src/HAL/STM32/inc/Conditionals_post.h +++ b/Marlin/src/HAL/STM32/inc/Conditionals_post.h @@ -24,7 +24,7 @@ // If no real or emulated EEPROM selected, fall back to SD emulation #if USE_FALLBACK_EEPROM #define SDCARD_EEPROM_EMULATION -#elif EITHER(I2C_EEPROM, SPI_EEPROM) +#elif ANY(I2C_EEPROM, SPI_EEPROM) #define USE_SHARED_EEPROM 1 #endif diff --git a/Marlin/src/HAL/STM32/tft/gt911.cpp b/Marlin/src/HAL/STM32/tft/gt911.cpp index 82b7c5b10391..6809f6620093 100644 --- a/Marlin/src/HAL/STM32/tft/gt911.cpp +++ b/Marlin/src/HAL/STM32/tft/gt911.cpp @@ -90,7 +90,7 @@ bool SW_IIC::read_ack() { } void SW_IIC::send_byte(uint8_t txd) { - LOOP_L_N(i, 8) { + for (uint8_t i = 0; i < 8; ++i) { write_sda(txd & 0x80); // write data bit txd <<= 1; iic_delay(1); @@ -107,7 +107,7 @@ uint8_t SW_IIC::read_byte(bool ack) { uint8_t data = 0; set_sda_in(); - LOOP_L_N(i, 8) { + for (uint8_t i = 0; i < 8; ++i) { write_scl(HIGH); // SCL = 1 iic_delay(1); data <<= 1; @@ -128,12 +128,12 @@ SW_IIC GT911::sw_iic = SW_IIC(GT911_SW_I2C_SDA_PIN, GT911_SW_I2C_SCL_PIN); void GT911::write_reg(uint16_t reg, uint8_t reg_len, uint8_t* w_data, uint8_t w_len) { sw_iic.start(); sw_iic.send_byte(gt911_slave_address); // Set IIC Slave address - LOOP_L_N(i, reg_len) { // Set reg address + for (uint8_t i = 0; i < reg_len; ++i) { // Set reg address uint8_t r = (reg >> (8 * (reg_len - 1 - i))) & 0xFF; sw_iic.send_byte(r); } - LOOP_L_N(i, w_len) { // Write data to reg + for (uint8_t i = 0; i < w_len; ++i) { // Write data to reg sw_iic.send_byte(w_data[i]); } sw_iic.stop(); @@ -142,7 +142,7 @@ void GT911::write_reg(uint16_t reg, uint8_t reg_len, uint8_t* w_data, uint8_t w_ void GT911::read_reg(uint16_t reg, uint8_t reg_len, uint8_t* r_data, uint8_t r_len) { sw_iic.start(); sw_iic.send_byte(gt911_slave_address); // Set IIC Slave address - LOOP_L_N(i, reg_len) { // Set reg address + for (uint8_t i = 0; i < reg_len; ++i) { // Set reg address uint8_t r = (reg >> (8 * (reg_len - 1 - i))) & 0xFF; sw_iic.send_byte(r); } @@ -150,7 +150,7 @@ void GT911::read_reg(uint16_t reg, uint8_t reg_len, uint8_t* r_data, uint8_t r_l sw_iic.start(); sw_iic.send_byte(gt911_slave_address + 1); // Set read mode - LOOP_L_N(i, r_len) + for (uint8_t i = 0; i < r_len; ++i) r_data[i] = sw_iic.read_byte(1); // Read data from reg sw_iic.stop(); diff --git a/Marlin/src/HAL/STM32/timers.cpp b/Marlin/src/HAL/STM32/timers.cpp index e68b59c46fee..54506cb4513f 100644 --- a/Marlin/src/HAL/STM32/timers.cpp +++ b/Marlin/src/HAL/STM32/timers.cpp @@ -292,9 +292,9 @@ static constexpr int get_timer_num_from_base_address(uintptr_t base_address) { // constexpr doesn't like using the base address pointers that timers evaluate to. // We can get away with casting them to uintptr_t, if we do so inside an array. // GCC will not currently do it directly to a uintptr_t. -IF_ENABLED(HAS_TMC_SW_SERIAL, static constexpr uintptr_t timer_serial[] = {uintptr_t(TIMER_SERIAL)}); -IF_ENABLED(SPEAKER, static constexpr uintptr_t timer_tone[] = {uintptr_t(TIMER_TONE)}); -IF_ENABLED(HAS_SERVOS, static constexpr uintptr_t timer_servo[] = {uintptr_t(TIMER_SERVO)}); +TERN_(HAS_TMC_SW_SERIAL, static constexpr uintptr_t timer_serial[] = {uintptr_t(TIMER_SERIAL)}); +TERN_(SPEAKER, static constexpr uintptr_t timer_tone[] = {uintptr_t(TIMER_TONE)}); +TERN_(HAS_SERVOS, static constexpr uintptr_t timer_servo[] = {uintptr_t(TIMER_SERVO)}); enum TimerPurpose { TP_SERIAL, TP_TONE, TP_SERVO, TP_STEP, TP_TEMP }; @@ -316,8 +316,8 @@ static constexpr struct { TimerPurpose p; int t; } timers_in_use[] = { }; static constexpr bool verify_no_timer_conflicts() { - LOOP_L_N(i, COUNT(timers_in_use)) - LOOP_S_L_N(j, i + 1, COUNT(timers_in_use)) + for (uint8_t i = 0; i < COUNT(timers_in_use); ++i) + for (uint8_t j = i + 1; j < COUNT(timers_in_use); ++j) if (timers_in_use[i].t == timers_in_use[j].t) return false; return true; } diff --git a/Marlin/src/HAL/STM32/usb_host.cpp b/Marlin/src/HAL/STM32/usb_host.cpp index f3784670049c..afafe1d4f3d1 100644 --- a/Marlin/src/HAL/STM32/usb_host.cpp +++ b/Marlin/src/HAL/STM32/usb_host.cpp @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfig.h" -#if BOTH(USE_OTG_USB_HOST, USBHOST) +#if ALL(USE_OTG_USB_HOST, USBHOST) #include "usb_host.h" #include "../shared/Marduino.h" diff --git a/Marlin/src/HAL/STM32F1/HAL.cpp b/Marlin/src/HAL/STM32F1/HAL.cpp index a0cdda3b4fd7..373116ba39fb 100644 --- a/Marlin/src/HAL/STM32F1/HAL.cpp +++ b/Marlin/src/HAL/STM32F1/HAL.cpp @@ -224,7 +224,7 @@ void MarlinHAL::init() { #endif #if HAS_SD_HOST_DRIVE MSC_SD_init(); - #elif BOTH(SERIAL_USB, EMERGENCY_PARSER) + #elif ALL(SERIAL_USB, EMERGENCY_PARSER) usb_cdcacm_set_hooks(USB_CDCACM_HOOK_RX, my_rx_callback); #endif #if PIN_EXISTS(USB_CONNECT) diff --git a/Marlin/src/HAL/STM32F1/HAL.h b/Marlin/src/HAL/STM32F1/HAL.h index 8ed525bfb71b..b5f4d6fe8bab 100644 --- a/Marlin/src/HAL/STM32F1/HAL.h +++ b/Marlin/src/HAL/STM32F1/HAL.h @@ -82,7 +82,7 @@ #define _MSERIAL(X) MSerial##X #define MSERIAL(X) _MSERIAL(X) -#if EITHER(STM32_HIGH_DENSITY, STM32_XL_DENSITY) +#if ANY(STM32_HIGH_DENSITY, STM32_XL_DENSITY) #define NUM_UARTS 5 #else #define NUM_UARTS 3 diff --git a/Marlin/src/HAL/STM32F1/MarlinSerial.cpp b/Marlin/src/HAL/STM32F1/MarlinSerial.cpp index 7898e9f2bcc1..568fc05d4185 100644 --- a/Marlin/src/HAL/STM32F1/MarlinSerial.cpp +++ b/Marlin/src/HAL/STM32F1/MarlinSerial.cpp @@ -116,7 +116,7 @@ constexpr bool serial_handles_emergency(int port) { #endif DEFINE_HWSERIAL_MARLIN(MSerial2, 2); DEFINE_HWSERIAL_MARLIN(MSerial3, 3); -#if EITHER(STM32_HIGH_DENSITY, STM32_XL_DENSITY) +#if ANY(STM32_HIGH_DENSITY, STM32_XL_DENSITY) DEFINE_HWSERIAL_UART_MARLIN(MSerial4, 4); DEFINE_HWSERIAL_UART_MARLIN(MSerial5, 5); #endif diff --git a/Marlin/src/HAL/STM32F1/MarlinSerial.h b/Marlin/src/HAL/STM32F1/MarlinSerial.h index dda32fe7a2ef..53bcd4847638 100644 --- a/Marlin/src/HAL/STM32F1/MarlinSerial.h +++ b/Marlin/src/HAL/STM32F1/MarlinSerial.h @@ -52,7 +52,7 @@ typedef Serial1Class MSerialT; extern MSerialT MSerial1; extern MSerialT MSerial2; extern MSerialT MSerial3; -#if EITHER(STM32_HIGH_DENSITY, STM32_XL_DENSITY) +#if ANY(STM32_HIGH_DENSITY, STM32_XL_DENSITY) extern MSerialT MSerial4; extern MSerialT MSerial5; #endif diff --git a/Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_swspi.cpp b/Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_swspi.cpp index 26ea1ea19af9..c57350aa2efd 100644 --- a/Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_swspi.cpp +++ b/Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_swspi.cpp @@ -24,7 +24,7 @@ #include "../../../inc/MarlinConfig.h" -#if BOTH(HAS_MARLINUI_U8GLIB, FORCE_SOFT_SPI) +#if ALL(HAS_MARLINUI_U8GLIB, FORCE_SOFT_SPI) #include #include "../../shared/HAL_SPI.h" @@ -37,7 +37,7 @@ static uint8_t SPI_speed = LCD_SPI_SPEED; static inline uint8_t swSpiTransfer_mode_0(uint8_t b, const uint8_t spi_speed, const pin_t miso_pin=-1) { - LOOP_L_N(i, 8) { + for (uint8_t i = 0; i < 8; ++i) { if (spi_speed == 0) { WRITE(DOGLCD_MOSI, !!(b & 0x80)); WRITE(DOGLCD_SCK, HIGH); @@ -47,16 +47,16 @@ static inline uint8_t swSpiTransfer_mode_0(uint8_t b, const uint8_t spi_speed, c } else { const uint8_t state = (b & 0x80) ? HIGH : LOW; - LOOP_L_N(j, spi_speed) + for (uint8_t j = 0; j < spi_speed; ++j) WRITE(DOGLCD_MOSI, state); - LOOP_L_N(j, spi_speed + (miso_pin >= 0 ? 0 : 1)) + for (uint8_t j = 0; j < spi_speed + (miso_pin >= 0 ? 0 : 1); ++j) WRITE(DOGLCD_SCK, HIGH); b <<= 1; if (miso_pin >= 0 && READ(miso_pin)) b |= 1; - LOOP_L_N(j, spi_speed) + for (uint8_t j = 0; j < spi_speed; ++j) WRITE(DOGLCD_SCK, LOW); } } @@ -64,7 +64,7 @@ static inline uint8_t swSpiTransfer_mode_0(uint8_t b, const uint8_t spi_speed, c } static inline uint8_t swSpiTransfer_mode_3(uint8_t b, const uint8_t spi_speed, const pin_t miso_pin=-1) { - LOOP_L_N(i, 8) { + for (uint8_t i = 0; i < 8; ++i) { const uint8_t state = (b & 0x80) ? HIGH : LOW; if (spi_speed == 0) { WRITE(DOGLCD_SCK, LOW); @@ -73,13 +73,13 @@ static inline uint8_t swSpiTransfer_mode_3(uint8_t b, const uint8_t spi_speed, c WRITE(DOGLCD_SCK, HIGH); } else { - LOOP_L_N(j, spi_speed + (miso_pin >= 0 ? 0 : 1)) + for (uint8_t j = 0; j < spi_speed + (miso_pin >= 0 ? 0 : 1); ++j) WRITE(DOGLCD_SCK, LOW); - LOOP_L_N(j, spi_speed) + for (uint8_t j = 0; j < spi_speed; ++j) WRITE(DOGLCD_MOSI, state); - LOOP_L_N(j, spi_speed) + for (uint8_t j = 0; j < spi_speed; ++j) WRITE(DOGLCD_SCK, HIGH); } b <<= 1; diff --git a/Marlin/src/HAL/STM32F1/inc/Conditionals_post.h b/Marlin/src/HAL/STM32F1/inc/Conditionals_post.h index 5a4bde16a5e6..f130f5cad8e1 100644 --- a/Marlin/src/HAL/STM32F1/inc/Conditionals_post.h +++ b/Marlin/src/HAL/STM32F1/inc/Conditionals_post.h @@ -24,7 +24,7 @@ // If no real EEPROM, Flash emulation, or SRAM emulation is available fall back to SD emulation #if USE_FALLBACK_EEPROM #define SDCARD_EEPROM_EMULATION -#elif EITHER(I2C_EEPROM, SPI_EEPROM) +#elif ANY(I2C_EEPROM, SPI_EEPROM) #define USE_SHARED_EEPROM 1 #endif diff --git a/Marlin/src/HAL/STM32F1/pinsDebug.h b/Marlin/src/HAL/STM32F1/pinsDebug.h index 2142f0ebac62..6f8e48f455bd 100644 --- a/Marlin/src/HAL/STM32F1/pinsDebug.h +++ b/Marlin/src/HAL/STM32F1/pinsDebug.h @@ -94,7 +94,7 @@ void pwm_details(const pin_t pin) { timer_dev * const tdev = PIN_MAP[pin].timer_device; const uint8_t channel = PIN_MAP[pin].timer_channel; const char num = ( - #if EITHER(STM32_HIGH_DENSITY, STM32_XL_DENSITY) + #if ANY(STM32_HIGH_DENSITY, STM32_XL_DENSITY) tdev == &timer8 ? '8' : tdev == &timer5 ? '5' : #endif diff --git a/Marlin/src/HAL/STM32F1/sdio.cpp b/Marlin/src/HAL/STM32F1/sdio.cpp index b00be302179d..1ab76440b7aa 100644 --- a/Marlin/src/HAL/STM32F1/sdio.cpp +++ b/Marlin/src/HAL/STM32F1/sdio.cpp @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfig.h" // Allow pins/pins.h to set density -#if EITHER(STM32_HIGH_DENSITY, STM32_XL_DENSITY) +#if ANY(STM32_HIGH_DENSITY, STM32_XL_DENSITY) #include "sdio.h" diff --git a/Marlin/src/HAL/STM32F1/tft/tft_spi.cpp b/Marlin/src/HAL/STM32F1/tft/tft_spi.cpp index 5264aabef662..a68b2b98f8a3 100644 --- a/Marlin/src/HAL/STM32F1/tft/tft_spi.cpp +++ b/Marlin/src/HAL/STM32F1/tft/tft_spi.cpp @@ -101,7 +101,7 @@ uint32_t TFT_SPI::ReadID(uint16_t Reg) { DataTransferBegin(DATASIZE_8BIT); WriteReg(Reg); - LOOP_L_N(i, 4) { + for (uint8_t i = 0; i < 4; ++i) { uint8_t d; SPIx.read(&d, 1); data = (data << 8) | d; diff --git a/Marlin/src/HAL/shared/HAL_ST7920.h b/Marlin/src/HAL/shared/HAL_ST7920.h index 4e362f96ba55..305736c3a514 100644 --- a/Marlin/src/HAL/shared/HAL_ST7920.h +++ b/Marlin/src/HAL/shared/HAL_ST7920.h @@ -27,7 +27,7 @@ * (bypassing U8G), it will allow the LIGHTWEIGHT_UI to operate. */ -#if BOTH(HAS_MARLINUI_U8GLIB, LIGHTWEIGHT_UI) +#if ALL(HAS_MARLINUI_U8GLIB, LIGHTWEIGHT_UI) void ST7920_cs(); void ST7920_ncs(); void ST7920_set_cmd(); diff --git a/Marlin/src/HAL/shared/eeprom_api.cpp b/Marlin/src/HAL/shared/eeprom_api.cpp index 47cfa5a2dbe0..083ccc70d7c9 100644 --- a/Marlin/src/HAL/shared/eeprom_api.cpp +++ b/Marlin/src/HAL/shared/eeprom_api.cpp @@ -22,7 +22,7 @@ */ #include "../../inc/MarlinConfigPre.h" -#if EITHER(EEPROM_SETTINGS, SD_FIRMWARE_UPDATE) +#if ANY(EEPROM_SETTINGS, SD_FIRMWARE_UPDATE) #include "eeprom_api.h" PersistentStore persistentStore; diff --git a/Marlin/src/HAL/shared/servo.cpp b/Marlin/src/HAL/shared/servo.cpp index b838800de654..bb9d61801841 100644 --- a/Marlin/src/HAL/shared/servo.cpp +++ b/Marlin/src/HAL/shared/servo.cpp @@ -67,7 +67,7 @@ uint8_t ServoCount = 0; // the total number of attached static bool anyTimerChannelActive(const timer16_Sequence_t timer) { // returns true if any servo is active on this timer - LOOP_L_N(channel, SERVOS_PER_TIMER) { + for (uint8_t channel = 0; channel < SERVOS_PER_TIMER; ++channel) { if (SERVO(timer, channel).Pin.isActive) return true; } diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index f1d43e7b6093..ac5a6b7ff9b0 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -199,7 +199,7 @@ #include "feature/runout.h" #endif -#if EITHER(PROBE_TARE, HAS_Z_SERVO_PROBE) +#if ANY(PROBE_TARE, HAS_Z_SERVO_PROBE) #include "module/probe.h" #endif @@ -321,7 +321,7 @@ bool pin_is_protected(const pin_t pin) { static constexpr size_t pincount = OnlyPins::size; static const pin_t (&sensitive_pins)[pincount] PROGMEM = OnlyPins::table; #endif - LOOP_L_N(i, pincount) { + for (uint8_t i = 0; i < pincount; ++i) { const pin_t * const pptr = &sensitive_pins[i]; if (pin == (sizeof(pin_t) == 2 ? (pin_t)pgm_read_word(pptr) : (pin_t)pgm_read_byte(pptr))) return true; } @@ -393,7 +393,7 @@ void startOrResumeJob() { if (queue.enqueue_one(F("M1001"))) { // Keep trying until it gets queued marlin_state = MF_RUNNING; // Signal to stop trying TERN_(PASSWORD_AFTER_SD_PRINT_END, password.lock_machine()); - TERN_(DGUS_LCD_UI_MKS, ScreenHandler.SDPrintingFinished()); + TERN_(DGUS_LCD_UI_MKS, screen.sdPrintingFinished()); } } @@ -726,7 +726,7 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) { #endif } -#if BOTH(EP_BABYSTEPPING, EMERGENCY_PARSER) +#if ALL(EP_BABYSTEPPING, EMERGENCY_PARSER) #include "feature/babystep.h" #endif @@ -800,7 +800,7 @@ void idle(const bool no_stepper_sleep/*=false*/) { // Run StallGuard endstop checks #if ENABLED(SPI_ENDSTOPS) if (endstops.tmc_spi_homing.any && TERN1(IMPROVE_HOMING_RELIABILITY, ELAPSED(millis(), sg_guard_period))) - LOOP_L_N(i, 4) if (endstops.tmc_spi_homing_check()) break; // Read SGT 4 times per idle loop + for (uint8_t i = 0; i < 4; ++i) if (endstops.tmc_spi_homing_check()) break; // Read SGT 4 times per idle loop #endif // Handle SD Card insert / remove @@ -853,7 +853,7 @@ void idle(const bool no_stepper_sleep/*=false*/) { TERN_(POLL_JOG, joystick.inject_jog_moves()); // Async Babystepping via the Emergency Parser - #if BOTH(EP_BABYSTEPPING, EMERGENCY_PARSER) + #if ALL(EP_BABYSTEPPING, EMERGENCY_PARSER) babystep.do_ep_steps(); #endif @@ -924,7 +924,7 @@ void minkill(const bool steppers_off/*=false*/) { TERN_(HAS_SUICIDE, suicide()); - #if EITHER(HAS_KILL, SOFT_RESET_ON_KILL) + #if ANY(HAS_KILL, SOFT_RESET_ON_KILL) // Wait for both KILL and ENC to be released while (TERN0(HAS_KILL, kill_state()) || TERN0(SOFT_RESET_ON_KILL, ui.button_pressed())) @@ -953,7 +953,7 @@ void stop() { print_job_timer.stop(); - #if EITHER(PROBING_FANS_OFF, ADVANCED_PAUSE_FANS_PAUSE) + #if ANY(PROBING_FANS_OFF, ADVANCED_PAUSE_FANS_PAUSE) thermalManager.set_fans_paused(false); // Un-pause fans for safety #endif @@ -1315,14 +1315,14 @@ void setup() { #endif #endif - #if BOTH(HAS_MEDIA, SDCARD_EEPROM_EMULATION) + #if ALL(HAS_MEDIA, SDCARD_EEPROM_EMULATION) SETUP_RUN(card.mount()); // Mount media with settings before first_load #endif SETUP_RUN(settings.first_load()); // Load data from EEPROM if available (or use defaults) // This also updates variables in the planner, elsewhere - #if BOTH(HAS_WIRED_LCD, SHOW_BOOTSCREEN) + #if ALL(HAS_WIRED_LCD, SHOW_BOOTSCREEN) SETUP_RUN(ui.show_bootscreen()); const millis_t bootscreen_ms = millis(); #endif @@ -1397,7 +1397,7 @@ void setup() { SETUP_RUN(stepper_dac.init()); #endif - #if EITHER(Z_PROBE_SLED, SOLENOID_PROBE) && HAS_SOLENOID_1 + #if ANY(Z_PROBE_SLED, SOLENOID_PROBE) && HAS_SOLENOID_1 OUT_WRITE(SOL1_PIN, LOW); // OFF #endif @@ -1605,7 +1605,7 @@ void setup() { SETUP_RUN(tft_lvgl_init()); #endif - #if BOTH(HAS_WIRED_LCD, SHOW_BOOTSCREEN) + #if ALL(HAS_WIRED_LCD, SHOW_BOOTSCREEN) const millis_t elapsed = millis() - bootscreen_ms; #if ENABLED(MARLIN_DEV_MODE) SERIAL_ECHOLNPGM("elapsed=", elapsed); @@ -1617,7 +1617,7 @@ void setup() { SETUP_RUN(password.lock_machine()); // Will not proceed until correct password provided #endif - #if BOTH(HAS_MARLINUI_MENU, TOUCH_SCREEN_CALIBRATION) && EITHER(TFT_CLASSIC_UI, TFT_COLOR_UI) + #if ALL(HAS_MARLINUI_MENU, TOUCH_SCREEN_CALIBRATION) && ANY(TFT_CLASSIC_UI, TFT_COLOR_UI) SETUP_RUN(ui.check_touch_calibration()); #endif @@ -1674,7 +1674,7 @@ void loop() { queue.advance(); - #if EITHER(POWER_OFF_TIMER, POWER_OFF_WAIT_FOR_COOLDOWN) + #if ANY(POWER_OFF_TIMER, POWER_OFF_WAIT_FOR_COOLDOWN) powerManager.checkAutoPowerOff(); #endif diff --git a/Marlin/src/core/language.h b/Marlin/src/core/language.h index 521fcfca3ec9..b76a3d301cc5 100644 --- a/Marlin/src/core/language.h +++ b/Marlin/src/core/language.h @@ -508,7 +508,7 @@ #define STR_W "" #endif -#if EITHER(HAS_MARLINUI_HD44780, IS_TFTGLCD_PANEL) +#if ANY(HAS_MARLINUI_HD44780, IS_TFTGLCD_PANEL) // Custom characters defined in the first 8 characters of the LCD #define LCD_STR_BEDTEMP "\x00" // Print only as a char. This will have 'unexpected' results when used in a string! diff --git a/Marlin/src/core/macros.h b/Marlin/src/core/macros.h index 7e20f838032a..565de2436c11 100644 --- a/Marlin/src/core/macros.h +++ b/Marlin/src/core/macros.h @@ -192,7 +192,11 @@ #define _DIS_1(O) NOT(_ENA_1(O)) #define ENABLED(V...) DO(ENA,&&,V) #define DISABLED(V...) DO(DIS,&&,V) +#define ANY(V...) !DISABLED(V) +#define ALL ENABLED +#define NONE DISABLED #define COUNT_ENABLED(V...) DO(ENA,+,V) +#define MANY(V...) (COUNT_ENABLED(V) > 1) #define TERN(O,A,B) _TERN(_ENA_1(O),B,A) // OPTION ? 'A' : 'B' #define TERN0(O,A) _TERN(_ENA_1(O),0,A) // OPTION ? 'A' : '0' @@ -216,16 +220,8 @@ #define SUM_TERN(O,B,A) ((B) PLUS_TERN0(O,A)) // ((B) (OPTION ? '+ (A)' : '')) #define DIFF_TERN(O,B,A) ((B) MINUS_TERN0(O,A)) // ((B) (OPTION ? '- (A)' : '')) -#define IF_ENABLED TERN_ #define IF_DISABLED(O,A) TERN(O,,A) -#define ANY(V...) !DISABLED(V) -#define NONE(V...) DISABLED(V) -#define ALL(V...) ENABLED(V) -#define BOTH(V1,V2) ALL(V1,V2) -#define EITHER(V1,V2) ANY(V1,V2) -#define MANY(V...) (COUNT_ENABLED(V) > 1) - // Macros to support pins/buttons exist testing #define PIN_EXISTS(PN) (defined(PN##_PIN) && PN##_PIN >= 0) #define _PINEX_1 PIN_EXISTS @@ -330,11 +326,6 @@ #define _JOIN_1(O) (O) #define JOIN_N(N,C,V...) (DO(JOIN,C,LIST_N(N,V))) -#define LOOP_S_LE_N(VAR, S, N) for (uint8_t VAR=(S); VAR<=(N); VAR++) -#define LOOP_S_L_N(VAR, S, N) for (uint8_t VAR=(S); VAR<(N); VAR++) -#define LOOP_LE_N(VAR, N) LOOP_S_LE_N(VAR, 0, N) -#define LOOP_L_N(VAR, N) LOOP_S_L_N(VAR, 0, N) - #define NOOP (void(0)) #define CEILING(x,y) (((x) + (y) - 1) / (y)) diff --git a/Marlin/src/core/serial_base.h b/Marlin/src/core/serial_base.h index 059b42428498..fa0a2298f7c0 100644 --- a/Marlin/src/core/serial_base.h +++ b/Marlin/src/core/serial_base.h @@ -234,7 +234,7 @@ struct SerialBase { // Round correctly so that print(1.999, 2) prints as "2.00" double rounding = 0.5; - LOOP_L_N(i, digits) rounding *= 0.1; + for (uint8_t i = 0; i < digits; ++i) rounding *= 0.1; number += rounding; // Extract the integer part of the number and print it diff --git a/Marlin/src/core/types.h b/Marlin/src/core/types.h index 958155860414..8fcaa0000c61 100644 --- a/Marlin/src/core/types.h +++ b/Marlin/src/core/types.h @@ -246,11 +246,11 @@ enum AxisEnum : uint8_t { // // Loop over axes // -#define LOOP_ABC(VAR) LOOP_S_LE_N(VAR, A_AXIS, C_AXIS) -#define LOOP_NUM_AXES(VAR) LOOP_S_L_N(VAR, 0, NUM_AXES) -#define LOOP_LOGICAL_AXES(VAR) LOOP_S_L_N(VAR, 0, LOGICAL_AXES) -#define LOOP_DISTINCT_AXES(VAR) LOOP_S_L_N(VAR, 0, DISTINCT_AXES) -#define LOOP_DISTINCT_E(VAR) LOOP_L_N(VAR, DISTINCT_E) +#define LOOP_ABC(VAR) for (uint8_t VAR = A_AXIS; VAR <= C_AXIS; ++VAR) +#define LOOP_NUM_AXES(VAR) for (uint8_t VAR = 0; VAR < NUM_AXES; ++VAR) +#define LOOP_LOGICAL_AXES(VAR) for (uint8_t VAR = 0; VAR < LOGICAL_AXES; ++VAR) +#define LOOP_DISTINCT_AXES(VAR) for (uint8_t VAR = 0; VAR < DISTINCT_AXES; ++VAR) +#define LOOP_DISTINCT_E(VAR) for (uint8_t VAR = 0; VAR < DISTINCT_E; ++VAR) // // feedRate_t is just a humble float @@ -452,9 +452,9 @@ struct XYval { FI constexpr XYval operator- (const XYZEval &rs) const { return { XY_OP(-) }; } FI constexpr XYval operator* (const XYZEval &rs) const { return { XY_OP(*) }; } FI constexpr XYval operator/ (const XYZEval &rs) const { return { XY_OP(/) }; } - FI constexpr XYval operator* (const float &p) const { return { x * p, y * p }; } + FI constexpr XYval operator* (const float &p) const { return { (T)(x * p), (T)(y * p) }; } FI constexpr XYval operator* (const int &p) const { return { x * p, y * p }; } - FI constexpr XYval operator/ (const float &p) const { return { x / p, y / p }; } + FI constexpr XYval operator/ (const float &p) const { return { (T)(x / p), (T)(y / p) }; } FI constexpr XYval operator/ (const int &p) const { return { x / p, y / p }; } FI constexpr XYval operator>>(const int &p) const { return { _RS(x), _RS(y) }; } FI constexpr XYval operator<<(const int &p) const { return { _LS(x), _LS(y) }; } @@ -479,6 +479,11 @@ struct XYval { FI XYval& operator>>=(const int &p) { _RSE(x); _RSE(y); return *this; } FI XYval& operator<<=(const int &p) { _LSE(x); _LSE(y); return *this; } + // Absolute difference between two objects + FI constexpr XYval diff(const XYZEval &rs) const { return { TERN(HAS_X_AXIS, T(_ABS(x - rs.x)), x), TERN(HAS_Y_AXIS, T(_ABS(y - rs.y)), y) }; } + FI constexpr XYval diff(const XYZval &rs) const { return { TERN(HAS_X_AXIS, T(_ABS(x - rs.x)), x), TERN(HAS_Y_AXIS, T(_ABS(y - rs.y)), y) }; } + FI constexpr XYval diff(const XYval &rs) const { return { T(_ABS(x - rs.x)), T(_ABS(y - rs.y)) }; } + // Exact comparisons. For floats a "NEAR" operation may be better. FI bool operator==(const XYval &rs) const { return x == rs.x && y == rs.y; } FI bool operator==(const XYZval &rs) const { return ENABLED(HAS_X_AXIS) XY_GANG(&& x == rs.x, && y == rs.y); } @@ -599,14 +604,19 @@ struct XYZval { FI constexpr XYZval operator- (const XYZEval &rs) const { return NUM_AXIS_ARRAY(x - rs.x, y - rs.y, z - rs.z, i - rs.i, j - rs.j, k - rs.k, u - rs.u, v - rs.v, w - rs.w ); } FI constexpr XYZval operator* (const XYZEval &rs) const { return NUM_AXIS_ARRAY(x * rs.x, y * rs.y, z * rs.z, i * rs.i, j * rs.j, k * rs.k, u * rs.u, v * rs.v, w * rs.w ); } FI constexpr XYZval operator/ (const XYZEval &rs) const { return NUM_AXIS_ARRAY(x / rs.x, y / rs.y, z / rs.z, i / rs.i, j / rs.j, k / rs.k, u / rs.u, v / rs.v, w / rs.w ); } - FI constexpr XYZval operator* (const float &p) const { return NUM_AXIS_ARRAY(x * p, y * p, z * p, i * p, j * p, k * p, u * p, v * p, w * p); } + FI constexpr XYZval operator* (const float &p) const { return NUM_AXIS_ARRAY((T)(x * p), (T)(y * p), (T)(z * p), (T)(i * p), (T)(j * p), (T)(k * p), (T)(u * p), (T)(v * p), (T)(w * p)); } FI constexpr XYZval operator* (const int &p) const { return NUM_AXIS_ARRAY(x * p, y * p, z * p, i * p, j * p, k * p, u * p, v * p, w * p); } - FI constexpr XYZval operator/ (const float &p) const { return NUM_AXIS_ARRAY(x / p, y / p, z / p, i / p, j / p, k / p, u / p, v / p, w / p); } + FI constexpr XYZval operator/ (const float &p) const { return NUM_AXIS_ARRAY((T)(x / p), (T)(y / p), (T)(z / p), (T)(i / p), (T)(j / p), (T)(k / p), (T)(u / p), (T)(v / p), (T)(w / p)); } FI constexpr XYZval operator/ (const int &p) const { return NUM_AXIS_ARRAY(x / p, y / p, z / p, i / p, j / p, k / p, u / p, v / p, w / p); } FI constexpr XYZval operator>>(const int &p) const { return NUM_AXIS_ARRAY(_RS(x), _RS(y), _RS(z), _RS(i), _RS(j), _RS(k), _RS(u), _RS(v), _RS(w)); } FI constexpr XYZval operator<<(const int &p) const { return NUM_AXIS_ARRAY(_LS(x), _LS(y), _LS(z), _LS(i), _LS(j), _LS(k), _LS(u), _LS(v), _LS(w)); } FI constexpr XYZval operator-() const { return NUM_AXIS_ARRAY(-x, -y, -z, -i, -j, -k, -u, -v, -w); } + // Absolute difference between two objects + FI constexpr XYZval diff(const XYZEval &rs) const { return NUM_AXIS_ARRAY(T(_ABS(x - rs.x)), T(_ABS(y - rs.y)), T(_ABS(z - rs.z)), T(_ABS(i - rs.i)), T(_ABS(j - rs.j)), T(_ABS(k - rs.k)), T(_ABS(u - rs.u)), T(_ABS(v - rs.v)), T(_ABS(w - rs.w)) ); } + FI constexpr XYZval diff(const XYZval &rs) const { return NUM_AXIS_ARRAY(T(_ABS(x - rs.x)), T(_ABS(y - rs.y)), T(_ABS(z - rs.z)), T(_ABS(i - rs.i)), T(_ABS(j - rs.j)), T(_ABS(k - rs.k)), T(_ABS(u - rs.u)), T(_ABS(v - rs.v)), T(_ABS(w - rs.w)) ); } + FI constexpr XYZval diff(const XYval &rs) const { return NUM_AXIS_ARRAY(T(_ABS(x - rs.x)), T(_ABS(y - rs.y)), z, i, j, k, u, v, w ); } + // Modifier operators FI XYZval& operator+=(const XYval &rs) { XY_CODE(x += rs.x, y += rs.y); return *this; } FI XYZval& operator-=(const XYval &rs) { XY_CODE(x -= rs.x, y -= rs.y); return *this; } @@ -741,14 +751,19 @@ struct XYZEval { FI constexpr XYZEval operator- (const XYZEval &rs) const { return LOGICAL_AXIS_ARRAY(e - rs.e, x - rs.x, y - rs.y, z - rs.z, i - rs.i, j - rs.j, k - rs.k, u - rs.u, v - rs.v, w - rs.w); } FI constexpr XYZEval operator* (const XYZEval &rs) const { return LOGICAL_AXIS_ARRAY(e * rs.e, x * rs.x, y * rs.y, z * rs.z, i * rs.i, j * rs.j, k * rs.k, u * rs.u, v * rs.v, w * rs.w); } FI constexpr XYZEval operator/ (const XYZEval &rs) const { return LOGICAL_AXIS_ARRAY(e / rs.e, x / rs.x, y / rs.y, z / rs.z, i / rs.i, j / rs.j, k / rs.k, u / rs.u, v / rs.v, w / rs.w); } - FI constexpr XYZEval operator* (const float &p) const { return LOGICAL_AXIS_ARRAY(e * p, x * p, y * p, z * p, i * p, j * p, k * p, u * p, v * p, w * p); } + FI constexpr XYZEval operator* (const float &p) const { return LOGICAL_AXIS_ARRAY((T)(e * p), (T)(x * p), (T)(y * p), (T)(z * p), (T)(i * p), (T)(j * p), (T)(k * p), (T)(u * p), (T)(v * p), (T)(w * p)); } FI constexpr XYZEval operator* (const int &p) const { return LOGICAL_AXIS_ARRAY(e * p, x * p, y * p, z * p, i * p, j * p, k * p, u * p, v * p, w * p); } - FI constexpr XYZEval operator/ (const float &p) const { return LOGICAL_AXIS_ARRAY(e / p, x / p, y / p, z / p, i / p, j / p, k / p, u / p, v / p, w / p); } + FI constexpr XYZEval operator/ (const float &p) const { return LOGICAL_AXIS_ARRAY((T)(e / p), (T)(x / p), (T)(y / p), (T)(z / p), (T)(i / p), (T)(j / p), (T)(k / p), (T)(u / p), (T)(v / p), (T)(w / p)); } FI constexpr XYZEval operator/ (const int &p) const { return LOGICAL_AXIS_ARRAY(e / p, x / p, y / p, z / p, i / p, j / p, k / p, u / p, v / p, w / p); } FI constexpr XYZEval operator>>(const int &p) const { return LOGICAL_AXIS_ARRAY(_RS(e), _RS(x), _RS(y), _RS(z), _RS(i), _RS(j), _RS(k), _RS(u), _RS(v), _RS(w)); } FI constexpr XYZEval operator<<(const int &p) const { return LOGICAL_AXIS_ARRAY(_LS(e), _LS(x), _LS(y), _LS(z), _LS(i), _LS(j), _LS(k), _LS(u), _LS(v), _LS(w)); } FI constexpr XYZEval operator-() const { return LOGICAL_AXIS_ARRAY(-e, -x, -y, -z, -i, -j, -k, -u, -v, -w); } + // Absolute difference between two objects + FI constexpr XYZEval diff(const XYZEval &rs) const { return LOGICAL_AXIS_ARRAY(T(_ABS(e - rs.e)), T(_ABS(x - rs.x)), T(_ABS(y - rs.y)), T(_ABS(z - rs.z)), T(_ABS(i - rs.i)), T(_ABS(j - rs.j)), T(_ABS(k - rs.k)), T(_ABS(u - rs.u)), T(_ABS(v - rs.v)), T(_ABS(w - rs.w)) ); } + FI constexpr XYZEval diff(const XYZval &rs) const { return LOGICAL_AXIS_ARRAY(0 , T(_ABS(x - rs.x)), T(_ABS(y - rs.y)), T(_ABS(z - rs.z)), T(_ABS(i - rs.i)), T(_ABS(j - rs.j)), T(_ABS(k - rs.k)), T(_ABS(u - rs.u)), T(_ABS(v - rs.v)), T(_ABS(w - rs.w)) ); } + FI constexpr XYZEval diff(const XYval &rs) const { return LOGICAL_AXIS_ARRAY(0 , T(_ABS(x - rs.x)), T(_ABS(y - rs.y)), z, i, j, k, u, v, w ); } + // Modifier operators FI XYZEval& operator+=(const XYval &rs) { XY_CODE(x += rs.x, y += rs.y); return *this; } FI XYZEval& operator-=(const XYval &rs) { XY_CODE(x -= rs.x, y -= rs.y); return *this; } diff --git a/Marlin/src/feature/babystep.cpp b/Marlin/src/feature/babystep.cpp index c8c1d42f886b..e431e40165ff 100644 --- a/Marlin/src/feature/babystep.cpp +++ b/Marlin/src/feature/babystep.cpp @@ -42,7 +42,7 @@ volatile int16_t Babystep::steps[BS_AXIS_IND(Z_AXIS) + 1]; #endif int16_t Babystep::accum; -#if BOTH(EP_BABYSTEPPING, EMERGENCY_PARSER) +#if ALL(EP_BABYSTEPPING, EMERGENCY_PARSER) int16_t Babystep::ep_babysteps; #endif diff --git a/Marlin/src/feature/babystep.h b/Marlin/src/feature/babystep.h index 1e319ec5446d..df88da6e147a 100644 --- a/Marlin/src/feature/babystep.h +++ b/Marlin/src/feature/babystep.h @@ -31,7 +31,7 @@ #define BABYSTEP_TICKS ((TEMP_TIMER_RATE) / (BABYSTEPS_PER_SEC)) #endif -#if IS_CORE || EITHER(BABYSTEP_XY, I2C_POSITION_ENCODERS) +#if ANY(IS_CORE, BABYSTEP_XY, I2C_POSITION_ENCODERS) #define BS_AXIS_IND(A) A #define BS_AXIS(I) AxisEnum(I) #else @@ -52,7 +52,7 @@ class Babystep { static volatile int16_t steps[BS_AXIS_IND(Z_AXIS) + 1]; static int16_t accum; // Total babysteps in current edit - #if BOTH(EP_BABYSTEPPING, EMERGENCY_PARSER) + #if ALL(EP_BABYSTEPPING, EMERGENCY_PARSER) static int16_t ep_babysteps; #endif @@ -95,7 +95,7 @@ class Babystep { // apply accumulated babysteps to the axes. // static void task() { - LOOP_LE_N(i, BS_AXIS_IND(Z_AXIS)) step_axis(BS_AXIS(i)); + for (uint8_t i = 0; i <= BS_AXIS_IND(Z_AXIS); ++i) step_axis(BS_AXIS(i)); } private: diff --git a/Marlin/src/feature/backlash.cpp b/Marlin/src/feature/backlash.cpp index 8d180c7a4a3e..c6eb0d33f309 100644 --- a/Marlin/src/feature/backlash.cpp +++ b/Marlin/src/feature/backlash.cpp @@ -66,7 +66,7 @@ Backlash backlash; void Backlash::add_correction_steps(const int32_t &da, const int32_t &db, const int32_t &dc, const AxisBits dm, block_t * const block) { AxisBits changed_dir = last_direction_bits ^ dm; // Ignore direction change unless steps are taken in that direction - #if DISABLED(CORE_BACKLASH) || EITHER(MARKFORGED_XY, MARKFORGED_YX) + #if DISABLED(CORE_BACKLASH) || ANY(MARKFORGED_XY, MARKFORGED_YX) if (!da) changed_dir.x = false; if (!db) changed_dir.y = false; if (!dc) changed_dir.z = false; diff --git a/Marlin/src/feature/bedlevel/abl/bbl.cpp b/Marlin/src/feature/bedlevel/abl/bbl.cpp index 6ef3945fa52c..14c4bd24bcf0 100644 --- a/Marlin/src/feature/bedlevel/abl/bbl.cpp +++ b/Marlin/src/feature/bedlevel/abl/bbl.cpp @@ -133,8 +133,8 @@ void LevelingBilinear::extrapolate_unprobed_bed_level() { yend = ctry1; #endif - LOOP_LE_N(xo, xend) - LOOP_LE_N(yo, yend) { + for (uint8_t xo = 0; xo <= xend; ++xo) + for (uint8_t yo = 0; yo <= yend; ++yo) { uint8_t x2 = ctrx2 + xo, y2 = ctry2 + yo; #ifndef HALF_IN_X const uint8_t x1 = ctrx1 - xo; @@ -231,8 +231,8 @@ void LevelingBilinear::print_leveling_grid(const bed_mesh_t* _z_values/*=nullptr float LevelingBilinear::virt_2cmr(const uint8_t x, const uint8_t y, const_float_t tx, const_float_t ty) { float row[4], column[4]; - LOOP_L_N(i, 4) { - LOOP_L_N(j, 4) { + for (uint8_t i = 0; i < 4; ++i) { + for (uint8_t j = 0; j < 4; ++j) { column[j] = virt_coord(i + x - 1, j + y - 1); } row[i] = virt_cmr(column, 1, ty); @@ -243,10 +243,10 @@ void LevelingBilinear::print_leveling_grid(const bed_mesh_t* _z_values/*=nullptr void LevelingBilinear::subdivide_mesh() { grid_spacing_virt = grid_spacing / (BILINEAR_SUBDIVISIONS); grid_factor_virt = grid_spacing_virt.reciprocal(); - LOOP_L_N(y, GRID_MAX_POINTS_Y) - LOOP_L_N(x, GRID_MAX_POINTS_X) - LOOP_L_N(ty, BILINEAR_SUBDIVISIONS) - LOOP_L_N(tx, BILINEAR_SUBDIVISIONS) { + for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; ++y) + for (uint8_t x = 0; x < GRID_MAX_POINTS_X; ++x) + for (uint8_t ty = 0; ty < BILINEAR_SUBDIVISIONS; ++ty) + for (uint8_t tx = 0; tx < BILINEAR_SUBDIVISIONS; ++tx) { if ((ty && y == (GRID_MAX_POINTS_Y) - 1) || (tx && x == (GRID_MAX_POINTS_X) - 1)) continue; z_values_virt[x * (BILINEAR_SUBDIVISIONS) + tx][y * (BILINEAR_SUBDIVISIONS) + ty] = diff --git a/Marlin/src/feature/bedlevel/bedlevel.cpp b/Marlin/src/feature/bedlevel/bedlevel.cpp index 03b67745ec16..17407eafb958 100644 --- a/Marlin/src/feature/bedlevel/bedlevel.cpp +++ b/Marlin/src/feature/bedlevel/bedlevel.cpp @@ -27,7 +27,7 @@ #include "bedlevel.h" #include "../../module/planner.h" -#if EITHER(MESH_BED_LEVELING, PROBE_MANUALLY) +#if ANY(MESH_BED_LEVELING, PROBE_MANUALLY) #include "../../module/motion.h" #endif @@ -120,7 +120,7 @@ void reset_bed_level() { TERN_(ABL_PLANAR, planner.bed_level_matrix.set_to_identity()); } -#if EITHER(AUTO_BED_LEVELING_BILINEAR, MESH_BED_LEVELING) +#if ANY(AUTO_BED_LEVELING_BILINEAR, MESH_BED_LEVELING) /** * Enable to produce output in JSON format suitable @@ -137,7 +137,7 @@ void reset_bed_level() { */ void print_2d_array(const uint8_t sx, const uint8_t sy, const uint8_t precision, const float *values) { #ifndef SCAD_MESH_OUTPUT - LOOP_L_N(x, sx) { + for (uint8_t x = 0; x < sx; ++x) { serial_spaces(precision + (x < 10 ? 3 : 2)); SERIAL_ECHO(x); } @@ -146,14 +146,14 @@ void reset_bed_level() { #ifdef SCAD_MESH_OUTPUT SERIAL_ECHOLNPGM("measured_z = ["); // open 2D array #endif - LOOP_L_N(y, sy) { + for (uint8_t y = 0; y < sy; ++y) { #ifdef SCAD_MESH_OUTPUT SERIAL_ECHOPGM(" ["); // open sub-array #else if (y < 10) SERIAL_CHAR(' '); SERIAL_ECHO(y); #endif - LOOP_L_N(x, sx) { + for (uint8_t x = 0; x < sx; ++x) { SERIAL_CHAR(' '); const float offset = values[x * sy + y]; if (!isnan(offset)) { @@ -166,7 +166,7 @@ void reset_bed_level() { SERIAL_CHAR(' '); SERIAL_ECHOPGM("NAN"); #else - LOOP_L_N(i, precision + 3) + for (uint8_t i = 0; i < precision + 3; ++i) SERIAL_CHAR(i ? '=' : ' '); #endif } @@ -188,7 +188,7 @@ void reset_bed_level() { #endif // AUTO_BED_LEVELING_BILINEAR || MESH_BED_LEVELING -#if EITHER(MESH_BED_LEVELING, PROBE_MANUALLY) +#if ANY(MESH_BED_LEVELING, PROBE_MANUALLY) void _manual_goto_xy(const xy_pos_t &pos) { diff --git a/Marlin/src/feature/bedlevel/bedlevel.h b/Marlin/src/feature/bedlevel/bedlevel.h index aeafec10d6ab..ccb9543e72e5 100644 --- a/Marlin/src/feature/bedlevel/bedlevel.h +++ b/Marlin/src/feature/bedlevel/bedlevel.h @@ -23,7 +23,7 @@ #include "../../inc/MarlinConfigPre.h" -#if EITHER(RESTORE_LEVELING_AFTER_G28, ENABLE_LEVELING_AFTER_G28) +#if ANY(RESTORE_LEVELING_AFTER_G28, ENABLE_LEVELING_AFTER_G28) #define CAN_SET_LEVELING_AFTER_G28 1 #endif @@ -41,7 +41,7 @@ void reset_bed_level(); void set_z_fade_height(const_float_t zfh, const bool do_report=true); #endif -#if EITHER(MESH_BED_LEVELING, PROBE_MANUALLY) +#if ANY(MESH_BED_LEVELING, PROBE_MANUALLY) void _manual_goto_xy(const xy_pos_t &pos); #endif @@ -69,7 +69,7 @@ class TemporaryBedLevelingState { #include "mbl/mesh_bed_leveling.h" #endif - #if EITHER(AUTO_BED_LEVELING_BILINEAR, MESH_BED_LEVELING) + #if ANY(AUTO_BED_LEVELING_BILINEAR, MESH_BED_LEVELING) #include diff --git a/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.cpp b/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.cpp index 193cbbf7654a..787827bb9bfc 100644 --- a/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.cpp +++ b/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.cpp @@ -40,9 +40,9 @@ mesh_bed_leveling::index_to_ypos[GRID_MAX_POINTS_Y]; mesh_bed_leveling::mesh_bed_leveling() { - LOOP_L_N(i, GRID_MAX_POINTS_X) + for (uint8_t i = 0; i < GRID_MAX_POINTS_X; ++i) index_to_xpos[i] = MESH_MIN_X + i * (MESH_X_DIST); - LOOP_L_N(i, GRID_MAX_POINTS_Y) + for (uint8_t i = 0; i < GRID_MAX_POINTS_Y; ++i) index_to_ypos[i] = MESH_MIN_Y + i * (MESH_Y_DIST); reset(); } diff --git a/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.h b/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.h index 0193b4f43e5b..cb4f36cd59f2 100644 --- a/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.h +++ b/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.h @@ -72,18 +72,18 @@ class mesh_bed_leveling { static float get_mesh_x(const uint8_t i) { return index_to_xpos[i]; } static float get_mesh_y(const uint8_t i) { return index_to_ypos[i]; } - static int8_t cell_index_x(const_float_t x) { + static uint8_t cell_index_x(const_float_t x) { int8_t cx = (x - (MESH_MIN_X)) * RECIPROCAL(MESH_X_DIST); return constrain(cx, 0, GRID_MAX_CELLS_X - 1); } - static int8_t cell_index_y(const_float_t y) { + static uint8_t cell_index_y(const_float_t y) { int8_t cy = (y - (MESH_MIN_Y)) * RECIPROCAL(MESH_Y_DIST); return constrain(cy, 0, GRID_MAX_CELLS_Y - 1); } - static xy_int8_t cell_indexes(const_float_t x, const_float_t y) { + static xy_uint8_t cell_indexes(const_float_t x, const_float_t y) { return { cell_index_x(x), cell_index_y(y) }; } - static xy_int8_t cell_indexes(const xy_pos_t &xy) { return cell_indexes(xy.x, xy.y); } + static xy_uint8_t cell_indexes(const xy_pos_t &xy) { return cell_indexes(xy.x, xy.y); } static int8_t probe_index_x(const_float_t x) { int8_t px = (x - (MESH_MIN_X) + 0.5f * (MESH_X_DIST)) * RECIPROCAL(MESH_X_DIST); @@ -107,7 +107,7 @@ class mesh_bed_leveling { static float get_z_offset() { return z_offset; } static float get_z_correction(const xy_pos_t &pos) { - const xy_int8_t ind = cell_indexes(pos); + const xy_uint8_t ind = cell_indexes(pos); const float x1 = index_to_xpos[ind.x], x2 = index_to_xpos[ind.x+1], y1 = index_to_ypos[ind.y], y2 = index_to_ypos[ind.y+1], z1 = calc_z0(pos.x, x1, z_values[ind.x][ind.y ], x2, z_values[ind.x+1][ind.y ]), diff --git a/Marlin/src/feature/bedlevel/ubl/ubl.cpp b/Marlin/src/feature/bedlevel/ubl/ubl.cpp index ca519f86b49d..b99334795d13 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl.cpp @@ -149,7 +149,7 @@ static void serial_echo_xy(const uint8_t sp, const int16_t x, const int16_t y) { static void serial_echo_column_labels(const uint8_t sp) { SERIAL_ECHO_SP(7); - LOOP_L_N(i, GRID_MAX_POINTS_X) { + for (uint8_t i = 0; i < GRID_MAX_POINTS_X; ++i) { if (i < 10) SERIAL_CHAR(' '); SERIAL_ECHO(i); SERIAL_ECHO_SP(sp); @@ -199,7 +199,7 @@ void unified_bed_leveling::display_map(const uint8_t map_type) { } // Row Values (I indexes) - LOOP_L_N(i, GRID_MAX_POINTS_X) { + for (uint8_t i = 0; i < GRID_MAX_POINTS_X; ++i) { // Opening Brace or Space const bool is_current = i == curr.x && j == curr.y; diff --git a/Marlin/src/feature/bedlevel/ubl/ubl.h b/Marlin/src/feature/bedlevel/ubl/ubl.h index 785cb5d883aa..c9bc7974296c 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl.h +++ b/Marlin/src/feature/bedlevel/ubl/ubl.h @@ -141,26 +141,26 @@ class unified_bed_leveling { return FLOOR((y - (MESH_MIN_Y)) * RECIPROCAL(MESH_Y_DIST)); } - static int8_t cell_index_x_valid(const_float_t x) { + static bool cell_index_x_valid(const_float_t x) { return WITHIN(cell_index_x_raw(x), 0, GRID_MAX_CELLS_X - 1); } - static int8_t cell_index_y_valid(const_float_t y) { + static bool cell_index_y_valid(const_float_t y) { return WITHIN(cell_index_y_raw(y), 0, GRID_MAX_CELLS_Y - 1); } - static int8_t cell_index_x(const_float_t x) { + static uint8_t cell_index_x(const_float_t x) { return constrain(cell_index_x_raw(x), 0, GRID_MAX_CELLS_X - 1); } - static int8_t cell_index_y(const_float_t y) { + static uint8_t cell_index_y(const_float_t y) { return constrain(cell_index_y_raw(y), 0, GRID_MAX_CELLS_Y - 1); } - static xy_int8_t cell_indexes(const_float_t x, const_float_t y) { + static xy_uint8_t cell_indexes(const_float_t x, const_float_t y) { return { cell_index_x(x), cell_index_y(y) }; } - static xy_int8_t cell_indexes(const xy_pos_t &xy) { return cell_indexes(xy.x, xy.y); } + static xy_uint8_t cell_indexes(const xy_pos_t &xy) { return cell_indexes(xy.x, xy.y); } static int8_t closest_x_index(const_float_t x) { const int8_t px = (x - (MESH_MIN_X) + (MESH_X_DIST) * 0.5) * RECIPROCAL(MESH_X_DIST); diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index ecbf76ec6ed6..551277c35d1c 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -396,7 +396,7 @@ void unified_bed_leveling::G29() { break; case 1: - LOOP_L_N(x, GRID_MAX_POINTS_X) { // Create a diagonal line several Mesh cells thick that is raised + for (uint8_t x = 0; x < GRID_MAX_POINTS_X; ++x) { // Create a diagonal line several Mesh cells thick that is raised const uint8_t x2 = x + (x < (GRID_MAX_POINTS_Y) - 1 ? 1 : -1); z_values[x][x] += 9.999f; z_values[x][x2] += 9.999f; // We want the altered line several mesh points thick @@ -1445,7 +1445,7 @@ void unified_bed_leveling::smart_fill_mesh() { info3 PROGMEM = { (GRID_MAX_POINTS_X) - 1, 0, 0, GRID_MAX_POINTS_Y, true }; // Right side of the mesh looking left static const smart_fill_info * const info[] PROGMEM = { &info0, &info1, &info2, &info3 }; - LOOP_L_N(i, COUNT(info)) { + for (uint8_t i = 0; i < COUNT(info); ++i) { const smart_fill_info *f = (smart_fill_info*)pgm_read_ptr(&info[i]); const int8_t sx = pgm_read_byte(&f->sx), sy = pgm_read_byte(&f->sy), ex = pgm_read_byte(&f->ex), ey = pgm_read_byte(&f->ey); @@ -1484,7 +1484,7 @@ void unified_bed_leveling::smart_fill_mesh() { #if ENABLED(UBL_TILT_ON_MESH_POINTS_3POINT) mesh_index_pair cpos[3]; - LOOP_L_N(ix, 3) { // Convert points to coordinates of mesh points + for (uint8_t ix = 0; ix < 3; ++ix) { // Convert points to coordinates of mesh points cpos[ix] = find_closest_mesh_point_of_type(REAL, points[ix], true); points[ix] = cpos[ix].meshpos(); } @@ -1494,7 +1494,7 @@ void unified_bed_leveling::smart_fill_mesh() { float gotz[3]; // Used for algorithm validation below #endif - LOOP_L_N(i, 3) { + for (uint8_t i = 0; i < 3; ++i) { SERIAL_ECHOLNPGM("Tilting mesh (", i + 1, "/3)"); TERN_(HAS_STATUS_MESSAGE, ui.status_printf(0, F(S_FMT " %i/3"), GET_TEXT(MSG_LCD_TILTING_MESH), i + 1)); @@ -1534,10 +1534,10 @@ void unified_bed_leveling::smart_fill_mesh() { const uint16_t total_points = sq(param.J_grid_size); uint16_t point_num = 1; - LOOP_L_N(ix, param.J_grid_size) { + for (uint8_t ix = 0; ix < param.J_grid_size; ++ix) { xy_pos_t rpos; rpos.x = x_min + ix * dx; - LOOP_L_N(iy, param.J_grid_size) { + for (uint8_t iy = 0; iy < param.J_grid_size; ++iy) { rpos.y = y_min + dy * (zig_zag ? param.J_grid_size - 1 - iy : iy); #if ENABLED(UBL_TILT_ON_MESH_POINTS) @@ -1714,17 +1714,17 @@ void unified_bed_leveling::smart_fill_mesh() { GRID_LOOP(jx, jy) if (!isnan(z_values[jx][jy])) SBI(bitmap[jx], jy); xy_pos_t ppos; - LOOP_L_N(ix, GRID_MAX_POINTS_X) { + for (uint8_t ix = 0; ix < GRID_MAX_POINTS_X; ++ix) { ppos.x = get_mesh_x(ix); - LOOP_L_N(iy, GRID_MAX_POINTS_Y) { + for (uint8_t iy = 0; iy < GRID_MAX_POINTS_Y; ++iy) { ppos.y = get_mesh_y(iy); if (isnan(z_values[ix][iy])) { // undefined mesh point at (ppos.x,ppos.y), compute weighted LSF from original valid mesh points. incremental_LSF_reset(&lsf_results); xy_pos_t rpos; - LOOP_L_N(jx, GRID_MAX_POINTS_X) { + for (uint8_t jx = 0; jx < GRID_MAX_POINTS_X; ++jx) { rpos.x = get_mesh_x(jx); - LOOP_L_N(jy, GRID_MAX_POINTS_Y) { + for (uint8_t jy = 0; jy < GRID_MAX_POINTS_Y; ++jy) { if (TEST(bitmap[jx], jy)) { rpos.y = get_mesh_y(jy); const float rz = z_values[jx][jy], @@ -1784,7 +1784,7 @@ void unified_bed_leveling::smart_fill_mesh() { SERIAL_ECHOLNPGM("MESH_Y_DIST ", MESH_Y_DIST); serial_delay(50); SERIAL_ECHOPGM("X-Axis Mesh Points at: "); - LOOP_L_N(i, GRID_MAX_POINTS_X) { + for (uint8_t i = 0; i < GRID_MAX_POINTS_X; ++i) { SERIAL_ECHO_F(LOGICAL_X_POSITION(get_mesh_x(i)), 3); SERIAL_ECHOPGM(" "); serial_delay(25); @@ -1792,7 +1792,7 @@ void unified_bed_leveling::smart_fill_mesh() { SERIAL_EOL(); SERIAL_ECHOPGM("Y-Axis Mesh Points at: "); - LOOP_L_N(i, GRID_MAX_POINTS_Y) { + for (uint8_t i = 0; i < GRID_MAX_POINTS_Y; ++i) { SERIAL_ECHO_F(LOGICAL_Y_POSITION(get_mesh_y(i)), 3); SERIAL_ECHOPGM(" "); serial_delay(25); diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp index 1a2b6eb23abd..053a68b77d78 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp @@ -61,7 +61,7 @@ const xyze_pos_t &start = current_position, &end = destination; #endif - const xy_int8_t istart = cell_indexes(start), iend = cell_indexes(end); + const xy_uint8_t istart = cell_indexes(start), iend = cell_indexes(end); // A move within the same cell needs no splitting if (istart == iend) { @@ -108,7 +108,7 @@ const xy_float_t dist = end - start; const xy_bool_t neg { dist.x < 0, dist.y < 0 }; - const xy_int8_t ineg { int8_t(neg.x), int8_t(neg.y) }; + const xy_uint8_t ineg { uint8_t(neg.x), uint8_t(neg.y) }; const xy_float_t sign { neg.x ? -1.0f : 1.0f, neg.y ? -1.0f : 1.0f }; const xy_int8_t iadd { int8_t(iend.x == istart.x ? 0 : sign.x), int8_t(iend.y == istart.y ? 0 : sign.y) }; @@ -131,7 +131,7 @@ const bool inf_normalized_flag = isinf(e_normalized_dist); #endif - xy_int8_t icell = istart; + xy_uint8_t icell = istart; const float ratio = dist.y / dist.x, // Allow divide by zero c = start.y - ratio * start.x; @@ -252,7 +252,7 @@ * Generic case of a line crossing both X and Y Mesh lines. */ - xy_int8_t cnt = (istart - iend).ABS(); + xy_uint8_t cnt = istart.diff(iend); icell += ineg; diff --git a/Marlin/src/feature/cancel_object.cpp b/Marlin/src/feature/cancel_object.cpp index bffd2bb72020..9b658315ed8b 100644 --- a/Marlin/src/feature/cancel_object.cpp +++ b/Marlin/src/feature/cancel_object.cpp @@ -44,7 +44,7 @@ void CancelObject::set_active_object(const int8_t obj) { else skipping = false; - #if BOTH(HAS_STATUS_MESSAGE, CANCEL_OBJECTS_REPORTING) + #if ALL(HAS_STATUS_MESSAGE, CANCEL_OBJECTS_REPORTING) if (active_object >= 0) ui.status_printf(0, F(S_FMT " %i"), GET_TEXT(MSG_PRINTING_OBJECT), int(active_object)); else diff --git a/Marlin/src/feature/cooler.cpp b/Marlin/src/feature/cooler.cpp index e0f99777d19a..6c45e992262e 100644 --- a/Marlin/src/feature/cooler.cpp +++ b/Marlin/src/feature/cooler.cpp @@ -22,7 +22,7 @@ #include "../inc/MarlinConfig.h" -#if EITHER(HAS_COOLER, LASER_COOLANT_FLOW_METER) +#if ANY(HAS_COOLER, LASER_COOLANT_FLOW_METER) #include "cooler.h" Cooler cooler; diff --git a/Marlin/src/feature/digipot/digipot_mcp4018.cpp b/Marlin/src/feature/digipot/digipot_mcp4018.cpp index 3f2ecbfcdc0b..f776c5a33901 100644 --- a/Marlin/src/feature/digipot/digipot_mcp4018.cpp +++ b/Marlin/src/feature/digipot/digipot_mcp4018.cpp @@ -89,7 +89,7 @@ void DigipotI2C::set_current(const uint8_t channel, const float current) { } void DigipotI2C::init() { - LOOP_L_N(i, DIGIPOT_I2C_NUM_CHANNELS) pots[i].i2c_init(); + for (uint8_t i = 0; i < DIGIPOT_I2C_NUM_CHANNELS; ++i) pots[i].i2c_init(); // Init currents according to Configuration_adv.h static const float digipot_motor_current[] PROGMEM = @@ -99,7 +99,7 @@ void DigipotI2C::init() { DIGIPOT_I2C_MOTOR_CURRENTS #endif ; - LOOP_L_N(i, COUNT(digipot_motor_current)) + for (uint8_t i = 0; i < COUNT(digipot_motor_current); ++i) set_current(i, pgm_read_float(&digipot_motor_current[i])); } diff --git a/Marlin/src/feature/digipot/digipot_mcp4451.cpp b/Marlin/src/feature/digipot/digipot_mcp4451.cpp index ba5ecdad050a..7416fe9f8d5c 100644 --- a/Marlin/src/feature/digipot/digipot_mcp4451.cpp +++ b/Marlin/src/feature/digipot/digipot_mcp4451.cpp @@ -94,7 +94,7 @@ void DigipotI2C::init() { DIGIPOT_I2C_MOTOR_CURRENTS #endif ; - LOOP_L_N(i, COUNT(digipot_motor_current)) + for (uint8_t i = 0; i < COUNT(digipot_motor_current); ++i) set_current(i, pgm_read_float(&digipot_motor_current[i])); } diff --git a/Marlin/src/feature/encoder_i2c.cpp b/Marlin/src/feature/encoder_i2c.cpp index b1ff21cf92c7..1c01e1c23b5e 100644 --- a/Marlin/src/feature/encoder_i2c.cpp +++ b/Marlin/src/feature/encoder_i2c.cpp @@ -138,7 +138,7 @@ void I2CPositionEncoder::update() { errIdx = (errIdx >= I2CPE_ERR_ARRAY_SIZE - 1) ? 0 : errIdx + 1; err[errIdx] = get_axis_error_steps(false); - LOOP_L_N(i, I2CPE_ERR_ARRAY_SIZE) { + for (uint8_t i = 0; i < I2CPE_ERR_ARRAY_SIZE; ++i) { sum += err[i]; if (i) diffSum += ABS(err[i-1] - err[i]); } @@ -170,7 +170,7 @@ void I2CPositionEncoder::update() { errPrst[errPrstIdx++] = error; // Error must persist for I2CPE_ERR_PRST_ARRAY_SIZE error cycles. This also serves to improve the average accuracy if (errPrstIdx >= I2CPE_ERR_PRST_ARRAY_SIZE) { float sumP = 0; - LOOP_L_N(i, I2CPE_ERR_PRST_ARRAY_SIZE) sumP += errPrst[i]; + for (uint8_t i = 0; i < I2CPE_ERR_PRST_ARRAY_SIZE; ++i) sumP += errPrst[i]; const int32_t errorP = int32_t(sumP * RECIPROCAL(I2CPE_ERR_PRST_ARRAY_SIZE)); SERIAL_CHAR(AXIS_CHAR(encoderAxis)); SERIAL_ECHOLNPGM(" : CORRECT ERR ", errorP * planner.mm_per_step[encoderAxis], "mm"); @@ -404,7 +404,7 @@ void I2CPositionEncoder::calibrate_steps_mm(const uint8_t iter) { planner.synchronize(); - LOOP_L_N(i, iter) { + for (uint8_t i = 0; i < iter; ++i) { TERN_(HAS_EXTRUDERS, startCoord.e = planner.get_axis_position_mm(E_AXIS)); planner.buffer_line(startCoord, fr_mm_s, 0); planner.synchronize(); diff --git a/Marlin/src/feature/encoder_i2c.h b/Marlin/src/feature/encoder_i2c.h index f25fe2ea6bc4..1ae05d1433b3 100644 --- a/Marlin/src/feature/encoder_i2c.h +++ b/Marlin/src/feature/encoder_i2c.h @@ -90,7 +90,7 @@ #define I2CPE_PARSE_ERR 1 #define I2CPE_PARSE_OK 0 -#define LOOP_PE(VAR) LOOP_L_N(VAR, I2CPE_ENCODER_CNT) +#define LOOP_PE(VAR) for (uint8_t VAR = 0; VAR < I2CPE_ENCODER_CNT; ++VAR) #define CHECK_IDX() do{ if (!WITHIN(idx, 0, I2CPE_ENCODER_CNT - 1)) return; }while(0) typedef union { diff --git a/Marlin/src/feature/fancheck.cpp b/Marlin/src/feature/fancheck.cpp index 126b79b0a409..844191e7e442 100644 --- a/Marlin/src/feature/fancheck.cpp +++ b/Marlin/src/feature/fancheck.cpp @@ -72,7 +72,7 @@ void FanCheck::update_tachometers() { bool status; #define _TACHO_CASE(N) case N: status = READ(E##N##_FAN_TACHO_PIN); break; - LOOP_L_N(f, TACHO_COUNT) { + for (uint8_t f = 0; f < TACHO_COUNT; ++f) { switch (f) { #if HAS_E0_FAN_TACHO _TACHO_CASE(0) @@ -113,7 +113,7 @@ void FanCheck::compute_speed(uint16_t elapsedTime) { static uint8_t fan_reported_errors_msk = 0; uint8_t fan_error_msk = 0; - LOOP_L_N(f, TACHO_COUNT) { + for (uint8_t f = 0; f < TACHO_COUNT; ++f) { switch (f) { TERN_(HAS_E0_FAN_TACHO, case 0:) TERN_(HAS_E1_FAN_TACHO, case 1:) @@ -150,7 +150,7 @@ void FanCheck::compute_speed(uint16_t elapsedTime) { if (fan_error_msk & ~fan_reported_errors_msk) { // Handle new faults only - LOOP_L_N(f, TACHO_COUNT) if (TEST(fan_error_msk, f)) report_speed_error(f); + for (uint8_t f = 0; f < TACHO_COUNT; ++f) if (TEST(fan_error_msk, f)) report_speed_error(f); } fan_reported_errors_msk = fan_error_msk; } @@ -176,8 +176,8 @@ void FanCheck::report_speed_error(uint8_t fan) { } void FanCheck::print_fan_states() { - LOOP_L_N(s, 2) { - LOOP_L_N(f, TACHO_COUNT) { + for (uint8_t s = 0; s < 2; ++s) { + for (uint8_t f = 0; f < TACHO_COUNT; ++f) { switch (f) { TERN_(HAS_E0_FAN_TACHO, case 0:) TERN_(HAS_E1_FAN_TACHO, case 1:) diff --git a/Marlin/src/feature/filwidth.cpp b/Marlin/src/feature/filwidth.cpp index 2bd9c789808e..3befd7752a6e 100644 --- a/Marlin/src/feature/filwidth.cpp +++ b/Marlin/src/feature/filwidth.cpp @@ -42,7 +42,7 @@ int8_t FilamentWidthSensor::ratios[MAX_MEASUREMENT_DELAY + 1], // Ring void FilamentWidthSensor::init() { const int8_t ratio = sample_to_size_ratio(); - LOOP_L_N(i, COUNT(ratios)) ratios[i] = ratio; + for (uint8_t i = 0; i < COUNT(ratios); ++i) ratios[i] = ratio; index_r = index_w = 0; } diff --git a/Marlin/src/feature/host_actions.cpp b/Marlin/src/feature/host_actions.cpp index a1c1bad5bb44..235253b5a345 100644 --- a/Marlin/src/feature/host_actions.cpp +++ b/Marlin/src/feature/host_actions.cpp @@ -187,13 +187,13 @@ void HostUI::action(FSTR_P const fstr, const bool eol) { switch (response) { case 0: // "Purge More" button - #if BOTH(M600_PURGE_MORE_RESUMABLE, ADVANCED_PAUSE_FEATURE) + #if ALL(M600_PURGE_MORE_RESUMABLE, ADVANCED_PAUSE_FEATURE) pause_menu_response = PAUSE_RESPONSE_EXTRUDE_MORE; // Simulate menu selection (menu exits, doesn't extrude more) #endif break; case 1: // "Continue" / "Disable Runout" button - #if BOTH(M600_PURGE_MORE_RESUMABLE, ADVANCED_PAUSE_FEATURE) + #if ALL(M600_PURGE_MORE_RESUMABLE, ADVANCED_PAUSE_FEATURE) pause_menu_response = PAUSE_RESPONSE_RESUME_PRINT; // Simulate menu selection #endif #if HAS_FILAMENT_SENSOR @@ -209,7 +209,7 @@ void HostUI::action(FSTR_P const fstr, const bool eol) { TERN_(HAS_RESUME_CONTINUE, wait_for_user = false); break; case PROMPT_PAUSE_RESUME: - #if BOTH(ADVANCED_PAUSE_FEATURE, HAS_MEDIA) + #if ALL(ADVANCED_PAUSE_FEATURE, HAS_MEDIA) extern const char M24_STR[]; queue.inject_P(M24_STR); #endif diff --git a/Marlin/src/feature/leds/leds.cpp b/Marlin/src/feature/leds/leds.cpp index 94900445dcbc..7305581cd046 100644 --- a/Marlin/src/feature/leds/leds.cpp +++ b/Marlin/src/feature/leds/leds.cpp @@ -30,7 +30,7 @@ #include "leds.h" -#if EITHER(CASE_LIGHT_USE_RGB_LED, CASE_LIGHT_USE_NEOPIXEL) +#if ANY(CASE_LIGHT_USE_RGB_LED, CASE_LIGHT_USE_NEOPIXEL) #include "../../feature/caselight.h" #endif @@ -50,7 +50,7 @@ LEDLights leds; void LEDLights::setup() { - #if EITHER(RGB_LED, RGBW_LED) + #if ANY(RGB_LED, RGBW_LED) if (PWM_PIN(RGB_LED_R_PIN)) SET_PWM(RGB_LED_R_PIN); else SET_OUTPUT(RGB_LED_R_PIN); if (PWM_PIN(RGB_LED_G_PIN)) SET_PWM(RGB_LED_G_PIN); else SET_OUTPUT(RGB_LED_G_PIN); if (PWM_PIN(RGB_LED_B_PIN)) SET_PWM(RGB_LED_B_PIN); else SET_OUTPUT(RGB_LED_B_PIN); @@ -76,8 +76,8 @@ void LEDLights::setup() { #endif delay(200); - LOOP_L_N(i, led_pin_count) { - LOOP_LE_N(b, 200) { + for (uint8_t i = 0; i < led_pin_count; ++i) { + for (uint8_t b = 0; b <= 200; ++b) { const uint16_t led_pwm = b <= 100 ? b : 200 - b; if (i == 0 && PWM_PIN(RGB_LED_R_PIN)) hal.set_pwm_duty(pin_t(RGB_LED_R_PIN), led_pwm); else WRITE(RGB_LED_R_PIN, b < 100 ? HIGH : LOW); if (i == 1 && PWM_PIN(RGB_LED_G_PIN)) hal.set_pwm_duty(pin_t(RGB_LED_G_PIN), led_pwm); else WRITE(RGB_LED_G_PIN, b < 100 ? HIGH : LOW); @@ -96,7 +96,7 @@ void LEDLights::setup() { } #endif // RGB_STARTUP_TEST - #elif BOTH(PCA9632, RGB_STARTUP_TEST) // PCA9632 RGB_STARTUP_TEST + #elif ALL(PCA9632, RGB_STARTUP_TEST) // PCA9632 RGB_STARTUP_TEST constexpr int8_t led_pin_count = TERN(HAS_WHITE_LED, 4, 3); @@ -118,7 +118,7 @@ void LEDLights::setup() { while (led_pin_counters[0] != 99 || !canEnd) { if (led_pin_counters[0] == 99) // End loop next time pin0 counter is 99 canEnd = true; - LOOP_L_N(i, led_pin_count) { + for (uint8_t i = 0; i < led_pin_count; ++i) { if (led_pin_counters[i] > 0) { if (++led_pin_counters[i] == 400) // turn off current pin counter in led_pin_counters led_pin_counters[i] = 0; @@ -140,7 +140,7 @@ void LEDLights::setup() { } // Fade to white - LOOP_LE_N(led_pwm, 100) { + for (uint8_t led_pwm = 0; led_pwm <= 100; ++led_pwm) { NOLESS(curColor.r, led_pwm); NOLESS(curColor.g, led_pwm); NOLESS(curColor.b, led_pwm); @@ -176,7 +176,7 @@ void LEDLights::set_color(const LEDColor &incol #endif #endif - #if BOTH(CASE_LIGHT_MENU, CASE_LIGHT_USE_NEOPIXEL) + #if ALL(CASE_LIGHT_MENU, CASE_LIGHT_USE_NEOPIXEL) // Update brightness only if caselight is ON or switching leds off if (caselight.on || incol.is_off()) #endif @@ -191,7 +191,7 @@ void LEDLights::set_color(const LEDColor &incol } #endif - #if BOTH(CASE_LIGHT_MENU, CASE_LIGHT_USE_NEOPIXEL) + #if ALL(CASE_LIGHT_MENU, CASE_LIGHT_USE_NEOPIXEL) // Update color only if caselight is ON or switching leds off if (caselight.on || incol.is_off()) #endif @@ -206,7 +206,7 @@ void LEDLights::set_color(const LEDColor &incol #endif - #if EITHER(RGB_LED, RGBW_LED) + #if ANY(RGB_LED, RGBW_LED) // This variant uses 3-4 separate pins for the RGB(W) components. // If the pins can do PWM then their intensity will be set. @@ -228,7 +228,7 @@ void LEDLights::set_color(const LEDColor &incol TERN_(PCA9632, PCA9632_set_led_color(incol)); TERN_(PCA9533, PCA9533_set_rgb(incol.r, incol.g, incol.b)); - #if EITHER(LED_CONTROL_MENU, PRINTER_EVENT_LEDS) + #if ANY(LED_CONTROL_MENU, PRINTER_EVENT_LEDS) // Don't update the color when OFF lights_on = !incol.is_off(); if (lights_on) color = incol; diff --git a/Marlin/src/feature/leds/leds.h b/Marlin/src/feature/leds/leds.h index c6137b45c355..7a31ca685d49 100644 --- a/Marlin/src/feature/leds/leds.h +++ b/Marlin/src/feature/leds/leds.h @@ -30,7 +30,7 @@ #include // A white component can be passed -#if EITHER(RGBW_LED, PCA9632_RGBW) +#if ANY(RGBW_LED, PCA9632_RGBW) #define HAS_WHITE_LED 1 #endif @@ -164,7 +164,7 @@ class LEDLights { #if ENABLED(LED_CONTROL_MENU) static void toggle(); // swap "off" with color #endif - #if EITHER(LED_CONTROL_MENU, CASE_LIGHT_USE_RGB_LED) || LED_POWEROFF_TIMEOUT > 0 + #if ANY(LED_CONTROL_MENU, CASE_LIGHT_USE_RGB_LED) || LED_POWEROFF_TIMEOUT > 0 static void update() { set_color(color); } #endif diff --git a/Marlin/src/feature/leds/neopixel.cpp b/Marlin/src/feature/leds/neopixel.cpp index 2193217df055..1b0772c2f9a6 100644 --- a/Marlin/src/feature/leds/neopixel.cpp +++ b/Marlin/src/feature/leds/neopixel.cpp @@ -30,7 +30,7 @@ #include "leds.h" -#if EITHER(NEOPIXEL_STARTUP_TEST, NEOPIXEL2_STARTUP_TEST) +#if ANY(NEOPIXEL_STARTUP_TEST, NEOPIXEL2_STARTUP_TEST) #include "../../core/utility.h" #endif diff --git a/Marlin/src/feature/leds/neopixel.h b/Marlin/src/feature/leds/neopixel.h index 3801ded6aa45..6cc8b6157e80 100644 --- a/Marlin/src/feature/leds/neopixel.h +++ b/Marlin/src/feature/leds/neopixel.h @@ -58,7 +58,7 @@ #define MULTIPLE_NEOPIXEL_TYPES 1 #endif -#if EITHER(MULTIPLE_NEOPIXEL_TYPES, NEOPIXEL2_INSERIES) +#if ANY(MULTIPLE_NEOPIXEL_TYPES, NEOPIXEL2_INSERIES) #define CONJOINED_NEOPIXEL 1 #endif diff --git a/Marlin/src/feature/max7219.cpp b/Marlin/src/feature/max7219.cpp index efc992f80fe1..d3328855f444 100644 --- a/Marlin/src/feature/max7219.cpp +++ b/Marlin/src/feature/max7219.cpp @@ -156,7 +156,7 @@ void Max7219::error(FSTR_P const func, const int32_t v1, const int32_t v2/*=-1*/ */ inline uint32_t flipped(const uint32_t bits, const uint8_t n_bytes) { uint32_t mask = 1, outbits = 0; - LOOP_L_N(b, n_bytes * 8) { + for (uint8_t b = 0; b < n_bytes * 8; ++b) { outbits <<= 1; if (bits & mask) outbits |= 1; mask <<= 1; @@ -339,13 +339,13 @@ void Max7219::fill() { void Max7219::clear_row(const uint8_t row) { if (row >= MAX7219_Y_LEDS) return error(F("clear_row"), row); - LOOP_L_N(x, MAX7219_X_LEDS) CLR_7219(x, row); + for (uint8_t x = 0; x < MAX7219_X_LEDS; ++x) CLR_7219(x, row); send_row(row); } void Max7219::clear_column(const uint8_t col) { if (col >= MAX7219_X_LEDS) return error(F("set_column"), col); - LOOP_L_N(y, MAX7219_Y_LEDS) CLR_7219(col, y); + for (uint8_t y = 0; y < MAX7219_Y_LEDS; ++y) CLR_7219(col, y); send_column(col); } @@ -357,7 +357,7 @@ void Max7219::clear_column(const uint8_t col) { void Max7219::set_row(const uint8_t row, const uint32_t val) { if (row >= MAX7219_Y_LEDS) return error(F("set_row"), row); uint32_t mask = _BV32(MAX7219_X_LEDS - 1); - LOOP_L_N(x, MAX7219_X_LEDS) { + for (uint8_t x = 0; x < MAX7219_X_LEDS; ++x) { if (val & mask) SET_7219(x, row); else CLR_7219(x, row); mask >>= 1; } @@ -372,7 +372,7 @@ void Max7219::set_row(const uint8_t row, const uint32_t val) { void Max7219::set_column(const uint8_t col, const uint32_t val) { if (col >= MAX7219_X_LEDS) return error(F("set_column"), col); uint32_t mask = _BV32(MAX7219_Y_LEDS - 1); - LOOP_L_N(y, MAX7219_Y_LEDS) { + for (uint8_t y = 0; y < MAX7219_Y_LEDS; ++y) { if (val & mask) SET_7219(col, y); else CLR_7219(col, y); mask >>= 1; } @@ -437,23 +437,23 @@ void Max7219::set_columns_32bits(const uint8_t x, uint32_t val) { // Initialize the Max7219 void Max7219::register_setup() { - LOOP_L_N(i, MAX7219_NUMBER_UNITS) + for (uint8_t i = 0; i < MAX7219_NUMBER_UNITS; ++i) send(max7219_reg_scanLimit, 0x07); pulse_load(); // Tell the chips to load the clocked out data - LOOP_L_N(i, MAX7219_NUMBER_UNITS) + for (uint8_t i = 0; i < MAX7219_NUMBER_UNITS; ++i) send(max7219_reg_decodeMode, 0x00); // Using an led matrix (not digits) pulse_load(); // Tell the chips to load the clocked out data - LOOP_L_N(i, MAX7219_NUMBER_UNITS) + for (uint8_t i = 0; i < MAX7219_NUMBER_UNITS; ++i) send(max7219_reg_shutdown, 0x01); // Not in shutdown mode pulse_load(); // Tell the chips to load the clocked out data - LOOP_L_N(i, MAX7219_NUMBER_UNITS) + for (uint8_t i = 0; i < MAX7219_NUMBER_UNITS; ++i) send(max7219_reg_displayTest, 0x00); // No display test pulse_load(); // Tell the chips to load the clocked out data - LOOP_L_N(i, MAX7219_NUMBER_UNITS) + for (uint8_t i = 0; i < MAX7219_NUMBER_UNITS; ++i) send(max7219_reg_intensity, 0x01 & 0x0F); // The first 0x0F is the value you can set // Range: 0x00 to 0x0F pulse_load(); // Tell the chips to load the clocked out data @@ -740,7 +740,7 @@ void Max7219::idle_tasks() { // batch line updates suspended--; if (!suspended) - LOOP_L_N(i, 8) if (row_change_mask & _BV(i)) + for (uint8_t i = 0; i < 8; ++i) if (row_change_mask & _BV(i)) refresh_line(i); // After resume() automatically do a refresh() diff --git a/Marlin/src/feature/mixing.cpp b/Marlin/src/feature/mixing.cpp index cf88b806f542..1ce489224813 100644 --- a/Marlin/src/feature/mixing.cpp +++ b/Marlin/src/feature/mixing.cpp @@ -42,7 +42,7 @@ int_fast8_t Mixer::runner = 0; mixer_comp_t Mixer::s_color[MIXING_STEPPERS]; mixer_accu_t Mixer::accu[MIXING_STEPPERS] = { 0 }; -#if EITHER(HAS_DUAL_MIXING, GRADIENT_MIX) +#if ANY(HAS_DUAL_MIXING, GRADIENT_MIX) mixer_perc_t Mixer::mix[MIXING_STEPPERS]; #endif @@ -94,13 +94,13 @@ void Mixer::normalize(const uint8_t tool_index) { void Mixer::reset_vtools() { // Virtual Tools 0, 1, 2, 3 = Filament 1, 2, 3, 4, etc. // Every virtual tool gets a pure filament - LOOP_L_N(t, _MIN(MIXING_VIRTUAL_TOOLS, MIXING_STEPPERS)) + for (uint8_t t = 0; t < _MIN(MIXING_VIRTUAL_TOOLS, MIXING_STEPPERS); ++t) MIXER_STEPPER_LOOP(i) color[t][i] = (t == i) ? COLOR_A_MASK : 0; // Remaining virtual tools are 100% filament 1 #if MIXING_VIRTUAL_TOOLS > MIXING_STEPPERS - LOOP_S_L_N(t, MIXING_STEPPERS, MIXING_VIRTUAL_TOOLS) + for (uint8_t t = MIXING_STEPPERS; t < MIXING_VIRTUAL_TOOLS; ++t) MIXER_STEPPER_LOOP(i) color[t][i] = (i == 0) ? COLOR_A_MASK : 0; #endif @@ -138,7 +138,7 @@ void Mixer::init() { color[MIXER_AUTORETRACT_TOOL][i] = COLOR_A_MASK; #endif - #if EITHER(HAS_DUAL_MIXING, GRADIENT_MIX) + #if ANY(HAS_DUAL_MIXING, GRADIENT_MIX) update_mix_from_vtool(); #endif diff --git a/Marlin/src/feature/mixing.h b/Marlin/src/feature/mixing.h index 3a14fdad5975..a43b0599447a 100644 --- a/Marlin/src/feature/mixing.h +++ b/Marlin/src/feature/mixing.h @@ -122,7 +122,7 @@ class Mixer { MIXER_STEPPER_LOOP(i) s_color[i] = b_color[i]; } - #if EITHER(HAS_DUAL_MIXING, GRADIENT_MIX) + #if ANY(HAS_DUAL_MIXING, GRADIENT_MIX) static mixer_perc_t mix[MIXING_STEPPERS]; // Scratch array for the Mix in proportion to 100 diff --git a/Marlin/src/feature/mmu/mmu2.cpp b/Marlin/src/feature/mmu/mmu2.cpp index 8aec1dc1db1b..ea1a33ddaad4 100644 --- a/Marlin/src/feature/mmu/mmu2.cpp +++ b/Marlin/src/feature/mmu/mmu2.cpp @@ -135,7 +135,7 @@ void MMU2::reset() { int8_t MMU2::get_current_tool() { return extruder == MMU2_NO_TOOL ? -1 : extruder; } -#if EITHER(HAS_PRUSA_MMU2S, MMU_EXTRUDER_SENSOR) +#if ANY(HAS_PRUSA_MMU2S, MMU_EXTRUDER_SENSOR) #define FILAMENT_PRESENT() (READ(FIL_RUNOUT1_PIN) != FIL_RUNOUT1_STATE) #else #define FILAMENT_PRESENT() true @@ -403,7 +403,7 @@ void MMU2::tx_str(FSTR_P fstr) { void MMU2::tx_printf(FSTR_P format, int argument = -1) { clear_rx_buffer(); const uint8_t len = sprintf_P(tx_buffer, FTOP(format), argument); - LOOP_L_N(i, len) MMU2_SERIAL.write(tx_buffer[i]); + for (uint8_t i = 0; i < len; ++i) MMU2_SERIAL.write(tx_buffer[i]); prev_request = millis(); } @@ -413,7 +413,7 @@ void MMU2::tx_printf(FSTR_P format, int argument = -1) { void MMU2::tx_printf(FSTR_P format, int argument1, int argument2) { clear_rx_buffer(); const uint8_t len = sprintf_P(tx_buffer, FTOP(format), argument1, argument2); - LOOP_L_N(i, len) MMU2_SERIAL.write(tx_buffer[i]); + for (uint8_t i = 0; i < len; ++i) MMU2_SERIAL.write(tx_buffer[i]); prev_request = millis(); } @@ -467,7 +467,7 @@ inline void beep_bad_cmd() { BUZZ(400, 40); } bool MMU2::load_to_gears() { command(MMU_CMD_C0); manage_response(true, true); - LOOP_L_N(i, MMU2_C0_RETRY) { // Keep loading until filament reaches gears + for (uint8_t i = 0; i < MMU2_C0_RETRY; ++i) { // Keep loading until filament reaches gears if (mmu2s_triggered) break; command(MMU_CMD_C0); manage_response(true, true); @@ -900,7 +900,7 @@ void MMU2::filament_runout() { int filament_detected_count = 0; const int steps = (MMU2_CAN_LOAD_RETRACT) / (MMU2_CAN_LOAD_INCREMENT); DEBUG_ECHOLNPGM("MMU can_load:"); - LOOP_L_N(i, steps) { + for (uint8_t i = 0; i < steps; ++i) { execute_extruder_sequence(can_load_increment_sequence, COUNT(can_load_increment_sequence)); check_filament(); // Don't trust the idle function DEBUG_CHAR(mmu2s_triggered ? 'O' : 'o'); @@ -1047,7 +1047,7 @@ void MMU2::execute_extruder_sequence(const E_Step * sequence, int steps) { const E_Step *step = sequence; - LOOP_L_N(i, steps) { + for (uint8_t i = 0; i < steps; ++i) { const float es = pgm_read_float(&(step->extrude)); const feedRate_t fr_mm_m = pgm_read_float(&(step->feedRate)); DEBUG_ECHO_MSG("E step ", es, "/", fr_mm_m); diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index 504a9f61c78a..66f7ad15edfd 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -210,7 +210,7 @@ bool load_filament(const_float_t slow_load_length/*=0*/, const_float_t fast_load while (wait_for_user) { impatient_beep(max_beep_count); - #if BOTH(FILAMENT_CHANGE_RESUME_ON_INSERT, FILAMENT_RUNOUT_SENSOR) + #if ALL(FILAMENT_CHANGE_RESUME_ON_INSERT, FILAMENT_RUNOUT_SENSOR) #if MULTI_FILAMENT_SENSOR #define _CASE_INSERTED(N) case N-1: if (READ(FIL_RUNOUT##N##_PIN) != FIL_RUNOUT##N##_STATE) wait_for_user = false; break; switch (active_extruder) { @@ -286,7 +286,7 @@ bool load_filament(const_float_t slow_load_length/*=0*/, const_float_t fast_load // Show "Purge More" / "Resume" menu and wait for reply KEEPALIVE_STATE(PAUSED_FOR_USER); wait_for_user = false; - #if EITHER(HAS_MARLINUI_MENU, DWIN_LCD_PROUI) + #if ANY(HAS_MARLINUI_MENU, DWIN_LCD_PROUI) ui.pause_show_message(PAUSE_MESSAGE_OPTION); // Also sets PAUSE_RESPONSE_WAIT_FOR #else pause_menu_response = PAUSE_RESPONSE_WAIT_FOR; @@ -331,18 +331,18 @@ inline void disable_active_extruder() { */ bool unload_filament(const_float_t unload_length, const bool show_lcd/*=false*/, const PauseMode mode/*=PAUSE_MODE_PAUSE_PRINT*/ - #if BOTH(FILAMENT_UNLOAD_ALL_EXTRUDERS, MIXING_EXTRUDER) + #if ALL(FILAMENT_UNLOAD_ALL_EXTRUDERS, MIXING_EXTRUDER) , const_float_t mix_multiplier/*=1.0*/ #endif ) { DEBUG_SECTION(uf, "unload_filament", true); DEBUG_ECHOLNPGM("... unloadlen:", unload_length, " showlcd:", show_lcd, " mode:", mode - #if BOTH(FILAMENT_UNLOAD_ALL_EXTRUDERS, MIXING_EXTRUDER) + #if ALL(FILAMENT_UNLOAD_ALL_EXTRUDERS, MIXING_EXTRUDER) , " mixmult:", mix_multiplier #endif ); - #if !BOTH(FILAMENT_UNLOAD_ALL_EXTRUDERS, MIXING_EXTRUDER) + #if !ALL(FILAMENT_UNLOAD_ALL_EXTRUDERS, MIXING_EXTRUDER) constexpr float mix_multiplier = 1.0f; #endif @@ -402,8 +402,6 @@ bool pause_print(const_float_t retract, const xyz_pos_t &park_point, const bool DEBUG_SECTION(pp, "pause_print", true); DEBUG_ECHOLNPGM("... park.x:", park_point.x, " y:", park_point.y, " z:", park_point.z, " unloadlen:", unload_length, " showlcd:", show_lcd DXC_SAY); - UNUSED(show_lcd); - if (did_pause_print) return false; // already paused #if ENABLED(HOST_ACTION_COMMANDS) @@ -445,7 +443,7 @@ bool pause_print(const_float_t retract, const xyz_pos_t &park_point, const bool // Wait for buffered blocks to complete planner.synchronize(); - #if BOTH(ADVANCED_PAUSE_FANS_PAUSE, HAS_FAN) + #if ALL(ADVANCED_PAUSE_FANS_PAUSE, HAS_FAN) thermalManager.set_fans_paused(true); #endif diff --git a/Marlin/src/feature/pause.h b/Marlin/src/feature/pause.h index 134b1d1b3294..7ea0c03b6bbb 100644 --- a/Marlin/src/feature/pause.h +++ b/Marlin/src/feature/pause.h @@ -117,7 +117,7 @@ bool unload_filament( const_float_t unload_length, // (mm) Filament Unload Length - 0 to skip const bool show_lcd=false, // Set LCD status messages? const PauseMode mode=PAUSE_MODE_PAUSE_PRINT // Pause Mode to apply - #if BOTH(FILAMENT_UNLOAD_ALL_EXTRUDERS, MIXING_EXTRUDER) + #if ALL(FILAMENT_UNLOAD_ALL_EXTRUDERS, MIXING_EXTRUDER) , const_float_t mix_multiplier=1.0f // Extrusion multiplier (for a Mixing Extruder) #endif ); diff --git a/Marlin/src/feature/power.cpp b/Marlin/src/feature/power.cpp index 8a16628bac45..d0f8a66fec36 100644 --- a/Marlin/src/feature/power.cpp +++ b/Marlin/src/feature/power.cpp @@ -26,7 +26,7 @@ #include "../inc/MarlinConfigPre.h" -#if EITHER(PSU_CONTROL, AUTO_POWER_CONTROL) +#if ANY(PSU_CONTROL, AUTO_POWER_CONTROL) #include "power.h" #include "../module/planner.h" @@ -49,7 +49,7 @@ bool Power::psu_on; #include "../module/stepper.h" #include "../module/temperature.h" - #if BOTH(USE_CONTROLLER_FAN, AUTO_POWER_CONTROLLERFAN) + #if ALL(USE_CONTROLLER_FAN, AUTO_POWER_CONTROLLERFAN) #include "controllerfan.h" #endif @@ -78,7 +78,7 @@ void Power::power_on() { if (psu_on) return; - #if EITHER(POWER_OFF_TIMER, POWER_OFF_WAIT_FOR_COOLDOWN) + #if ANY(POWER_OFF_TIMER, POWER_OFF_WAIT_FOR_COOLDOWN) cancelAutoPowerOff(); #endif @@ -115,12 +115,12 @@ void Power::power_off() { OUT_WRITE(PS_ON_PIN, !PSU_ACTIVE_STATE); psu_on = false; - #if EITHER(POWER_OFF_TIMER, POWER_OFF_WAIT_FOR_COOLDOWN) + #if ANY(POWER_OFF_TIMER, POWER_OFF_WAIT_FOR_COOLDOWN) cancelAutoPowerOff(); #endif } -#if EITHER(AUTO_POWER_CONTROL, POWER_OFF_WAIT_FOR_COOLDOWN) +#if ANY(AUTO_POWER_CONTROL, POWER_OFF_WAIT_FOR_COOLDOWN) bool Power::is_cooling_needed() { #if HAS_HOTEND && AUTO_POWER_E_TEMP @@ -140,7 +140,7 @@ void Power::power_off() { #endif -#if EITHER(POWER_OFF_TIMER, POWER_OFF_WAIT_FOR_COOLDOWN) +#if ANY(POWER_OFF_TIMER, POWER_OFF_WAIT_FOR_COOLDOWN) #if ENABLED(POWER_OFF_TIMER) millis_t Power::power_off_time = 0; @@ -192,7 +192,7 @@ void Power::power_off() { HOTEND_LOOP() if (thermalManager.autofan_speed[e]) return true; #endif - #if BOTH(USE_CONTROLLER_FAN, AUTO_POWER_CONTROLLERFAN) + #if ALL(USE_CONTROLLER_FAN, AUTO_POWER_CONTROLLERFAN) if (controllerFan.state()) return true; #endif diff --git a/Marlin/src/feature/power.h b/Marlin/src/feature/power.h index 839366ca602b..fdbb7126ceae 100644 --- a/Marlin/src/feature/power.h +++ b/Marlin/src/feature/power.h @@ -25,7 +25,7 @@ * power.h - power control */ -#if EITHER(AUTO_POWER_CONTROL, POWER_OFF_TIMER) +#if ANY(AUTO_POWER_CONTROL, POWER_OFF_TIMER) #include "../core/millis_t.h" #endif @@ -37,7 +37,7 @@ class Power { static void power_on(); static void power_off(); - #if EITHER(POWER_OFF_TIMER, POWER_OFF_WAIT_FOR_COOLDOWN) + #if ANY(POWER_OFF_TIMER, POWER_OFF_WAIT_FOR_COOLDOWN) #if ENABLED(POWER_OFF_TIMER) static millis_t power_off_time; static void setPowerOffTimer(const millis_t delay_ms); diff --git a/Marlin/src/feature/powerloss.cpp b/Marlin/src/feature/powerloss.cpp index 29c4695ca476..af85a1644862 100644 --- a/Marlin/src/feature/powerloss.cpp +++ b/Marlin/src/feature/powerloss.cpp @@ -630,7 +630,7 @@ void PrintJobRecovery::resume() { #if ENABLED(GCODE_REPEAT_MARKERS) DEBUG_ECHOLNPGM("repeat index: ", info.stored_repeat.index); - LOOP_L_N(i, info.stored_repeat.index) + for (uint8_t i = 0; i < info.stored_repeat.index; ++i) DEBUG_ECHOLNPGM("..... sdpos: ", info.stored_repeat.marker.sdpos, " count: ", info.stored_repeat.marker.counter); #endif @@ -699,7 +699,7 @@ void PrintJobRecovery::resume() { #endif // Mixing extruder and gradient - #if BOTH(MIXING_EXTRUDER, GRADIENT_MIX) + #if ALL(MIXING_EXTRUDER, GRADIENT_MIX) DEBUG_ECHOLNPGM("gradient: ", info.gradient.enabled ? "ON" : "OFF"); #endif diff --git a/Marlin/src/feature/probe_temp_comp.cpp b/Marlin/src/feature/probe_temp_comp.cpp index b5f636e698c9..2b362a2186b6 100644 --- a/Marlin/src/feature/probe_temp_comp.cpp +++ b/Marlin/src/feature/probe_temp_comp.cpp @@ -66,13 +66,13 @@ float ProbeTempComp::init_measurement; // = 0.0 bool ProbeTempComp::enabled = true; void ProbeTempComp::reset() { - TERN_(PTC_PROBE, LOOP_L_N(i, PTC_PROBE_COUNT) z_offsets_probe[i] = z_offsets_probe_default[i]); - TERN_(PTC_BED, LOOP_L_N(i, PTC_BED_COUNT) z_offsets_bed[i] = z_offsets_bed_default[i]); - TERN_(PTC_HOTEND, LOOP_L_N(i, PTC_HOTEND_COUNT) z_offsets_hotend[i] = z_offsets_hotend_default[i]); + TERN_(PTC_PROBE, for (uint8_t i = 0; i < PTC_PROBE_COUNT; ++i) z_offsets_probe[i] = z_offsets_probe_default[i]); + TERN_(PTC_BED, for (uint8_t i = 0; i < PTC_BED_COUNT; ++i) z_offsets_bed[i] = z_offsets_bed_default[i]); + TERN_(PTC_HOTEND, for (uint8_t i = 0; i < PTC_HOTEND_COUNT; ++i) z_offsets_hotend[i] = z_offsets_hotend_default[i]); } void ProbeTempComp::clear_offsets(const TempSensorID tsi) { - LOOP_L_N(i, cali_info[tsi].measurements) + for (uint8_t i = 0; i < cali_info[tsi].measurements; ++i) sensor_z_offsets[tsi][i] = 0; calib_idx = 0; } @@ -84,7 +84,7 @@ bool ProbeTempComp::set_offset(const TempSensorID tsi, const uint8_t idx, const } void ProbeTempComp::print_offsets() { - LOOP_L_N(s, TSI_COUNT) { + for (uint8_t s = 0; s < TSI_COUNT; ++s) { celsius_t temp = cali_info[s].start_temp; for (int16_t i = -1; i < cali_info[s].measurements; ++i) { SERIAL_ECHOF( @@ -232,7 +232,7 @@ bool ProbeTempComp::linear_regression(const TempSensorID tsi, float &k, float &d sum_xy = 0, sum_y = 0; float xi = static_cast(start_temp); - LOOP_L_N(i, calib_idx) { + for (uint8_t i = 0; i < calib_idx; ++i) { const float yi = static_cast(data[i]); xi += res_temp; sum_x += xi; diff --git a/Marlin/src/feature/repeat.cpp b/Marlin/src/feature/repeat.cpp index fed7ac0908a0..4484dab95b39 100644 --- a/Marlin/src/feature/repeat.cpp +++ b/Marlin/src/feature/repeat.cpp @@ -66,7 +66,7 @@ void Repeat::loop() { } } -void Repeat::cancel() { LOOP_L_N(i, index) marker[i].counter = 0; } +void Repeat::cancel() { for (uint8_t i = 0; i < index; ++i) marker[i].counter = 0; } void Repeat::early_parse_M808(char * const cmd) { if (is_command_M808(cmd)) { diff --git a/Marlin/src/feature/repeat.h b/Marlin/src/feature/repeat.h index fc11e4a9e2cf..8a54149b3d1e 100644 --- a/Marlin/src/feature/repeat.h +++ b/Marlin/src/feature/repeat.h @@ -40,7 +40,7 @@ class Repeat { public: static void reset() { index = 0; } static bool is_active() { - LOOP_L_N(i, index) if (marker[i].counter) return true; + for (uint8_t i = 0; i < index; ++i) if (marker[i].counter) return true; return false; } static bool is_command_M808(char * const cmd) { return cmd[0] == 'M' && cmd[1] == '8' && cmd[2] == '0' && cmd[3] == '8' && !NUMERIC(cmd[4]); } diff --git a/Marlin/src/feature/runout.h b/Marlin/src/feature/runout.h index e160f889050d..ea17cbc4422b 100644 --- a/Marlin/src/feature/runout.h +++ b/Marlin/src/feature/runout.h @@ -155,7 +155,7 @@ class TFilamentMonitor : public FilamentMonitorBase { #if ENABLED(FILAMENT_RUNOUT_SENSOR_DEBUG) if (runout_flags) { SERIAL_ECHOPGM("Runout Sensors: "); - LOOP_L_N(i, 8) SERIAL_ECHO('0' + TEST(runout_flags, i)); + for (uint8_t i = 0; i < 8; ++i) SERIAL_ECHO('0' + TEST(runout_flags, i)); SERIAL_ECHOPGM(" -> ", extruder); if (ran_out) SERIAL_ECHOPGM(" RUN OUT"); SERIAL_EOL(); @@ -255,7 +255,7 @@ class FilamentSensorBase { #if ENABLED(FILAMENT_RUNOUT_SENSOR_DEBUG) if (change) { SERIAL_ECHOPGM("Motion detected:"); - LOOP_L_N(e, TERN(FILAMENT_SWITCH_AND_MOTION, NUM_MOTION_SENSORS, NUM_RUNOUT_SENSORS)) + for (uint8_t e = 0; e < TERN(FILAMENT_SWITCH_AND_MOTION, NUM_MOTION_SENSORS, NUM_RUNOUT_SENSORS); ++e) if (TEST(change, e)) SERIAL_CHAR(' ', '0' + e); SERIAL_EOL(); } @@ -304,7 +304,7 @@ class FilamentSensorBase { static void block_completed(const block_t * const) {} static void run() { - LOOP_L_N(s, NUM_RUNOUT_SENSORS) { + for (uint8_t s = 0; s < NUM_RUNOUT_SENSORS; ++s) { const bool out = poll_runout_state(s); if (!out) filament_present(s); #if ENABLED(FILAMENT_RUNOUT_SENSOR_DEBUG) @@ -364,9 +364,9 @@ class FilamentSensorBase { static float runout_distance_mm; static void reset() { - LOOP_L_N(i, NUM_RUNOUT_SENSORS) filament_present(i); + for (uint8_t i = 0; i < NUM_RUNOUT_SENSORS; ++i) filament_present(i); #if ENABLED(FILAMENT_SWITCH_AND_MOTION) - LOOP_L_N(i, NUM_MOTION_SENSORS) filament_motion_present(i); + for (uint8_t i = 0; i < NUM_MOTION_SENSORS; ++i) filament_motion_present(i); #endif } @@ -376,10 +376,10 @@ class FilamentSensorBase { const millis_t ms = millis(); if (ELAPSED(ms, t)) { t = millis() + 1000UL; - LOOP_L_N(i, NUM_RUNOUT_SENSORS) + for (uint8_t i = 0; i < NUM_RUNOUT_SENSORS; ++i) SERIAL_ECHOF(i ? F(", ") : F("Runout remaining mm: "), mm_countdown.runout[i]); #if ENABLED(FILAMENT_SWITCH_AND_MOTION) - LOOP_L_N(i, NUM_MOTION_SENSORS) + for (uint8_t i = 0; i < NUM_MOTION_SENSORS; ++i) SERIAL_ECHOF(i ? F(", ") : F("Motion remaining mm: "), mm_countdown.motion[i]); #endif SERIAL_EOL(); @@ -389,9 +389,9 @@ class FilamentSensorBase { static uint8_t has_run_out() { uint8_t runout_flags = 0; - LOOP_L_N(i, NUM_RUNOUT_SENSORS) if (mm_countdown.runout[i] < 0) SBI(runout_flags, i); + for (uint8_t i = 0; i < NUM_RUNOUT_SENSORS; ++i) if (mm_countdown.runout[i] < 0) SBI(runout_flags, i); #if ENABLED(FILAMENT_SWITCH_AND_MOTION) - LOOP_L_N(i, NUM_MOTION_SENSORS) if (mm_countdown.motion[i] < 0) SBI(runout_flags, i); + for (uint8_t i = 0; i < NUM_MOTION_SENSORS; ++i) if (mm_countdown.motion[i] < 0) SBI(runout_flags, i); #endif return runout_flags; } @@ -432,16 +432,16 @@ class FilamentSensorBase { public: static void reset() { - LOOP_L_N(i, NUM_RUNOUT_SENSORS) filament_present(i); + for (uint8_t i = 0; i < NUM_RUNOUT_SENSORS; ++i) filament_present(i); } static void run() { - LOOP_L_N(i, NUM_RUNOUT_SENSORS) if (runout_count[i] >= 0) runout_count[i]--; + for (uint8_t i = 0; i < NUM_RUNOUT_SENSORS; ++i) if (runout_count[i] >= 0) runout_count[i]--; } static uint8_t has_run_out() { uint8_t runout_flags = 0; - LOOP_L_N(i, NUM_RUNOUT_SENSORS) if (runout_count[i] < 0) SBI(runout_flags, i); + for (uint8_t i = 0; i < NUM_RUNOUT_SENSORS; ++i) if (runout_count[i] < 0) SBI(runout_flags, i); return runout_flags; } diff --git a/Marlin/src/feature/solenoid.cpp b/Marlin/src/feature/solenoid.cpp index 861e44ed05de..46364eaf8f5b 100644 --- a/Marlin/src/feature/solenoid.cpp +++ b/Marlin/src/feature/solenoid.cpp @@ -22,7 +22,7 @@ #include "../inc/MarlinConfig.h" -#if EITHER(EXT_SOLENOID, MANUAL_SOLENOID_CONTROL) +#if ANY(EXT_SOLENOID, MANUAL_SOLENOID_CONTROL) #include "solenoid.h" diff --git a/Marlin/src/feature/twibus.cpp b/Marlin/src/feature/twibus.cpp index 9aec6b030537..4aedb4b5f3c5 100644 --- a/Marlin/src/feature/twibus.cpp +++ b/Marlin/src/feature/twibus.cpp @@ -145,7 +145,7 @@ void TWIBus::echodata(uint8_t bytes, FSTR_P const pref, uint8_t adr, const uint8 void TWIBus::echobuffer(FSTR_P const prefix, uint8_t adr) { echoprefix(buffer_s, prefix, adr); - LOOP_L_N(i, buffer_s) SERIAL_CHAR(buffer[i]); + for (uint8_t i = 0; i < buffer_s; ++i) SERIAL_CHAR(buffer[i]); SERIAL_EOL(); } diff --git a/Marlin/src/feature/x_twist.cpp b/Marlin/src/feature/x_twist.cpp index b5ad25cba87d..b8f7e52ab6d5 100644 --- a/Marlin/src/feature/x_twist.cpp +++ b/Marlin/src/feature/x_twist.cpp @@ -43,12 +43,12 @@ void XATC::reset() { void XATC::print_points() { SERIAL_ECHOLNPGM(" X-Twist Correction:"); - LOOP_L_N(x, XATC_MAX_POINTS) { + for (uint8_t x = 0; x < XATC_MAX_POINTS; ++x) { SERIAL_CHAR(' '); if (!isnan(z_offset[x])) serial_offset(z_offset[x]); else - LOOP_L_N(i, 6) SERIAL_CHAR(i ? '=' : ' '); + for (uint8_t i = 0; i < 6; ++i) SERIAL_CHAR(i ? '=' : ' '); } SERIAL_EOL(); } diff --git a/Marlin/src/gcode/bedlevel/G26.cpp b/Marlin/src/gcode/bedlevel/G26.cpp index 1b55bdb4286c..30643cb84e9b 100644 --- a/Marlin/src/gcode/bedlevel/G26.cpp +++ b/Marlin/src/gcode/bedlevel/G26.cpp @@ -707,7 +707,7 @@ void GcodeSuite::G26() { #error "A_CNT must be a positive value. Please change A_INT." #endif float trig_table[A_CNT]; - LOOP_L_N(i, A_CNT) + for (uint8_t i = 0; i < A_CNT; ++i) trig_table[i] = INTERSECTION_CIRCLE_RADIUS * cos(RADIANS(i * A_INT)); #endif // !ARC_SUPPORT diff --git a/Marlin/src/gcode/bedlevel/G35.cpp b/Marlin/src/gcode/bedlevel/G35.cpp index f5f395ee2e25..9c1ee472ec5a 100644 --- a/Marlin/src/gcode/bedlevel/G35.cpp +++ b/Marlin/src/gcode/bedlevel/G35.cpp @@ -97,7 +97,7 @@ void GcodeSuite::G35() { bool err_break = false; // Probe all positions - LOOP_L_N(i, G35_PROBE_COUNT) { + for (uint8_t i = 0; i < G35_PROBE_COUNT; ++i) { const float z_probed_height = probe.probe_at_point(tramming_points[i], PROBE_PT_RAISE); if (isnan(z_probed_height)) { SERIAL_ECHOPGM("G35 failed at point ", i + 1, " ("); @@ -122,7 +122,7 @@ void GcodeSuite::G35() { const float threads_factor[] = { 0.5, 0.7, 0.8 }; // Calculate adjusts - LOOP_S_L_N(i, 1, G35_PROBE_COUNT) { + for (uint8_t i = 1; i < G35_PROBE_COUNT; ++i) { const float diff = z_measured[0] - z_measured[i], adjust = ABS(diff) < 0.001f ? 0 : diff / threads_factor[(screw_thread - 30) / 10]; @@ -144,7 +144,7 @@ void GcodeSuite::G35() { // Restore the active tool after homing probe.use_probing_tool(false); - #if BOTH(HAS_LEVELING, RESTORE_LEVELING_AFTER_G35) + #if ALL(HAS_LEVELING, RESTORE_LEVELING_AFTER_G35) set_bed_leveling_enabled(leveling_was_active); #endif diff --git a/Marlin/src/gcode/bedlevel/abl/G29.cpp b/Marlin/src/gcode/bedlevel/abl/G29.cpp index 1fe4a31bee48..ca02fc976536 100644 --- a/Marlin/src/gcode/bedlevel/abl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/abl/G29.cpp @@ -97,7 +97,7 @@ class G29_State { bool dryrun, reenable; - #if EITHER(PROBE_MANUALLY, AUTO_BED_LEVELING_LINEAR) + #if ANY(PROBE_MANUALLY, AUTO_BED_LEVELING_LINEAR) int abl_probe_index; #endif @@ -139,7 +139,7 @@ class G29_State { #endif }; -#if ABL_USES_GRID && EITHER(AUTO_BED_LEVELING_3POINT, AUTO_BED_LEVELING_BILINEAR) +#if ABL_USES_GRID && ANY(AUTO_BED_LEVELING_3POINT, AUTO_BED_LEVELING_BILINEAR) constexpr xy_uint8_t G29_State::grid_points; constexpr grid_count_t G29_State::abl_points; #endif @@ -231,7 +231,7 @@ G29_TYPE GcodeSuite::G29() { reset_stepper_timeout(); // Q = Query leveling and G29 state - const bool seenQ = EITHER(DEBUG_LEVELING_FEATURE, PROBE_MANUALLY) && parser.seen_test('Q'); + const bool seenQ = ANY(DEBUG_LEVELING_FEATURE, PROBE_MANUALLY) && parser.seen_test('Q'); // G29 Q is also available if debugging #if ENABLED(DEBUG_LEVELING_FEATURE) @@ -279,7 +279,7 @@ G29_TYPE GcodeSuite::G29() { probe.use_probing_tool(); - #if EITHER(PROBE_MANUALLY, AUTO_BED_LEVELING_LINEAR) + #if ANY(PROBE_MANUALLY, AUTO_BED_LEVELING_LINEAR) abl.abl_probe_index = -1; #endif @@ -436,7 +436,7 @@ G29_TYPE GcodeSuite::G29() { #if ENABLED(PREHEAT_BEFORE_LEVELING) if (!abl.dryrun) probe.preheat_for_probing(LEVELING_NOZZLE_TEMP, - #if BOTH(DWIN_LCD_PROUI, HAS_HEATED_BED) + #if ALL(DWIN_LCD_PROUI, HAS_HEATED_BED) HMI_data.BedLevT #else LEVELING_BED_TEMP @@ -484,7 +484,7 @@ G29_TYPE GcodeSuite::G29() { if (!no_action) set_bed_leveling_enabled(false); // Deploy certain probes before starting probing - #if ENABLED(BLTOUCH) || BOTH(HAS_Z_SERVO_PROBE, Z_SERVO_INTERMEDIATE_STOW) + #if ENABLED(BLTOUCH) || ALL(HAS_Z_SERVO_PROBE, Z_SERVO_INTERMEDIATE_STOW) do_z_clearance(Z_CLEARANCE_DEPLOY_PROBE); #elif HAS_BED_PROBE if (probe.deploy()) { // (returns true on deploy failure) @@ -542,7 +542,7 @@ G29_TYPE GcodeSuite::G29() { } else { - #if EITHER(AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_3POINT) + #if ANY(AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_3POINT) const uint16_t index = abl.abl_probe_index - 1; #endif @@ -728,7 +728,7 @@ G29_TYPE GcodeSuite::G29() { // Probe at 3 arbitrary points - LOOP_L_N(i, 3) { + for (uint8_t i = 0; i < 3; ++i) { if (abl.verbose_level) SERIAL_ECHOLNPGM("Probing point ", i + 1, "/3."); TERN_(HAS_STATUS_MESSAGE, ui.status_printf(0, F(S_FMT " %i/3"), GET_TEXT(MSG_PROBING_POINT), int(i + 1))); @@ -839,7 +839,7 @@ G29_TYPE GcodeSuite::G29() { auto print_topo_map = [&](FSTR_P const title, const bool get_min) { SERIAL_ECHOF(title); for (int8_t yy = abl.grid_points.y - 1; yy >= 0; yy--) { - LOOP_L_N(xx, abl.grid_points.x) { + for (uint8_t xx = 0; xx < abl.grid_points.x; ++xx) { const int ind = abl.indexIntoAB[xx][yy]; xyz_float_t tmp = { abl.eqnAMatrix[ind + 0 * abl.abl_points], abl.eqnAMatrix[ind + 1 * abl.abl_points], 0 }; diff --git a/Marlin/src/gcode/bedlevel/abl/M421.cpp b/Marlin/src/gcode/bedlevel/abl/M421.cpp index 3272ea1bd227..f66d0231901e 100644 --- a/Marlin/src/gcode/bedlevel/abl/M421.cpp +++ b/Marlin/src/gcode/bedlevel/abl/M421.cpp @@ -56,8 +56,8 @@ void GcodeSuite::M421() { const float zval = parser.value_linear_units(); uint8_t sx = ix >= 0 ? ix : 0, ex = ix >= 0 ? ix : GRID_MAX_POINTS_X - 1, sy = iy >= 0 ? iy : 0, ey = iy >= 0 ? iy : GRID_MAX_POINTS_Y - 1; - LOOP_S_LE_N(x, sx, ex) { - LOOP_S_LE_N(y, sy, ey) { + for (uint8_t x = sx; x <= ex; ++x) { + for (uint8_t y = sy; y <= ey; ++y) { bedlevel.z_values[x][y] = zval + (hasQ ? bedlevel.z_values[x][y] : 0); TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, bedlevel.z_values[x][y])); } diff --git a/Marlin/src/gcode/calibrate/G28.cpp b/Marlin/src/gcode/calibrate/G28.cpp index be593d0d5b1b..fde640fe9895 100644 --- a/Marlin/src/gcode/calibrate/G28.cpp +++ b/Marlin/src/gcode/calibrate/G28.cpp @@ -486,7 +486,7 @@ void GcodeSuite::G28() { } #endif // HAS_X_AXIS - #if BOTH(FOAMCUTTER_XYUV, HAS_I_AXIS) + #if ALL(FOAMCUTTER_XYUV, HAS_I_AXIS) // Home I (after X) if (doI) homeaxis(I_AXIS); #endif @@ -497,7 +497,7 @@ void GcodeSuite::G28() { homeaxis(Y_AXIS); #endif - #if BOTH(FOAMCUTTER_XYUV, HAS_J_AXIS) + #if ALL(FOAMCUTTER_XYUV, HAS_J_AXIS) // Home J (after Y) if (doJ) homeaxis(J_AXIS); #endif @@ -514,7 +514,7 @@ void GcodeSuite::G28() { // Home Z last if homing towards the bed #if DISABLED(HOME_Z_FIRST) if (doZ) { - #if EITHER(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN) + #if ANY(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN) stepper.set_all_z_lock(false); stepper.set_separate_multi_axis(false); #endif @@ -525,7 +525,7 @@ void GcodeSuite::G28() { homeaxis(Z_AXIS); #endif - #if EITHER(Z_HOME_TO_MIN, ALLOW_Z_AFTER_HOMING) + #if ANY(Z_HOME_TO_MIN, ALLOW_Z_AFTER_HOMING) finalRaiseZ = true; #endif } diff --git a/Marlin/src/gcode/calibrate/G34_M422.cpp b/Marlin/src/gcode/calibrate/G34_M422.cpp index 3e7ed08b6c1e..7650443de862 100644 --- a/Marlin/src/gcode/calibrate/G34_M422.cpp +++ b/Marlin/src/gcode/calibrate/G34_M422.cpp @@ -22,7 +22,7 @@ #include "../../inc/MarlinConfigPre.h" -#if EITHER(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN) +#if ANY(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN) #include "../../feature/z_stepper_align.h" @@ -204,7 +204,7 @@ void GcodeSuite::G34() { float z_measured_max = -100000.0f; // Probe all positions (one per Z-Stepper) - LOOP_L_N(i, NUM_Z_STEPPERS) { + for (uint8_t i = 0; i < NUM_Z_STEPPERS; ++i) { // iteration odd/even --> downward / upward stepper sequence const uint8_t iprobe = (iteration & 1) ? NUM_Z_STEPPERS - 1 - i : i; @@ -255,14 +255,14 @@ void GcodeSuite::G34() { // This allows the actual adjustment logic to be shared by both algorithms. linear_fit_data lfd; incremental_LSF_reset(&lfd); - LOOP_L_N(i, NUM_Z_STEPPERS) { + for (uint8_t i = 0; i < NUM_Z_STEPPERS; ++i) { SERIAL_ECHOLNPGM("PROBEPT_", i, ": ", z_measured[i]); incremental_LSF(&lfd, z_stepper_align.xy[i], z_measured[i]); } finish_incremental_LSF(&lfd); z_measured_min = 100000.0f; - LOOP_L_N(i, NUM_Z_STEPPERS) { + for (uint8_t i = 0; i < NUM_Z_STEPPERS; ++i) { z_measured[i] = -(lfd.A * z_stepper_align.stepper_xy[i].x + lfd.B * z_stepper_align.stepper_xy[i].y + lfd.D); z_measured_min = _MIN(z_measured_min, z_measured[i]); } @@ -330,12 +330,12 @@ void GcodeSuite::G34() { // Calculate mean value as a reference float z_measured_mean = 0.0f; - LOOP_L_N(zstepper, NUM_Z_STEPPERS) z_measured_mean += z_measured[zstepper]; + for (uint8_t zstepper = 0; zstepper < NUM_Z_STEPPERS; ++zstepper) z_measured_mean += z_measured[zstepper]; z_measured_mean /= NUM_Z_STEPPERS; // Calculate the sum of the absolute deviations from the mean value float z_align_level_indicator = 0.0f; - LOOP_L_N(zstepper, NUM_Z_STEPPERS) + for (uint8_t zstepper = 0; zstepper < NUM_Z_STEPPERS; ++zstepper) z_align_level_indicator += ABS(z_measured[zstepper] - z_measured_mean); // If it's getting worse, stop and throw an error @@ -350,7 +350,7 @@ void GcodeSuite::G34() { bool success_break = true; // Correct the individual stepper offsets - LOOP_L_N(zstepper, NUM_Z_STEPPERS) { + for (uint8_t zstepper = 0; zstepper < NUM_Z_STEPPERS; ++zstepper) { // Calculate current stepper move float z_align_move = z_measured[zstepper] - z_measured_min; const float z_align_abs = ABS(z_align_move); @@ -431,7 +431,7 @@ void GcodeSuite::G34() { probe.use_probing_tool(false); - #if BOTH(HAS_LEVELING, RESTORE_LEVELING_AFTER_G34) + #if ALL(HAS_LEVELING, RESTORE_LEVELING_AFTER_G34) set_bed_leveling_enabled(leveling_was_active); #endif @@ -529,7 +529,7 @@ void GcodeSuite::M422() { void GcodeSuite::M422_report(const bool forReplay/*=true*/) { report_heading(forReplay, F(STR_Z_AUTO_ALIGN)); - LOOP_L_N(i, NUM_Z_STEPPERS) { + for (uint8_t i = 0; i < NUM_Z_STEPPERS; ++i) { report_echo_start(forReplay); SERIAL_ECHOLNPGM_P( PSTR(" M422 S"), i + 1, @@ -538,7 +538,7 @@ void GcodeSuite::M422_report(const bool forReplay/*=true*/) { ); } #if HAS_Z_STEPPER_ALIGN_STEPPER_XY - LOOP_L_N(i, NUM_Z_STEPPERS) { + for (uint8_t i = 0; i < NUM_Z_STEPPERS; ++i) { report_echo_start(forReplay); SERIAL_ECHOLNPGM_P( PSTR(" M422 W"), i + 1, diff --git a/Marlin/src/gcode/calibrate/G425.cpp b/Marlin/src/gcode/calibrate/G425.cpp index ef055498a922..fb211ad88c74 100644 --- a/Marlin/src/gcode/calibrate/G425.cpp +++ b/Marlin/src/gcode/calibrate/G425.cpp @@ -171,7 +171,7 @@ inline void park_above_object(measurements_t &m, const float uncertainty) { #if HAS_HOTEND_OFFSET inline void normalize_hotend_offsets() { - LOOP_S_L_N(e, 1, HOTENDS) + for (uint8_t e = 1; e < HOTENDS; ++e) hotend_offset[e] -= hotend_offset[0]; hotend_offset[0].reset(); } @@ -618,7 +618,7 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { // This function requires normalize_hotend_offsets() to be called // inline void report_hotend_offsets() { - LOOP_S_L_N(e, 1, HOTENDS) + for (uint8_t e = 1; e < HOTENDS; ++e) SERIAL_ECHOLNPGM_P(PSTR("T"), e, PSTR(" Hotend Offset X"), hotend_offset[e].x, SP_Y_STR, hotend_offset[e].y, SP_Z_STR, hotend_offset[e].z); } #endif diff --git a/Marlin/src/gcode/calibrate/G76_M871.cpp b/Marlin/src/gcode/calibrate/G76_M871.cpp index f25c848f2fac..34b72ecdf317 100644 --- a/Marlin/src/gcode/calibrate/G76_M871.cpp +++ b/Marlin/src/gcode/calibrate/G76_M871.cpp @@ -81,7 +81,7 @@ * - `P` - Run probe temperature calibration. */ -#if BOTH(PTC_PROBE, PTC_BED) +#if ALL(PTC_PROBE, PTC_BED) static void say_waiting_for() { SERIAL_ECHOPGM("Waiting for "); } static void say_waiting_for_probe_heating() { say_waiting_for(); SERIAL_ECHOLNPGM("probe heating."); } diff --git a/Marlin/src/gcode/calibrate/M100.cpp b/Marlin/src/gcode/calibrate/M100.cpp index 338392b59746..3791c69f88bd 100644 --- a/Marlin/src/gcode/calibrate/M100.cpp +++ b/Marlin/src/gcode/calibrate/M100.cpp @@ -60,7 +60,7 @@ #define TEST_BYTE ((char) 0xE5) -#if EITHER(__AVR__, IS_32BIT_TEENSY) +#if ANY(__AVR__, IS_32BIT_TEENSY) extern char __bss_end; char *end_bss = &__bss_end, @@ -163,14 +163,14 @@ inline int32_t count_test_bytes(const char * const start_free_memory) { while (start_free_memory < end_free_memory) { print_hex_address(start_free_memory); // Print the address SERIAL_CHAR(':'); - LOOP_L_N(i, 16) { // and 16 data bytes + for (uint8_t i = 0; i < 16; ++i) { // and 16 data bytes if (i == 8) SERIAL_CHAR('-'); print_hex_byte(start_free_memory[i]); SERIAL_CHAR(' '); } serial_delay(25); SERIAL_CHAR('|'); // Point out non test bytes - LOOP_L_N(i, 16) { + for (uint8_t i = 0; i < 16; ++i) { char ccc = (char)start_free_memory[i]; // cast to char before automatically casting to char on assignment, in case the compiler is broken ccc = (ccc == TEST_BYTE) ? ' ' : '?'; SERIAL_CHAR(ccc); diff --git a/Marlin/src/gcode/calibrate/M48.cpp b/Marlin/src/gcode/calibrate/M48.cpp index 701e9386979a..2748d4e7bada 100644 --- a/Marlin/src/gcode/calibrate/M48.cpp +++ b/Marlin/src/gcode/calibrate/M48.cpp @@ -148,7 +148,7 @@ void GcodeSuite::M48() { float sample_sum = 0.0; - LOOP_L_N(n, n_samples) { + for (uint8_t n = 0; n < n_samples; ++n) { #if HAS_STATUS_MESSAGE // Display M48 progress in the status bar ui.status_printf(0, F(S_FMT ": %d/%d"), GET_TEXT(MSG_M48_POINT), int(n + 1), int(n_samples)); @@ -175,7 +175,7 @@ void GcodeSuite::M48() { } // Move from leg to leg in rapid succession - LOOP_L_N(l, n_legs - 1) { + for (uint8_t l = 0; l < n_legs - 1; ++l) { // Move some distance around the perimeter float delta_angle; @@ -243,7 +243,7 @@ void GcodeSuite::M48() { // Calculate the standard deviation so far. // The value after the last sample will be the final output. float dev_sum = 0.0; - LOOP_LE_N(j, n) dev_sum += sq(sample_set[j] - mean); + for (uint8_t j = 0; j <= n; ++j) dev_sum += sq(sample_set[j] - mean); sigma = SQRT(dev_sum / (n + 1)); if (verbose_level > 1) { diff --git a/Marlin/src/gcode/calibrate/M666.cpp b/Marlin/src/gcode/calibrate/M666.cpp index 546aa7fcb54a..dbee73f3947b 100644 --- a/Marlin/src/gcode/calibrate/M666.cpp +++ b/Marlin/src/gcode/calibrate/M666.cpp @@ -22,7 +22,7 @@ #include "../../inc/MarlinConfig.h" -#if EITHER(DELTA, HAS_EXTRA_ENDSTOPS) +#if ANY(DELTA, HAS_EXTRA_ENDSTOPS) #include "../gcode.h" diff --git a/Marlin/src/gcode/config/M200-M205.cpp b/Marlin/src/gcode/config/M200-M205.cpp index 8383be691466..e5e1edf3261f 100644 --- a/Marlin/src/gcode/config/M200-M205.cpp +++ b/Marlin/src/gcode/config/M200-M205.cpp @@ -168,7 +168,7 @@ void GcodeSuite::M201_report(const bool forReplay/*=true*/) { #endif #if ENABLED(DISTINCT_E_FACTORS) - LOOP_L_N(i, E_STEPPERS) { + for (uint8_t i = 0; i < E_STEPPERS; ++i) { report_echo_start(forReplay); SERIAL_ECHOLNPGM_P( PSTR(" M201 T"), i @@ -224,7 +224,7 @@ void GcodeSuite::M203_report(const bool forReplay/*=true*/) { #endif #if ENABLED(DISTINCT_E_FACTORS) - LOOP_L_N(i, E_STEPPERS) { + for (uint8_t i = 0; i < E_STEPPERS; ++i) { if (!forReplay) SERIAL_ECHO_START(); SERIAL_ECHOLNPGM_P( PSTR(" M203 T"), i diff --git a/Marlin/src/gcode/config/M218.cpp b/Marlin/src/gcode/config/M218.cpp index 62295f5771c6..d645685701ec 100644 --- a/Marlin/src/gcode/config/M218.cpp +++ b/Marlin/src/gcode/config/M218.cpp @@ -64,7 +64,7 @@ void GcodeSuite::M218() { void GcodeSuite::M218_report(const bool forReplay/*=true*/) { report_heading_etc(forReplay, F(STR_HOTEND_OFFSETS)); - LOOP_S_L_N(e, 1, HOTENDS) { + for (uint8_t e = 1; e < HOTENDS; ++e) { report_echo_start(forReplay); SERIAL_ECHOPGM_P( PSTR(" M218 T"), e, diff --git a/Marlin/src/gcode/config/M281.cpp b/Marlin/src/gcode/config/M281.cpp index e4ef3ab40b8c..2e7f08fe8659 100644 --- a/Marlin/src/gcode/config/M281.cpp +++ b/Marlin/src/gcode/config/M281.cpp @@ -56,7 +56,7 @@ void GcodeSuite::M281() { void GcodeSuite::M281_report(const bool forReplay/*=true*/) { report_heading_etc(forReplay, F(STR_SERVO_ANGLES)); - LOOP_L_N(i, NUM_SERVOS) { + for (uint8_t i = 0; i < NUM_SERVOS; ++i) { switch (i) { default: break; #if ENABLED(SWITCHING_EXTRUDER) diff --git a/Marlin/src/gcode/config/M305.cpp b/Marlin/src/gcode/config/M305.cpp index e7746923b318..48d7cf18820a 100644 --- a/Marlin/src/gcode/config/M305.cpp +++ b/Marlin/src/gcode/config/M305.cpp @@ -69,7 +69,7 @@ void GcodeSuite::M305() { SERIAL_ECHO_MSG("!Invalid Steinhart-Hart C coeff. (-0.01 < C < +0.01)"); } // If not setting then report parameters else if (t_index < 0) { // ...all user thermistors - LOOP_L_N(i, USER_THERMISTORS) + for (uint8_t i = 0; i < USER_THERMISTORS; ++i) thermalManager.M305_report(i); } else // ...one user thermistor diff --git a/Marlin/src/gcode/config/M43.cpp b/Marlin/src/gcode/config/M43.cpp index 3b95ccd3bb1c..7daf8afab8b6 100644 --- a/Marlin/src/gcode/config/M43.cpp +++ b/Marlin/src/gcode/config/M43.cpp @@ -61,7 +61,7 @@ inline void toggle_pins() { end = PARSED_PIN_INDEX('L', NUM_DIGITAL_PINS - 1), wait = parser.intval('W', 500); - LOOP_S_LE_N(i, start, end) { + for (uint8_t i = start; i <= end; ++i) { pin_t pin = GET_PIN_MAP_PIN_M43(i); if (!VALID_PIN(pin)) continue; if (M43_NEVER_TOUCH(i) || (!ignore_protection && pin_is_protected(pin))) { @@ -189,7 +189,7 @@ inline void servo_probe_test() { // DEPLOY and STOW 4 times and see if the signal follows // Then it is a mechanical switch SERIAL_ECHOLNPGM(". Deploy & stow 4 times"); - LOOP_L_N(i, 4) { + for (uint8_t i = 0; i < 4; ++i) { servo[probe_index].move(servo_angles[Z_PROBE_SERVO_NR][0]); // Deploy safe_delay(500); deploy_state = READ(PROBE_TEST_PIN); @@ -328,7 +328,7 @@ void GcodeSuite::M43() { const uint8_t pin_count = last_pin - first_pin + 1; uint8_t pin_state[pin_count]; bool can_watch = false; - LOOP_S_LE_N(i, first_pin, last_pin) { + for (uint8_t i = first_pin; i <= last_pin; ++i) { pin_t pin = GET_PIN_MAP_PIN_M43(i); if (!VALID_PIN(pin)) continue; if (M43_NEVER_TOUCH(i) || (!ignore_protection && pin_is_protected(pin))) continue; @@ -371,7 +371,7 @@ void GcodeSuite::M43() { #endif for (;;) { - LOOP_S_LE_N(i, first_pin, last_pin) { + for (uint8_t i = first_pin; i <= last_pin; ++i) { const pin_t pin = GET_PIN_MAP_PIN_M43(i); if (!VALID_PIN(pin)) continue; if (M43_NEVER_TOUCH(i) || (!ignore_protection && pin_is_protected(pin))) continue; @@ -400,7 +400,7 @@ void GcodeSuite::M43() { } else { // Report current state of selected pin(s) - LOOP_S_LE_N(i, first_pin, last_pin) { + for (uint8_t i = first_pin; i <= last_pin; ++i) { const pin_t pin = GET_PIN_MAP_PIN_M43(i); if (VALID_PIN(pin)) report_pin_state_extended(pin, ignore_protection, true); } diff --git a/Marlin/src/gcode/config/M672.cpp b/Marlin/src/gcode/config/M672.cpp index 257b49471f61..064d05d0b639 100644 --- a/Marlin/src/gcode/config/M672.cpp +++ b/Marlin/src/gcode/config/M672.cpp @@ -54,7 +54,7 @@ // b3 b2 b1 b0 ~b0 ... lo bits, NOT last bit // void M672_send(uint8_t b) { // bit rate requirement: 1kHz +/- 30% - LOOP_L_N(bits, 14) { + for (uint8_t bits = 0; bits < 14; ++bits) { switch (bits) { default: { OUT_WRITE(SMART_EFFECTOR_MOD_PIN, !!(b & 0x80)); b <<= 1; break; } // send bit, shift next into place case 7: diff --git a/Marlin/src/gcode/config/M92.cpp b/Marlin/src/gcode/config/M92.cpp index 888a7e5c21d0..e848665e6b6d 100644 --- a/Marlin/src/gcode/config/M92.cpp +++ b/Marlin/src/gcode/config/M92.cpp @@ -115,7 +115,7 @@ void GcodeSuite::M92_report(const bool forReplay/*=true*/, const int8_t e/*=-1*/ #endif #if ENABLED(DISTINCT_E_FACTORS) - LOOP_L_N(i, E_STEPPERS) { + for (uint8_t i = 0; i < E_STEPPERS; ++i) { if (e >= 0 && i != e) continue; report_echo_start(forReplay); SERIAL_ECHOLNPGM_P( diff --git a/Marlin/src/gcode/control/M111.cpp b/Marlin/src/gcode/control/M111.cpp index a92d334ae9d3..02f37f84974e 100644 --- a/Marlin/src/gcode/control/M111.cpp +++ b/Marlin/src/gcode/control/M111.cpp @@ -46,7 +46,7 @@ void GcodeSuite::M111() { SERIAL_ECHOPGM(STR_DEBUG_PREFIX); if (marlin_debug_flags) { uint8_t comma = 0; - LOOP_L_N(i, COUNT(debug_strings)) { + for (uint8_t i = 0; i < COUNT(debug_strings); ++i) { if (TEST(marlin_debug_flags, i)) { if (comma++) SERIAL_CHAR(','); SERIAL_ECHOPGM_P((PGM_P)pgm_read_ptr(&debug_strings[i])); diff --git a/Marlin/src/gcode/control/M380_M381.cpp b/Marlin/src/gcode/control/M380_M381.cpp index 6bcec891e281..20d24484ed0f 100644 --- a/Marlin/src/gcode/control/M380_M381.cpp +++ b/Marlin/src/gcode/control/M380_M381.cpp @@ -22,7 +22,7 @@ #include "../../inc/MarlinConfig.h" -#if EITHER(EXT_SOLENOID, MANUAL_SOLENOID_CONTROL) +#if ANY(EXT_SOLENOID, MANUAL_SOLENOID_CONTROL) #include "../gcode.h" #include "../../feature/solenoid.h" diff --git a/Marlin/src/gcode/control/M7-M9.cpp b/Marlin/src/gcode/control/M7-M9.cpp index ccde4f552cb9..837bb114b299 100644 --- a/Marlin/src/gcode/control/M7-M9.cpp +++ b/Marlin/src/gcode/control/M7-M9.cpp @@ -37,7 +37,7 @@ } #endif -#if EITHER(COOLANT_FLOOD, AIR_ASSIST) +#if ANY(COOLANT_FLOOD, AIR_ASSIST) #if ENABLED(AIR_ASSIST) #include "../../feature/spindle_laser.h" diff --git a/Marlin/src/gcode/control/M80_M81.cpp b/Marlin/src/gcode/control/M80_M81.cpp index 90b25e7ed34d..94dd5e3dd93f 100644 --- a/Marlin/src/gcode/control/M80_M81.cpp +++ b/Marlin/src/gcode/control/M80_M81.cpp @@ -79,7 +79,7 @@ void GcodeSuite::M81() { print_job_timer.stop(); - #if BOTH(HAS_FAN, PROBING_FANS_OFF) + #if ALL(HAS_FAN, PROBING_FANS_OFF) thermalManager.fans_paused = false; ZERO(thermalManager.saved_fan_speed); #endif diff --git a/Marlin/src/gcode/control/T.cpp b/Marlin/src/gcode/control/T.cpp index 5e8f6b5436d4..5e1579ec123a 100644 --- a/Marlin/src/gcode/control/T.cpp +++ b/Marlin/src/gcode/control/T.cpp @@ -23,7 +23,7 @@ #include "../gcode.h" #include "../../module/tool_change.h" -#if EITHER(HAS_MULTI_EXTRUDER, DEBUG_LEVELING_FEATURE) +#if ANY(HAS_MULTI_EXTRUDER, DEBUG_LEVELING_FEATURE) #include "../../module/motion.h" #endif diff --git a/Marlin/src/gcode/feature/camera/M240.cpp b/Marlin/src/gcode/feature/camera/M240.cpp index cf2e47ef6d2f..f79e80bcc236 100644 --- a/Marlin/src/gcode/feature/camera/M240.cpp +++ b/Marlin/src/gcode/feature/camera/M240.cpp @@ -84,7 +84,7 @@ inline void spin_photo_pin() { static constexpr uint32_t sequence[] = PHOTO_PULSES_US; - LOOP_L_N(i, COUNT(sequence)) + for (uint8_t i = 0; i < COUNT(sequence); ++i) pulse_photo_pin(sequence[i], !(i & 1)); } diff --git a/Marlin/src/gcode/feature/digipot/M907-M910.cpp b/Marlin/src/gcode/feature/digipot/M907-M910.cpp index 9ebe713cde46..8869f8d49462 100644 --- a/Marlin/src/gcode/feature/digipot/M907-M910.cpp +++ b/Marlin/src/gcode/feature/digipot/M907-M910.cpp @@ -51,7 +51,7 @@ void GcodeSuite::M907() { if (!parser.seen("BS" STR_AXES_LOGICAL)) return M907_report(); - if (parser.seenval('S')) LOOP_L_N(i, MOTOR_CURRENT_COUNT) stepper.set_digipot_current(i, parser.value_int()); + if (parser.seenval('S')) for (uint8_t i = 0; i < MOTOR_CURRENT_COUNT; ++i) stepper.set_digipot_current(i, parser.value_int()); LOOP_LOGICAL_AXES(i) if (parser.seenval(IAXIS_CHAR(i))) stepper.set_digipot_current(i, parser.value_int()); // X Y Z (I J K U V W) E (map to drivers according to DIGIPOT_CHANNELS. Default with NUM_AXES 3: map X Y Z E to X Y Z E0) // Additional extruders use B,C. // TODO: Change these parameters because 'E' is used and D should be reserved for debugging. B? @@ -82,7 +82,7 @@ void GcodeSuite::M907() { #endif )) return M907_report(); - if (parser.seenval('S')) LOOP_L_N(a, MOTOR_CURRENT_COUNT) stepper.set_digipot_current(a, parser.value_int()); + if (parser.seenval('S')) for (uint8_t a = 0; a < MOTOR_CURRENT_COUNT; ++a) stepper.set_digipot_current(a, parser.value_int()); #if HAS_X_Y_XY_I_J_K_U_V_W if (NUM_AXIS_GANG( @@ -104,7 +104,7 @@ void GcodeSuite::M907() { #if HAS_MOTOR_CURRENT_I2C // this one uses actual amps in floating point - if (parser.seenval('S')) LOOP_L_N(q, DIGIPOT_I2C_NUM_CHANNELS) digipot_i2c.set_current(q, parser.value_float()); + if (parser.seenval('S')) for (uint8_t q = 0; q < DIGIPOT_I2C_NUM_CHANNELS; ++q) digipot_i2c.set_current(q, parser.value_float()); LOOP_LOGICAL_AXES(i) if (parser.seenval(IAXIS_CHAR(i))) digipot_i2c.set_current(i, parser.value_float()); // X Y Z (I J K U V W) E (map to drivers according to pots adresses. Default with NUM_AXES 3 X Y Z E: map to X Y Z E0) // Additional extruders use B,C,D. // TODO: Change these parameters because 'E' is used and because 'D' should be reserved for debugging. B? diff --git a/Marlin/src/gcode/feature/leds/M7219.cpp b/Marlin/src/gcode/feature/leds/M7219.cpp index 40d3554dfe6e..1f74217be3cb 100644 --- a/Marlin/src/gcode/feature/leds/M7219.cpp +++ b/Marlin/src/gcode/feature/leds/M7219.cpp @@ -79,7 +79,7 @@ void GcodeSuite::M7219() { } if (parser.seen('P')) { - LOOP_L_N(r, MAX7219_LINES) { + for (uint8_t r = 0; r < MAX7219_LINES; ++r) { SERIAL_ECHOPGM("led_line["); if (r < 10) SERIAL_CHAR(' '); SERIAL_ECHO(r); diff --git a/Marlin/src/gcode/feature/network/M552-M554.cpp b/Marlin/src/gcode/feature/network/M552-M554.cpp index 0973fb87bf1a..ca7ddd0d360f 100644 --- a/Marlin/src/gcode/feature/network/M552-M554.cpp +++ b/Marlin/src/gcode/feature/network/M552-M554.cpp @@ -46,7 +46,7 @@ void MAC_report() { if (ethernet.hardware_enabled) { Ethernet.MACAddress(mac); SERIAL_ECHOPGM(" MAC: "); - LOOP_L_N(i, 6) { + for (uint8_t i = 0; i < 6; ++i) { if (mac[i] < 16) SERIAL_CHAR('0'); SERIAL_PRINT(mac[i], PrintBase::Hex); if (i < 5) SERIAL_CHAR(':'); @@ -59,7 +59,7 @@ void MAC_report() { // otherwise show the stored values void ip_report(const uint16_t cmd, FSTR_P const post, const IPAddress &ipo) { SERIAL_CHAR('M'); SERIAL_ECHO(cmd); SERIAL_CHAR(' '); - LOOP_L_N(i, 4) { + for (uint8_t i = 0; i < 4; ++i) { SERIAL_ECHO(ipo[i]); if (i < 3) SERIAL_CHAR('.'); } diff --git a/Marlin/src/gcode/feature/pause/M125.cpp b/Marlin/src/gcode/feature/pause/M125.cpp index d6e6cb93150a..b8d9d4811bc7 100644 --- a/Marlin/src/gcode/feature/pause/M125.cpp +++ b/Marlin/src/gcode/feature/pause/M125.cpp @@ -96,7 +96,7 @@ void GcodeSuite::M125() { const bool show_lcd = TERN0(HAS_MARLINUI_MENU, parser.boolval('P')); if (pause_print(retract, park_point, show_lcd, 0)) { - if (ENABLED(EXTENSIBLE_UI) || BOTH(EMERGENCY_PARSER, HOST_PROMPT_SUPPORT) || !sd_printing || show_lcd) { + if (ENABLED(HAS_DISPLAY) || ALL(EMERGENCY_PARSER, HOST_PROMPT_SUPPORT) || !sd_printing || show_lcd) { wait_for_confirmation(false, 0); resume_print(0, 0, -retract, 0); } diff --git a/Marlin/src/gcode/feature/pause/M701_M702.cpp b/Marlin/src/gcode/feature/pause/M701_M702.cpp index 6ec560f5c6d6..aec3a16a2a02 100644 --- a/Marlin/src/gcode/feature/pause/M701_M702.cpp +++ b/Marlin/src/gcode/feature/pause/M701_M702.cpp @@ -199,7 +199,7 @@ void GcodeSuite::M702() { #if HAS_PRUSA_MMU2 mmu2.unload(); #else - #if BOTH(HAS_MULTI_EXTRUDER, FILAMENT_UNLOAD_ALL_EXTRUDERS) + #if ALL(HAS_MULTI_EXTRUDER, FILAMENT_UNLOAD_ALL_EXTRUDERS) if (!parser.seenval('T')) { HOTEND_LOOP() { if (e != active_extruder) tool_change(e); diff --git a/Marlin/src/gcode/feature/trinamic/M122.cpp b/Marlin/src/gcode/feature/trinamic/M122.cpp index 61786d51ada1..a1765bfb43b4 100644 --- a/Marlin/src/gcode/feature/trinamic/M122.cpp +++ b/Marlin/src/gcode/feature/trinamic/M122.cpp @@ -30,6 +30,14 @@ /** * M122: Debug TMC drivers + * + * I - Flag to re-initialize stepper drivers with current settings. + * X, Y, Z, E - Flags to only report the specified axes. + * + * With TMC_DEBUG: + * V - Report raw register data. Refer to the datasheet to decipher the report. + * S - Flag to enable/disable continuous debug reporting. + * P - Interval between continuous debug reports, in milliseconds. */ void GcodeSuite::M122() { xyze_bool_t print_axis = ARRAY_N_1(LOGICAL_AXES, false); diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index 530cde7901a2..01b48a4af92b 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -82,7 +82,7 @@ millis_t GcodeSuite::previous_move_ms = 0, // Relative motion mode for each logical axis relative_t GcodeSuite::axis_relative; // Init in constructor -#if EITHER(HAS_AUTO_REPORTING, HOST_KEEPALIVE_FEATURE) +#if ANY(HAS_AUTO_REPORTING, HOST_KEEPALIVE_FEATURE) bool GcodeSuite::autoreport_paused; // = false #endif @@ -204,13 +204,13 @@ void GcodeSuite::get_destination_from_command() { TERN_(LASER_FEATURE, cutter.feedrate_mm_m = MMS_TO_MMM(feedrate_mm_s)); } - #if BOTH(PRINTCOUNTER, HAS_EXTRUDERS) + #if ALL(PRINTCOUNTER, HAS_EXTRUDERS) if (!DEBUGGING(DRYRUN) && !skip_move) print_job_timer.incFilamentUsed(destination.e - current_position.e); #endif // Get ABCDHI mixing factors - #if BOTH(MIXING_EXTRUDER, DIRECT_MIXING_IN_G1) + #if ALL(MIXING_EXTRUDER, DIRECT_MIXING_IN_G1) M165(); #endif @@ -442,7 +442,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 61: G61(); break; // G61: Apply/restore saved coordinates. #endif - #if BOTH(PTC_PROBE, PTC_BED) + #if ALL(PTC_PROBE, PTC_BED) case 76: G76(); break; // G76: Calibrate first layer compensation values #endif @@ -484,11 +484,11 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 7: M7(); break; // M7: Coolant Mist ON #endif - #if EITHER(AIR_ASSIST, COOLANT_FLOOD) + #if ANY(AIR_ASSIST, COOLANT_FLOOD) case 8: M8(); break; // M8: Air Assist / Coolant Flood ON #endif - #if EITHER(AIR_ASSIST, COOLANT_CONTROL) + #if ANY(AIR_ASSIST, COOLANT_CONTROL) case 9: M9(); break; // M9: Air Assist / Coolant OFF #endif @@ -528,7 +528,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 33: M33(); break; // M33: Get the long full path to a file or folder #endif - #if BOTH(SDCARD_SORT_ALPHA, SDSORT_GCODE) + #if ALL(SDCARD_SORT_ALPHA, SDSORT_GCODE) case 34: M34(); break; // M34: Set SD card sorting options #endif @@ -628,7 +628,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 154: M154(); break; // M154: Set position auto-report interval #endif - #if BOTH(AUTO_REPORT_TEMPERATURES, HAS_TEMP_SENSOR) + #if ALL(AUTO_REPORT_TEMPERATURES, HAS_TEMP_SENSOR) case 155: M155(); break; // M155: Set temperature auto-report interval #endif @@ -828,7 +828,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 364: if (M364()) return; break; // M364: SCARA Psi pos3 (90 deg to Theta) #endif - #if EITHER(EXT_SOLENOID, MANUAL_SOLENOID_CONTROL) + #if ANY(EXT_SOLENOID, MANUAL_SOLENOID_CONTROL) case 380: M380(); break; // M380: Activate solenoid on active (or specified) extruder case 381: M381(); break; // M381: Disable all solenoids or, if MANUAL_SOLENOID_CONTROL, active (or specified) solenoid #endif @@ -946,7 +946,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 665: M665(); break; // M665: Set Kinematics parameters #endif - #if EITHER(DELTA, HAS_EXTRA_ENDSTOPS) + #if ANY(DELTA, HAS_EXTRA_ENDSTOPS) case 666: M666(); break; // M666: Set delta or multiple endstop adjustment #endif @@ -987,7 +987,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { #if ANY(HAS_MOTOR_CURRENT_SPI, HAS_MOTOR_CURRENT_PWM, HAS_MOTOR_CURRENT_I2C, HAS_MOTOR_CURRENT_DAC) case 907: M907(); break; // M907: Set digital trimpot motor current using axis codes. - #if EITHER(HAS_MOTOR_CURRENT_SPI, HAS_MOTOR_CURRENT_DAC) + #if ANY(HAS_MOTOR_CURRENT_SPI, HAS_MOTOR_CURRENT_DAC) case 908: M908(); break; // M908: Control digital trimpot directly. #if HAS_MOTOR_CURRENT_DAC case 909: M909(); break; // M909: Print digipot/DAC current value diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index 52e8fbf8025e..73729491adab 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -336,7 +336,7 @@ #include "../feature/encoder_i2c.h" #endif -#if EITHER(IS_SCARA, POLAR) || defined(G0_FEEDRATE) +#if ANY(IS_SCARA, POLAR) || defined(G0_FEEDRATE) #define HAS_FAST_MOVES 1 #endif @@ -442,7 +442,7 @@ class GcodeSuite { process_subcommands_now(keep_leveling ? FPSTR(G28_STR) : TERN(CAN_SET_LEVELING_AFTER_G28, F("G28L0"), FPSTR(G28_STR))); } - #if EITHER(HAS_AUTO_REPORTING, HOST_KEEPALIVE_FEATURE) + #if ANY(HAS_AUTO_REPORTING, HOST_KEEPALIVE_FEATURE) static bool autoreport_paused; static bool set_autoreport_paused(const bool p) { const bool was = autoreport_paused; @@ -592,7 +592,7 @@ class GcodeSuite { static void G59(); #endif - #if BOTH(PTC_PROBE, PTC_BED) + #if ALL(PTC_PROBE, PTC_BED) static void G76(); #endif @@ -624,11 +624,11 @@ class GcodeSuite { static void M7(); #endif - #if EITHER(AIR_ASSIST, COOLANT_FLOOD) + #if ANY(AIR_ASSIST, COOLANT_FLOOD) static void M8(); #endif - #if EITHER(AIR_ASSIST, COOLANT_CONTROL) + #if ANY(AIR_ASSIST, COOLANT_CONTROL) static void M9(); #endif @@ -672,7 +672,7 @@ class GcodeSuite { #if ENABLED(LONG_FILENAME_HOST_SUPPORT) static void M33(); #endif - #if BOTH(SDCARD_SORT_ALPHA, SDSORT_GCODE) + #if ALL(SDCARD_SORT_ALPHA, SDSORT_GCODE) static void M34(); #endif #endif @@ -821,7 +821,7 @@ class GcodeSuite { static void M154(); #endif - #if BOTH(AUTO_REPORT_TEMPERATURES, HAS_TEMP_SENSOR) + #if ALL(AUTO_REPORT_TEMPERATURES, HAS_TEMP_SENSOR) static void M155(); #endif @@ -993,7 +993,7 @@ class GcodeSuite { static bool M364(); #endif - #if EITHER(EXT_SOLENOID, MANUAL_SOLENOID_CONTROL) + #if ANY(EXT_SOLENOID, MANUAL_SOLENOID_CONTROL) static void M380(); static void M381(); #endif @@ -1120,7 +1120,7 @@ class GcodeSuite { static void M665_report(const bool forReplay=true); #endif - #if EITHER(DELTA, HAS_EXTRA_ENDSTOPS) + #if ANY(DELTA, HAS_EXTRA_ENDSTOPS) static void M666(); static void M666_report(const bool forReplay=true); #endif diff --git a/Marlin/src/gcode/geometry/G92.cpp b/Marlin/src/gcode/geometry/G92.cpp index b36f21d3c08f..dfe4170620ec 100644 --- a/Marlin/src/gcode/geometry/G92.cpp +++ b/Marlin/src/gcode/geometry/G92.cpp @@ -88,28 +88,28 @@ void GcodeSuite::G92() { case 0: LOOP_LOGICAL_AXES(i) { if (parser.seenval(AXIS_CHAR(i))) { - const float l = parser.value_axis_units((AxisEnum)i), // Given axis coordinate value, converted to millimeters + const float l = parser.value_axis_units((AxisEnum)i), // Given axis coordinate value, converted to millimeters v = TERN0(HAS_EXTRUDERS, i == E_AXIS) ? l : LOGICAL_TO_NATIVE(l, i), // Axis position in NATIVE space (applying the existing offset) - d = v - current_position[i]; // How much is the current axis position altered by? + d = v - current_position[i]; // How much is the current axis position altered by? if (!NEAR_ZERO(d)) { - #if HAS_POSITION_SHIFT && NONE(IS_SCARA, POLARGRAPH) // When using workspaces... + #if HAS_POSITION_SHIFT && NONE(IS_SCARA, POLARGRAPH) // When using workspaces... if (TERN1(HAS_EXTRUDERS, i != E_AXIS)) { - position_shift[i] += d; // ...most axes offset the workspace... + position_shift[i] += d; // ...most axes offset the workspace... update_workspace_offset((AxisEnum)i); } else { #if HAS_EXTRUDERS sync_E = true; - current_position.e = v; // ...but E is set directly + current_position.e = v; // ...but E is set directly #endif } - #else // Without workspaces... + #else // Without workspaces... if (TERN1(HAS_EXTRUDERS, i != E_AXIS)) sync_XYZE = true; else { TERN_(HAS_EXTRUDERS, sync_E = true); } - current_position[i] = v; // ...set Current Position directly (like Marlin 1.0) + current_position[i] = v; // ...set Current Position directly (like Marlin 1.0) #endif } } diff --git a/Marlin/src/gcode/host/M114.cpp b/Marlin/src/gcode/host/M114.cpp index 3a75e687b846..979764f75e30 100644 --- a/Marlin/src/gcode/host/M114.cpp +++ b/Marlin/src/gcode/host/M114.cpp @@ -30,7 +30,7 @@ void report_all_axis_pos(const xyze_pos_t &pos, const uint8_t n=LOGICAL_AXES, const uint8_t precision=3) { char str[12]; - LOOP_L_N(a, n) { + for (uint8_t a = 0; a < n; ++a) { SERIAL_ECHOPGM_P((PGM_P)pgm_read_ptr(&SP_AXIS_LBL[a])); if (pos[a] >= 0) SERIAL_CHAR(' '); SERIAL_ECHO(dtostrf(pos[a], 1, precision, str)); diff --git a/Marlin/src/gcode/host/M115.cpp b/Marlin/src/gcode/host/M115.cpp index 8ca6d07ce269..806e593fcb4a 100644 --- a/Marlin/src/gcode/host/M115.cpp +++ b/Marlin/src/gcode/host/M115.cpp @@ -81,7 +81,7 @@ void GcodeSuite::M115() { // Although this code should work on all STM32 based boards SERIAL_ECHOPGM(" UUID:"); uint32_t *uid_address = (uint32_t*)UID_BASE; - LOOP_L_N(i, 3) { + for (uint8_t i = 0; i < 3; ++i) { const uint32_t UID = uint32_t(READ_REG(*(uid_address))); uid_address += 4U; for (int B = 24; B >= 0; B -= 8) print_hex_byte(UID >> B); diff --git a/Marlin/src/gcode/lcd/M145.cpp b/Marlin/src/gcode/lcd/M145.cpp index 942d20afd2f8..d72d5d678989 100644 --- a/Marlin/src/gcode/lcd/M145.cpp +++ b/Marlin/src/gcode/lcd/M145.cpp @@ -62,7 +62,7 @@ void GcodeSuite::M145() { void GcodeSuite::M145_report(const bool forReplay/*=true*/) { report_heading(forReplay, F(STR_MATERIAL_HEATUP)); - LOOP_L_N(i, PREHEAT_COUNT) { + for (uint8_t i = 0; i < PREHEAT_COUNT; ++i) { report_echo_start(forReplay); SERIAL_ECHOLNPGM_P( PSTR(" M145 S"), i diff --git a/Marlin/src/gcode/motion/G0_G1.cpp b/Marlin/src/gcode/motion/G0_G1.cpp index 88551f5eb6e9..957541a361d0 100644 --- a/Marlin/src/gcode/motion/G0_G1.cpp +++ b/Marlin/src/gcode/motion/G0_G1.cpp @@ -25,7 +25,7 @@ #include "../../MarlinCore.h" -#if BOTH(FWRETRACT, FWRETRACT_AUTORETRACT) +#if ALL(FWRETRACT, FWRETRACT_AUTORETRACT) #include "../../feature/fwretract.h" #endif @@ -72,7 +72,7 @@ void GcodeSuite::G0_G1(TERN_(HAS_FAST_MOVES, const bool fast_move/*=false*/)) { } #endif - #if BOTH(FWRETRACT, FWRETRACT_AUTORETRACT) + #if ALL(FWRETRACT, FWRETRACT_AUTORETRACT) if (MIN_AUTORETRACT <= MAX_AUTORETRACT) { // When M209 Autoretract is enabled, convert E-only moves to firmware retract/recover moves @@ -91,7 +91,7 @@ void GcodeSuite::G0_G1(TERN_(HAS_FAST_MOVES, const bool fast_move/*=false*/)) { #endif // FWRETRACT - #if EITHER(IS_SCARA, POLAR) + #if ANY(IS_SCARA, POLAR) fast_move ? prepare_fast_move_to_destination() : prepare_line_to_destination(); #else prepare_line_to_destination(); diff --git a/Marlin/src/gcode/parser.cpp b/Marlin/src/gcode/parser.cpp index 3fc1fc1625ad..ccd6b4111f10 100644 --- a/Marlin/src/gcode/parser.cpp +++ b/Marlin/src/gcode/parser.cpp @@ -229,11 +229,11 @@ void GCodeParser::parse(char *p) { } #endif - } break; + } break; #if ENABLED(GCODE_MOTION_MODES) - #if EITHER(BEZIER_CURVE_SUPPORT, ARC_SUPPORT) + #if ANY(BEZIER_CURVE_SUPPORT, ARC_SUPPORT) case 'I' ... 'J': case 'P': if (TERN1(BEZIER_CURVE_SUPPORT, motion_mode_codenum != 5) && TERN1(ARC_P_CIRCLES, !WITHIN(motion_mode_codenum, 2, 3)) diff --git a/Marlin/src/gcode/probe/G30.cpp b/Marlin/src/gcode/probe/G30.cpp index ad797688bb83..4c044af9d6e7 100644 --- a/Marlin/src/gcode/probe/G30.cpp +++ b/Marlin/src/gcode/probe/G30.cpp @@ -79,7 +79,7 @@ void GcodeSuite::G30() { TERN_(HAS_PTC, ptc.set_enabled(true)); if (!isnan(measured_z)) { SERIAL_ECHOLNPGM("Bed X: ", probepos.asLogical().x, " Y: ", probepos.asLogical().y, " Z: ", measured_z); - #if EITHER(DWIN_LCD_PROUI, DWIN_CREALITY_LCD_JYERSUI) + #if ANY(DWIN_LCD_PROUI, DWIN_CREALITY_LCD_JYERSUI) char msg[31], str_1[6], str_2[6], str_3[6]; sprintf_P(msg, PSTR("X:%s, Y:%s, Z:%s"), dtostrf(probepos.x, 1, 1, str_1), diff --git a/Marlin/src/gcode/probe/M423.cpp b/Marlin/src/gcode/probe/M423.cpp index fde5aaaf87c9..7c82a4f8af30 100644 --- a/Marlin/src/gcode/probe/M423.cpp +++ b/Marlin/src/gcode/probe/M423.cpp @@ -88,7 +88,7 @@ void GcodeSuite::M423() { void GcodeSuite::M423_report(const bool forReplay/*=true*/) { report_heading(forReplay, F("X-Twist Correction")); SERIAL_ECHOLNPGM(" M423 A", xatc.start, " I", xatc.spacing); - LOOP_L_N(x, XATC_MAX_POINTS) { + for (uint8_t x = 0; x < XATC_MAX_POINTS; ++x) { const float z = xatc.z_offset[x]; SERIAL_ECHOPGM(" M423 X", x, " Z"); serial_offset(isnan(z) ? 0 : z); diff --git a/Marlin/src/gcode/queue.cpp b/Marlin/src/gcode/queue.cpp index b64aa951129e..967ab76897f7 100644 --- a/Marlin/src/gcode/queue.cpp +++ b/Marlin/src/gcode/queue.cpp @@ -294,7 +294,7 @@ static bool serial_data_available(serial_index_t index) { #if NO_TIMEOUTS > 0 // Multiserial already handles dispatch to/from multiple ports static bool any_serial_data_available() { - LOOP_L_N(p, NUM_SERIAL) + for (uint8_t p = 0; p < NUM_SERIAL; ++p) if (serial_data_available(p)) return true; return false; @@ -313,7 +313,7 @@ inline int read_serial(const serial_index_t index) { return SERIAL_IMPL.read(ind */ void GCodeQueue::flush_rx() { // Flush receive buffer - LOOP_L_N(p, NUM_SERIAL) { + for (uint8_t p = 0; p < NUM_SERIAL; ++p) { if (!serial_data_available(p)) continue; // No data for this port? Skip. while (SERIAL_IMPL.available(p)) (void)read_serial(p); } @@ -441,7 +441,7 @@ void GCodeQueue::get_serial_commands() { // Unless a serial port has data, this will exit on next iteration hadData = false; - LOOP_L_N(p, NUM_SERIAL) { + for (uint8_t p = 0; p < NUM_SERIAL; ++p) { // Check if the queue is full and exit if it is. if (ring_buffer.full()) return; @@ -713,8 +713,8 @@ void GCodeQueue::advance() { void GCodeQueue::report_buffer_statistics() { SERIAL_ECHOLNPGM("D576" - " P:", planner.moves_free(), " ", -planner_buffer_underruns, " (", max_planner_buffer_empty_duration, ")" - " B:", BUFSIZE - ring_buffer.length, " ", -command_buffer_underruns, " (", max_command_buffer_empty_duration, ")" + " P:", planner.moves_free(), " ", planner_buffer_underruns, " (", max_planner_buffer_empty_duration, ")" + " B:", BUFSIZE - ring_buffer.length, " ", command_buffer_underruns, " (", max_command_buffer_empty_duration, ")" ); command_buffer_underruns = planner_buffer_underruns = 0; max_command_buffer_empty_duration = max_planner_buffer_empty_duration = 0; diff --git a/Marlin/src/gcode/sd/M1001.cpp b/Marlin/src/gcode/sd/M1001.cpp index 3c8f38a1448a..c49909646eaa 100644 --- a/Marlin/src/gcode/sd/M1001.cpp +++ b/Marlin/src/gcode/sd/M1001.cpp @@ -34,7 +34,7 @@ #include "../queue.h" #endif -#if EITHER(SET_PROGRESS_MANUALLY, SD_REPRINT_LAST_SELECTED_FILE) +#if ANY(SET_PROGRESS_MANUALLY, SD_REPRINT_LAST_SELECTED_FILE) #include "../../lcd/marlinui.h" #endif diff --git a/Marlin/src/gcode/sd/M34.cpp b/Marlin/src/gcode/sd/M34.cpp index 2dd7dc580c93..0a7d4d8c6221 100644 --- a/Marlin/src/gcode/sd/M34.cpp +++ b/Marlin/src/gcode/sd/M34.cpp @@ -22,7 +22,7 @@ #include "../../inc/MarlinConfig.h" -#if BOTH(SDCARD_SORT_ALPHA, SDSORT_GCODE) +#if ALL(SDCARD_SORT_ALPHA, SDSORT_GCODE) #include "../gcode.h" #include "../../sd/cardreader.h" diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 5b643386622a..b33720b2a5f3 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -31,12 +31,12 @@ #endif // MKS_LCD12864A/B is a variant of MKS_MINI_12864 -#if EITHER(MKS_LCD12864A, MKS_LCD12864B) +#if ANY(MKS_LCD12864A, MKS_LCD12864B) #define MKS_MINI_12864 #endif // MKS_MINI_12864_V3 and BTT_MINI_12864_V1 are identical to FYSETC_MINI_12864_2_1 -#if EITHER(MKS_MINI_12864_V3, BTT_MINI_12864_V1) +#if ANY(MKS_MINI_12864_V3, BTT_MINI_12864_V1) #define FYSETC_MINI_12864_2_1 #endif @@ -70,7 +70,7 @@ * IS_U8GLIB_ST7565_64128N : ST7565 128x64 LCD with SPI interface via U8GLib * IS_U8GLIB_LM6059_AF : LM6059 with Hardware SPI via U8GLib */ -#if EITHER(MKS_MINI_12864, ENDER2_STOCKDISPLAY) +#if ANY(MKS_MINI_12864, ENDER2_STOCKDISPLAY) #define MINIPANEL @@ -83,7 +83,7 @@ #define DOGLCD #define IS_ULTIPANEL 1 -#elif EITHER(DWIN_MARLINUI_PORTRAIT, DWIN_MARLINUI_LANDSCAPE) +#elif ANY(DWIN_MARLINUI_PORTRAIT, DWIN_MARLINUI_LANDSCAPE) #define IS_DWIN_MARLINUI 1 #define IS_ULTIPANEL 1 @@ -216,7 +216,7 @@ #define LCD_WIDTH 16 #define LCD_HEIGHT 2 -#elif EITHER(TFTGLCD_PANEL_SPI, TFTGLCD_PANEL_I2C) +#elif ANY(TFTGLCD_PANEL_SPI, TFTGLCD_PANEL_I2C) #define IS_TFTGLCD_PANEL 1 #define IS_ULTIPANEL 1 // Note that IS_ULTIPANEL leads to HAS_WIRED_LCD @@ -246,7 +246,7 @@ #define LCD_ST7920_DELAY_2 125 #define LCD_ST7920_DELAY_3 125 -#elif EITHER(ANET_FULL_GRAPHICS_LCD, ANET_FULL_GRAPHICS_LCD_ALT_WIRING) +#elif ANY(ANET_FULL_GRAPHICS_LCD, ANET_FULL_GRAPHICS_LCD_ALT_WIRING) #define IS_RRD_FG_SC 1 #define LCD_ST7920_DELAY_1 150 @@ -276,7 +276,7 @@ #endif // ST7565 / 64128N graphical displays -#if EITHER(MAKRPANEL, MINIPANEL) +#if ANY(MAKRPANEL, MINIPANEL) #define IS_ULTIPANEL 1 #define DOGLCD #if ENABLED(MAKRPANEL) @@ -337,11 +337,11 @@ #elif ANY(SPI_GRAPHICAL_TFT, TFT_320x240_SPI, TFT_480x320_SPI, TFT_LVGL_UI_SPI) #define TFT_INTERFACE_SPI #endif - #if EITHER(FSMC_GRAPHICAL_TFT, SPI_GRAPHICAL_TFT) + #if ANY(FSMC_GRAPHICAL_TFT, SPI_GRAPHICAL_TFT) #define TFT_CLASSIC_UI #elif ANY(TFT_320x240, TFT_480x320, TFT_320x240_SPI, TFT_480x320_SPI) #define TFT_COLOR_UI - #elif EITHER(TFT_LVGL_UI_FSMC, TFT_LVGL_UI_SPI) + #elif ANY(TFT_LVGL_UI_FSMC, TFT_LVGL_UI_SPI) #define TFT_LVGL_UI #endif #endif @@ -387,7 +387,7 @@ #define IS_ULTIPANEL 1 #endif -#elif EITHER(LCD_SAINSMART_I2C_1602, LCD_SAINSMART_I2C_2004) +#elif ANY(LCD_SAINSMART_I2C_1602, LCD_SAINSMART_I2C_2004) #define LCD_I2C_TYPE_PCF8575 // I2C Character-based 12864 display #define LCD_I2C_ADDRESS 0x27 // I2C Address of the port expander @@ -425,7 +425,7 @@ #endif -#if EITHER(LCD_I2C_TYPE_MCP23017, LCD_I2C_TYPE_MCP23008) && DISABLED(NO_LCD_DETECT) +#if ANY(LCD_I2C_TYPE_MCP23017, LCD_I2C_TYPE_MCP23008) && DISABLED(NO_LCD_DETECT) #define DETECT_I2C_LCD_DEVICE 1 #endif @@ -463,15 +463,15 @@ #define IS_ULTIPANEL 1 #endif -#if EITHER(IS_ULTIPANEL, ULTRA_LCD) +#if ANY(IS_ULTIPANEL, ULTRA_LCD) #define HAS_WIRED_LCD 1 #endif -#if EITHER(IS_ULTIPANEL, REPRAPWORLD_KEYPAD) +#if ANY(IS_ULTIPANEL, REPRAPWORLD_KEYPAD) #define IS_NEWPANEL 1 #endif -#if EITHER(ZONESTAR_LCD, REPRAPWORLD_KEYPAD) +#if ANY(ZONESTAR_LCD, REPRAPWORLD_KEYPAD) #define IS_RRW_KEYPAD 1 #ifndef REPRAPWORLD_KEYPAD_MOVE_STEP #define REPRAPWORLD_KEYPAD_MOVE_STEP 1.0 @@ -493,10 +493,10 @@ #endif // Aliases for LCD features -#if EITHER(DWIN_CREALITY_LCD, DWIN_LCD_PROUI) +#if ANY(DWIN_CREALITY_LCD, DWIN_LCD_PROUI) #define HAS_DWIN_E3V2_BASIC 1 #endif -#if EITHER(HAS_DWIN_E3V2_BASIC, DWIN_CREALITY_LCD_JYERSUI) +#if ANY(HAS_DWIN_E3V2_BASIC, DWIN_CREALITY_LCD_JYERSUI) #define HAS_DWIN_E3V2 1 #endif @@ -639,10 +639,10 @@ #define E_TERN_(N) TERN_(HAS_MULTI_EXTRUDER, N) #define E_TERN0(N) TERN0(HAS_MULTI_EXTRUDER, N) -#if EITHER(SWITCHING_EXTRUDER, MECHANICAL_SWITCHING_EXTRUDER) +#if ANY(SWITCHING_EXTRUDER, MECHANICAL_SWITCHING_EXTRUDER) #define HAS_SWITCHING_EXTRUDER 1 #endif -#if EITHER(SWITCHING_NOZZLE, MECHANICAL_SWITCHING_NOZZLE) +#if ANY(SWITCHING_NOZZLE, MECHANICAL_SWITCHING_NOZZLE) #define HAS_SWITCHING_NOZZLE 1 #endif @@ -700,14 +700,14 @@ #endif // Number of hotends... -#if EITHER(SINGLENOZZLE, MIXING_EXTRUDER) // Only one for singlenozzle or mixing extruder +#if ANY(SINGLENOZZLE, MIXING_EXTRUDER) // Only one for singlenozzle or mixing extruder #define HOTENDS 1 -#elif HAS_SWITCHING_EXTRUDER && !HAS_SWITCHING_NOZZLE // One for each pair of abstract "extruders" +#elif HAS_SWITCHING_EXTRUDER && !HAS_SWITCHING_NOZZLE // One for each pair of abstract "extruders" #define HOTENDS E_STEPPERS #elif TEMP_SENSOR_0 - #define HOTENDS EXTRUDERS // One per extruder if at least one heater exists + #define HOTENDS EXTRUDERS // One per extruder if at least one heater exists #else - #define HOTENDS 0 // A machine with no hotends at all can still extrude + #define HOTENDS 0 // A machine with no hotends at all can still extrude #endif // More than one hotend... @@ -833,8 +833,8 @@ #undef AVOID_OBSTACLES #undef ENDSTOPPULLUP_XMIN #undef ENDSTOPPULLUP_XMAX - #undef X_MIN_ENDSTOP_INVERTING - #undef X_MAX_ENDSTOP_INVERTING + #undef X_MIN_ENDSTOP_HIT_STATE + #undef X_MAX_ENDSTOP_HIT_STATE #undef X2_DRIVER_TYPE #undef X_ENABLE_ON #undef DISABLE_X @@ -1104,7 +1104,7 @@ #if DISABLED(SINGLENOZZLE) #undef SINGLENOZZLE_STANDBY_TEMP #endif -#if !BOTH(HAS_FAN, SINGLENOZZLE) +#if !ALL(HAS_FAN, SINGLENOZZLE) #undef SINGLENOZZLE_STANDBY_FAN #endif @@ -1409,7 +1409,7 @@ #if DISABLED(NOZZLE_AS_PROBE) #define HAS_PROBE_XY_OFFSET 1 #endif - #if BOTH(DELTA, SENSORLESS_PROBING) + #if ALL(DELTA, SENSORLESS_PROBING) #define HAS_DELTA_SENSORLESS_PROBING 1 #endif #if NONE(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN, HAS_DELTA_SENSORLESS_PROBING) @@ -1421,7 +1421,7 @@ #ifndef Z_PROBE_LOW_POINT #define Z_PROBE_LOW_POINT -5 #endif - #if EITHER(Z_PROBE_ALLEN_KEY, MAG_MOUNTED_PROBE) + #if ANY(Z_PROBE_ALLEN_KEY, MAG_MOUNTED_PROBE) #define PROBE_TRIGGERED_WHEN_STOWED_TEST 1 // Extra test for Allen Key Probe #endif #if MULTIPLE_PROBING > 1 @@ -1451,14 +1451,14 @@ */ #if ENABLED(AUTO_BED_LEVELING_UBL) #undef LCD_BED_LEVELING - #if EITHER(DELTA, SEGMENT_LEVELED_MOVES) + #if ANY(DELTA, SEGMENT_LEVELED_MOVES) #define UBL_SEGMENTED 1 #endif #endif -#if EITHER(AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_3POINT) +#if ANY(AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_3POINT) #define ABL_PLANAR 1 #endif -#if EITHER(AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_BILINEAR) +#if ANY(AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_BILINEAR) #define ABL_USES_GRID 1 #endif #if ANY(AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_BILINEAR, AUTO_BED_LEVELING_3POINT) @@ -1467,16 +1467,16 @@ #if ANY(AUTO_BED_LEVELING_BILINEAR, AUTO_BED_LEVELING_UBL, MESH_BED_LEVELING) #define HAS_MESH 1 #endif -#if EITHER(AUTO_BED_LEVELING_UBL, AUTO_BED_LEVELING_3POINT) +#if ANY(AUTO_BED_LEVELING_UBL, AUTO_BED_LEVELING_3POINT) #define NEEDS_THREE_PROBE_POINTS 1 #endif -#if EITHER(HAS_ABL_NOT_UBL, AUTO_BED_LEVELING_UBL) +#if ANY(HAS_ABL_NOT_UBL, AUTO_BED_LEVELING_UBL) #define HAS_ABL_OR_UBL 1 #if DISABLED(PROBE_MANUALLY) #define HAS_AUTOLEVEL 1 #endif #endif -#if EITHER(HAS_ABL_OR_UBL, MESH_BED_LEVELING) +#if ANY(HAS_ABL_OR_UBL, MESH_BED_LEVELING) #define HAS_LEVELING 1 #if DISABLED(AUTO_BED_LEVELING_UBL) #define PLANNER_LEVELING 1 @@ -1487,7 +1487,7 @@ #undef ENABLE_LEVELING_AFTER_G28 #undef G29_RETRY_AND_RECOVER #endif -#if !HAS_LEVELING || EITHER(MESH_BED_LEVELING, AUTO_BED_LEVELING_UBL) +#if !HAS_LEVELING || ANY(MESH_BED_LEVELING, AUTO_BED_LEVELING_UBL) #undef PROBE_MANUALLY #endif #if ANY(HAS_BED_PROBE, PROBE_MANUALLY, MESH_BED_LEVELING) @@ -1496,7 +1496,7 @@ #ifdef GRID_MAX_POINTS_X #define GRID_MAX_POINTS ((GRID_MAX_POINTS_X) * (GRID_MAX_POINTS_Y)) - #define GRID_LOOP(A,B) LOOP_L_N(A, GRID_MAX_POINTS_X) LOOP_L_N(B, GRID_MAX_POINTS_Y) + #define GRID_LOOP(A,B) for (uint8_t A = 0; A < GRID_MAX_POINTS_X; ++A) for (uint8_t B = 0; B < GRID_MAX_POINTS_Y; ++B) #endif // Slim menu optimizations @@ -1507,13 +1507,13 @@ /** * CoreXY, CoreXZ, and CoreYZ - and their reverse */ -#if EITHER(COREXY, COREYX) +#if ANY(COREXY, COREYX) #define CORE_IS_XY 1 #endif -#if EITHER(COREXZ, COREZX) +#if ANY(COREXZ, COREZX) #define CORE_IS_XZ 1 #endif -#if EITHER(COREYZ, COREZY) +#if ANY(COREYZ, COREZY) #define CORE_IS_YZ 1 #endif #if CORE_IS_XY || CORE_IS_XZ || CORE_IS_YZ @@ -1534,7 +1534,7 @@ #define CORE_AXIS_2 C_AXIS #endif #define CORESIGN(n) (ANY(COREYX, COREZX, COREZY) ? (-(n)) : (n)) -#elif EITHER(MARKFORGED_XY, MARKFORGED_YX) +#elif ANY(MARKFORGED_XY, MARKFORGED_YX) // Markforged kinematics #define CORE_AXIS_1 A_AXIS #define CORE_AXIS_2 B_AXIS @@ -1558,7 +1558,7 @@ #endif // This flag indicates some kind of jerk storage is needed -#if EITHER(CLASSIC_JERK, IS_KINEMATIC) +#if ANY(CLASSIC_JERK, IS_KINEMATIC) #define HAS_CLASSIC_JERK 1 #endif @@ -1622,12 +1622,12 @@ * - TFT_COLOR * - GRAPHICAL_TFT_UPSCALE */ -#if EITHER(MKS_TS35_V2_0, BTT_TFT35_SPI_V1_0) // ST7796 +#if ANY(MKS_TS35_V2_0, BTT_TFT35_SPI_V1_0) // ST7796 #define TFT_DEFAULT_DRIVER ST7796 #define TFT_DEFAULT_ORIENTATION TFT_EXCHANGE_XY #define TFT_RES_480x320 #define TFT_INTERFACE_SPI -#elif EITHER(LERDGE_TFT35, ANET_ET5_TFT35) // ST7796 +#elif ANY(LERDGE_TFT35, ANET_ET5_TFT35) // ST7796 #define TFT_DEFAULT_ORIENTATION TFT_EXCHANGE_XY #define TFT_RES_480x320 #define TFT_INTERFACE_FSMC @@ -1645,7 +1645,7 @@ #define TFT_DEFAULT_ORIENTATION 0 #define TFT_RES_480x272 #define TFT_INTERFACE_FSMC -#elif EITHER(MKS_ROBIN_TFT_V1_1R, LONGER_LK_TFT28) // ILI9328 or R61505 +#elif ANY(MKS_ROBIN_TFT_V1_1R, LONGER_LK_TFT28) // ILI9328 or R61505 #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY | TFT_INVERT_X | TFT_INVERT_Y) #define TFT_RES_320x240 #define TFT_INTERFACE_FSMC @@ -1756,13 +1756,13 @@ #endif #endif -#if EITHER(TFT_320x240, TFT_320x240_SPI) +#if ANY(TFT_320x240, TFT_320x240_SPI) #define HAS_UI_320x240 1 -#elif EITHER(TFT_480x320, TFT_480x320_SPI) +#elif ANY(TFT_480x320, TFT_480x320_SPI) #define HAS_UI_480x320 1 -#elif EITHER(TFT_480x272, TFT_480x272_SPI) +#elif ANY(TFT_480x272, TFT_480x272_SPI) #define HAS_UI_480x272 1 -#elif EITHER(TFT_1024x600_LTDC, TFT_1024x600_SIM) +#elif ANY(TFT_1024x600_LTDC, TFT_1024x600_SIM) #define HAS_UI_1024x600 1 #endif #if ANY(HAS_UI_320x240, HAS_UI_480x320, HAS_UI_480x272) diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h index 70644ddf0d1b..683eeb3da217 100644 --- a/Marlin/src/inc/Conditionals_adv.h +++ b/Marlin/src/inc/Conditionals_adv.h @@ -245,8 +245,8 @@ #define DISABLE_IDLE_E #endif -#define _OR_HAS_DI(A) || BOTH(HAS_##A##_AXIS, DISABLE_IDLE_##A) -#if BOTH(HAS_EXTRUDERS, DISABLE_IDLE_E) MAP(_OR_HAS_DI, X, Y, Z, I, J, K, U, V, W) +#define _OR_HAS_DI(A) || ALL(HAS_##A##_AXIS, DISABLE_IDLE_##A) +#if ALL(HAS_EXTRUDERS, DISABLE_IDLE_E) MAP(_OR_HAS_DI, X, Y, Z, I, J, K, U, V, W) #define HAS_DISABLE_IDLE_AXES 1 #endif #undef _OR_HAS_DI @@ -688,8 +688,6 @@ #define TEMP_SENSOR_BED_IS_CUSTOM 1 #endif #else - #undef THERMAL_PROTECTION_BED - #undef THERMAL_PROTECTION_BED_PERIOD #undef BED_MINTEMP #undef BED_MAXTEMP #endif @@ -770,11 +768,11 @@ #endif #endif -#if ENABLED(MIXING_EXTRUDER) && (ENABLED(RETRACT_SYNC_MIXING) || BOTH(FILAMENT_LOAD_UNLOAD_GCODES, FILAMENT_UNLOAD_ALL_EXTRUDERS)) +#if ENABLED(MIXING_EXTRUDER) && (ENABLED(RETRACT_SYNC_MIXING) || ALL(FILAMENT_LOAD_UNLOAD_GCODES, FILAMENT_UNLOAD_ALL_EXTRUDERS)) #define HAS_MIXER_SYNC_CHANNEL 1 #endif -#if EITHER(DUAL_X_CARRIAGE, MULTI_NOZZLE_DUPLICATION) +#if ANY(DUAL_X_CARRIAGE, MULTI_NOZZLE_DUPLICATION) #define HAS_DUPLICATION_MODE 1 #endif @@ -812,7 +810,7 @@ #undef MENU_ADDAUTOSTART #endif -#if EITHER(HAS_MEDIA, SET_PROGRESS_MANUALLY) +#if ANY(HAS_MEDIA, SET_PROGRESS_MANUALLY) #define HAS_PRINT_PROGRESS 1 #endif @@ -838,7 +836,7 @@ #define HAS_EXTRA_PROGRESS 1 #endif -#if HAS_PRINT_PROGRESS && EITHER(PRINT_PROGRESS_SHOW_DECIMALS, SHOW_REMAINING_TIME) +#if HAS_PRINT_PROGRESS && ANY(PRINT_PROGRESS_SHOW_DECIMALS, SHOW_REMAINING_TIME) #define HAS_PRINT_PROGRESS_PERMYRIAD 1 #endif @@ -856,7 +854,7 @@ #if ANY(X_DUAL_ENDSTOPS, Y_DUAL_ENDSTOPS, Z_MULTI_ENDSTOPS) #define HAS_EXTRA_ENDSTOPS 1 #endif -#if EITHER(MIN_SOFTWARE_ENDSTOPS, MAX_SOFTWARE_ENDSTOPS) +#if ANY(MIN_SOFTWARE_ENDSTOPS, MAX_SOFTWARE_ENDSTOPS) #define HAS_SOFTWARE_ENDSTOPS 1 #endif #if ANY(EXTENSIBLE_UI, IS_NEWPANEL, EMERGENCY_PARSER, HAS_ADC_BUTTONS, HAS_DWIN_E3V2) @@ -878,7 +876,7 @@ #define HAS_GCODE_M255 1 #endif -#if EITHER(DIGIPOT_MCP4018, DIGIPOT_MCP4451) +#if ANY(DIGIPOT_MCP4018, DIGIPOT_MCP4451) #define HAS_MOTOR_CURRENT_I2C 1 #endif @@ -929,7 +927,7 @@ // Spindle/Laser power display types // Defined here so sanity checks can use them // -#if EITHER(SPINDLE_FEATURE, LASER_FEATURE) +#if ANY(SPINDLE_FEATURE, LASER_FEATURE) #define HAS_CUTTER 1 #define _CUTTER_POWER_PWM255 1 #define _CUTTER_POWER_PERCENT 2 @@ -1002,7 +1000,7 @@ #endif #endif -#if EITHER(FYSETC_MINI_12864_2_1, FYSETC_242_OLED_12864) +#if ANY(FYSETC_MINI_12864_2_1, FYSETC_242_OLED_12864) #ifndef LED_USER_PRESET_GREEN #define LED_USER_PRESET_GREEN 128 #endif @@ -1037,7 +1035,7 @@ #endif #endif -#if BOTH(LED_CONTROL_MENU, NEOPIXEL2_SEPARATE) +#if ALL(LED_CONTROL_MENU, NEOPIXEL2_SEPARATE) #ifndef LED2_USER_PRESET_RED #define LED2_USER_PRESET_RED 255 #endif @@ -1060,7 +1058,7 @@ #endif // Full Touch Screen needs 'tft/xpt2046' -#if EITHER(TFT_TOUCH_DEVICE_XPT2046, HAS_TFT_LVGL_UI) +#if ANY(TFT_TOUCH_DEVICE_XPT2046, HAS_TFT_LVGL_UI) #define HAS_TFT_XPT2046 1 #endif @@ -1190,7 +1188,7 @@ #endif // Power Monitor sensors -#if EITHER(POWER_MONITOR_CURRENT, POWER_MONITOR_VOLTAGE) +#if ANY(POWER_MONITOR_CURRENT, POWER_MONITOR_VOLTAGE) #define HAS_POWER_MONITOR 1 #if ENABLED(POWER_MONITOR_CURRENT) && (ENABLED(POWER_MONITOR_VOLTAGE) || defined(POWER_MONITOR_FIXED_VOLTAGE)) #define HAS_POWER_MONITOR_WATTS 1 @@ -1209,7 +1207,7 @@ // Flags for Case Light having a color property or a single pin #if ENABLED(CASE_LIGHT_ENABLE) - #if EITHER(CASE_LIGHT_USE_NEOPIXEL, CASE_LIGHT_USE_RGB_LED) + #if ANY(CASE_LIGHT_USE_NEOPIXEL, CASE_LIGHT_USE_RGB_LED) #define CASE_LIGHT_IS_COLOR_LED 1 #else #define NEED_CASE_LIGHT_PIN 1 @@ -1226,7 +1224,7 @@ #define NEED_LSF 1 #endif -#if BOTH(HAS_TFT_LVGL_UI, CUSTOM_MENU_MAIN) +#if ALL(HAS_TFT_LVGL_UI, CUSTOM_MENU_MAIN) #define _HAS_1(N) (defined(MAIN_MENU_ITEM_##N##_DESC) && defined(MAIN_MENU_ITEM_##N##_GCODE)) #define HAS_USER_ITEM(V...) DO(HAS,||,V) #else @@ -1253,18 +1251,18 @@ #if !HAS_MULTI_SERIAL #undef MEATPACK_ON_SERIAL_PORT_2 #endif -#if EITHER(MEATPACK_ON_SERIAL_PORT_1, MEATPACK_ON_SERIAL_PORT_2) +#if ANY(MEATPACK_ON_SERIAL_PORT_1, MEATPACK_ON_SERIAL_PORT_2) #define HAS_MEATPACK 1 #endif // AVR are (usually) too limited in resources to store the configuration into the binary -#if ENABLED(CONFIGURATION_EMBEDDING) && !defined(FORCE_CONFIG_EMBED) && (defined(__AVR__) || !HAS_MEDIA || EITHER(SDCARD_READONLY, DISABLE_M503)) +#if ENABLED(CONFIGURATION_EMBEDDING) && !defined(FORCE_CONFIG_EMBED) && (defined(__AVR__) || !HAS_MEDIA || ANY(SDCARD_READONLY, DISABLE_M503)) #undef CONFIGURATION_EMBEDDING #define CANNOT_EMBED_CONFIGURATION defined(__AVR__) #endif // Input shaping -#if EITHER(INPUT_SHAPING_X, INPUT_SHAPING_Y) +#if ANY(INPUT_SHAPING_X, INPUT_SHAPING_Y) #define HAS_ZV_SHAPING 1 #endif diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index d137e1d9c198..6d2bbd6edf22 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -38,7 +38,7 @@ #endif // Linear advance uses Jerk since E is an isolated axis -#if BOTH(HAS_JUNCTION_DEVIATION, LIN_ADVANCE) +#if ALL(HAS_JUNCTION_DEVIATION, LIN_ADVANCE) #define HAS_LINEAR_E_JERK 1 #endif @@ -48,7 +48,7 @@ // Set additional flags to let HALs choose in their Conditionals_post.h #if ANY(FLASH_EEPROM_EMULATION, SRAM_EEPROM_EMULATION, SDCARD_EEPROM_EMULATION, QSPI_EEPROM) #define USE_EMULATED_EEPROM 1 - #elif EITHER(I2C_EEPROM, SPI_EEPROM) + #elif ANY(I2C_EEPROM, SPI_EEPROM) #define USE_WIRED_EEPROM 1 #elif ENABLED(IIC_BL24CXX_EEPROM) // nothing @@ -265,7 +265,7 @@ #endif // Calibration codes only for non-core axes -#if EITHER(BACKLASH_GCODE, CALIBRATION_GCODE) +#if ANY(BACKLASH_GCODE, CALIBRATION_GCODE) #if ANY(IS_CORE, MARKFORGED_XY, MARKFORGED_YX) #define CAN_CALIBRATE(A,B) TERN0(HAS_##A##_AXIS, (_AXIS(A) == B)) #else @@ -466,14 +466,14 @@ #elif ENABLED(AZSMZ_12864) #define _LCD_CONTRAST_MIN 120 #define _LCD_CONTRAST_INIT 190 -#elif EITHER(MKS_LCD12864A, MKS_LCD12864B) +#elif ANY(MKS_LCD12864A, MKS_LCD12864B) #define _LCD_CONTRAST_MIN 120 #define _LCD_CONTRAST_INIT 205 -#elif EITHER(MKS_MINI_12864, ENDER2_STOCKDISPLAY) +#elif ANY(MKS_MINI_12864, ENDER2_STOCKDISPLAY) #define _LCD_CONTRAST_MIN 120 #define _LCD_CONTRAST_INIT 195 -#elif EITHER(MKS_MINI_12864_V3, BTT_MINI_12864_V1) - #define _LCD_CONTRAST_MIN 255 +#elif ENABLED(FYSETC_MINI_12864_2_1) + #define _LCD_CONTRAST_MIN 230 #define _LCD_CONTRAST_INIT 255 #elif ENABLED(FYSETC_MINI_12864) #define _LCD_CONTRAST_MIN 180 @@ -558,7 +558,7 @@ #endif #endif - #if DISABLED(USB_FLASH_DRIVE_SUPPORT) || BOTH(MULTI_VOLUME, VOLUME_SD_ONBOARD) + #if DISABLED(USB_FLASH_DRIVE_SUPPORT) || ALL(MULTI_VOLUME, VOLUME_SD_ONBOARD) #if ENABLED(ONBOARD_SDIO) #define NEED_SD2CARD_SDIO 1 #else @@ -731,13 +731,13 @@ // Add LIB_MAX6675 / LIB_MAX31855 / LIB_MAX31865 to the build_flags // to select a USER library for MAX6675, MAX31855, MAX31865 // - #if BOTH(HAS_MAX6675, LIB_MAX6675) + #if ALL(HAS_MAX6675, LIB_MAX6675) #define USE_LIB_MAX6675 1 #endif - #if BOTH(HAS_MAX31855, LIB_MAX31855) + #if ALL(HAS_MAX31855, LIB_MAX31855) #define USE_ADAFRUIT_MAX31855 1 #endif - #if BOTH(HAS_MAX31865, LIB_MAX31865) + #if ALL(HAS_MAX31865, LIB_MAX31865) #define USE_ADAFRUIT_MAX31865 1 #elif HAS_MAX31865 #define LIB_INTERNAL_MAX31865 1 @@ -1375,7 +1375,7 @@ * - Z_PROBE_SLED uses SOL1_PIN, when defined (unless EXT_SOLENOID is enabled) */ #if ANY(EXT_SOLENOID, MANUAL_SOLENOID_CONTROL, PARKING_EXTRUDER, SOLENOID_PROBE, Z_PROBE_SLED) - #if PIN_EXISTS(SOL0) && (EITHER(MANUAL_SOLENOID_CONTROL, PARKING_EXTRUDER) || BOTH(EXT_SOLENOID, HAS_EXTRUDERS)) + #if PIN_EXISTS(SOL0) && (ANY(MANUAL_SOLENOID_CONTROL, PARKING_EXTRUDER) || ALL(EXT_SOLENOID, HAS_EXTRUDERS)) #define HAS_SOLENOID_0 1 #endif #if PIN_EXISTS(SOL1) && (ANY(MANUAL_SOLENOID_CONTROL, PARKING_EXTRUDER, SOLENOID_PROBE, Z_PROBE_SLED) || TERN0(EXT_SOLENOID, E_STEPPERS > 1)) @@ -1409,7 +1409,7 @@ #if ANY(STEALTHCHOP_E, STEALTHCHOP_XY, STEALTHCHOP_Z, STEALTHCHOP_I, STEALTHCHOP_J, STEALTHCHOP_K, STEALTHCHOP_U, STEALTHCHOP_V, STEALTHCHOP_W) #define STEALTHCHOP_ENABLED 1 #endif - #if EITHER(SENSORLESS_HOMING, SENSORLESS_PROBING) + #if ANY(SENSORLESS_HOMING, SENSORLESS_PROBING) #define USE_SENSORLESS 1 #endif @@ -1970,7 +1970,7 @@ #define HAS_Y_ENDSTOP 1 #endif -#if _USE_STOP(Z,,MIN,EITHER(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN, HAS_DELTA_SENSORLESS_PROBING)) +#if _USE_STOP(Z,,MIN,ANY(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN, HAS_DELTA_SENSORLESS_PROBING)) #define USE_Z_MIN 1 #if !HAS_DELTA_SENSORLESS_PROBING #define HAS_Z_MIN_PIN 1 @@ -2037,7 +2037,7 @@ #define HAS_W_ENDSTOP 1 #endif -#if EITHER(DUAL_X_CARRIAGE, X_DUAL_ENDSTOPS) +#if ANY(DUAL_X_CARRIAGE, X_DUAL_ENDSTOPS) #if _USE_STOP(X,2,MIN,) #define USE_X2_MIN 1 #elif _USE_STOP(X,2,MAX,) @@ -2240,8 +2240,11 @@ #if HOTENDS > 7 && HAS_ADC_TEST(7) #define HAS_TEMP_ADC_7 1 #endif -#if HAS_ADC_TEST(BED) - #define HAS_TEMP_ADC_BED 1 +#if TEMP_SENSOR_BED + #define HAS_HEATED_BED 1 + #if HAS_ADC_TEST(BED) + #define HAS_TEMP_ADC_BED 1 + #endif #endif #if HAS_ADC_TEST(PROBE) #define HAS_TEMP_ADC_PROBE 1 @@ -2262,7 +2265,7 @@ #define HAS_TEMP_ADC_REDUNDANT 1 #endif -#define HAS_TEMP(N) (TEMP_SENSOR_IS_MAX_TC(N) || EITHER(HAS_TEMP_ADC_##N, TEMP_SENSOR_##N##_IS_DUMMY)) +#define HAS_TEMP(N) (TEMP_SENSOR_IS_MAX_TC(N) || HAS_TEMP_ADC_##N || TEMP_SENSOR_##N##_IS_DUMMY) #if HAS_HOTEND && HAS_TEMP(0) #define HAS_TEMP_HOTEND 1 #endif @@ -2331,10 +2334,12 @@ #if PIN_EXISTS(HEATER_BED) #define HAS_HEATER_BED 1 #endif +#if PIN_EXISTS(HEATER_CHAMBER) + #define HAS_HEATER_CHAMBER 1 +#endif // Shorthand for common combinations -#if HAS_TEMP_BED && HAS_HEATER_BED - #define HAS_HEATED_BED 1 +#if HAS_HEATED_BED #ifndef BED_OVERSHOOT #define BED_OVERSHOOT 10 #endif @@ -2361,7 +2366,7 @@ #define HAS_TEMP_SENSOR 1 #endif -#if HAS_TEMP_CHAMBER && PIN_EXISTS(HEATER_CHAMBER) +#if HAS_TEMP_CHAMBER && HAS_HEATER_CHAMBER #define HAS_HEATED_CHAMBER 1 #ifndef CHAMBER_OVERSHOOT #define CHAMBER_OVERSHOOT 10 @@ -2377,10 +2382,10 @@ #endif #if ENABLED(DWIN_LCD_PROUI) - #if EITHER(PIDTEMP, PIDTEMPBED) + #if ANY(PIDTEMP, PIDTEMPBED) #define DWIN_PID_TUNE 1 #endif - #if EITHER(DWIN_PID_TUNE, MPC_AUTOTUNE) && DISABLED(DISABLE_TUNING_GRAPH) + #if ANY(DWIN_PID_TUNE, MPC_AUTOTUNE) && DISABLED(DISABLE_TUNING_GRAPH) #define SHOW_TUNING_GRAPH 1 #endif #endif @@ -2388,6 +2393,7 @@ // Thermal protection #if !HAS_HEATED_BED #undef THERMAL_PROTECTION_BED + #undef THERMAL_PROTECTION_BED_PERIOD #endif #if ENABLED(THERMAL_PROTECTION_HOTENDS) && WATCH_TEMP_PERIOD > 0 #define WATCH_HOTENDS 1 @@ -2395,10 +2401,10 @@ #if ENABLED(THERMAL_PROTECTION_BED) && WATCH_BED_TEMP_PERIOD > 0 #define WATCH_BED 1 #endif -#if BOTH(HAS_HEATED_CHAMBER, THERMAL_PROTECTION_CHAMBER) && WATCH_CHAMBER_TEMP_PERIOD > 0 +#if ALL(HAS_HEATED_CHAMBER, THERMAL_PROTECTION_CHAMBER) && WATCH_CHAMBER_TEMP_PERIOD > 0 #define WATCH_CHAMBER 1 #endif -#if BOTH(HAS_COOLER, THERMAL_PROTECTION_COOLER) && WATCH_COOLER_TEMP_PERIOD > 0 +#if ALL(HAS_COOLER, THERMAL_PROTECTION_COOLER) && WATCH_COOLER_TEMP_PERIOD > 0 #define WATCH_COOLER 1 #endif #if NONE(THERMAL_PROTECTION_HOTENDS, THERMAL_PROTECTION_CHAMBER, THERMAL_PROTECTION_BED, THERMAL_PROTECTION_COOLER) @@ -2610,7 +2616,7 @@ /** * MIN/MAX fan PWM scaling */ -#if EITHER(HAS_FAN, USE_CONTROLLER_FAN) +#if ANY(HAS_FAN, USE_CONTROLLER_FAN) #ifndef FAN_OFF_PWM #define FAN_OFF_PWM 0 #endif @@ -2710,7 +2716,7 @@ * Helper Macros for heaters and extruder fan */ #define WRITE_HEATER_0P(v) WRITE(HEATER_0_PIN, (v) ^ ENABLED(HEATER_0_INVERTING)) -#if EITHER(HAS_MULTI_HOTEND, HEATERS_PARALLEL) +#if ANY(HAS_MULTI_HOTEND, HEATERS_PARALLEL) #define WRITE_HEATER_1(v) WRITE(HEATER_1_PIN, (v) ^ ENABLED(HEATER_1_INVERTING)) #if HOTENDS > 2 #define WRITE_HEATER_2(v) WRITE(HEATER_2_PIN, (v) ^ ENABLED(HEATER_2_INVERTING)) @@ -2823,7 +2829,7 @@ /** * Bed Probe dependencies */ -#if EITHER(MESH_BED_LEVELING, HAS_BED_PROBE) +#if ANY(MESH_BED_LEVELING, HAS_BED_PROBE) #ifndef Z_PROBE_OFFSET_RANGE_MIN #define Z_PROBE_OFFSET_RANGE_MIN -20 #endif @@ -2832,7 +2838,7 @@ #endif #endif #if HAS_BED_PROBE - #if BOTH(ENDSTOPPULLUPS, USE_Z_MIN_PROBE) + #if ALL(ENDSTOPPULLUPS, USE_Z_MIN_PROBE) #define ENDSTOPPULLUP_ZMIN_PROBE #endif #ifndef XY_PROBE_FEEDRATE @@ -2890,16 +2896,16 @@ #undef ADAPTIVE_FAN_SLOWING #undef TEMP_TUNING_MAINTAIN_FAN #endif -#if !BOTH(HAS_BED_PROBE, HAS_FAN) +#if !ALL(HAS_BED_PROBE, HAS_FAN) #undef PROBING_FANS_OFF #endif -#if !BOTH(HAS_BED_PROBE, HAS_EXTRUDERS) +#if !ALL(HAS_BED_PROBE, HAS_EXTRUDERS) #undef PROBING_ESTEPPERS_OFF #elif ENABLED(PROBING_STEPPERS_OFF) // PROBING_STEPPERS_OFF implies PROBING_ESTEPPERS_OFF, make sure it is defined #define PROBING_ESTEPPERS_OFF #endif -#if EITHER(ADVANCED_PAUSE_FEATURE, PROBING_HEATERS_OFF) +#if ANY(ADVANCED_PAUSE_FEATURE, PROBING_HEATERS_OFF) #define HEATER_IDLE_HANDLER 1 #endif #if HAS_BED_PROBE && (ANY(PROBING_HEATERS_OFF, PROBING_STEPPERS_OFF, PROBING_ESTEPPERS_OFF, PROBING_FANS_OFF) || DELAY_BEFORE_PROBING > 0) @@ -2910,7 +2916,7 @@ * Advanced Pause - Filament Change */ #if ENABLED(ADVANCED_PAUSE_FEATURE) - #if ANY(HAS_MARLINUI_MENU, EXTENSIBLE_UI, DWIN_LCD_PROUI, DWIN_CREALITY_LCD_JYERSUI) || BOTH(EMERGENCY_PARSER, HOST_PROMPT_SUPPORT) + #if ANY(HAS_MARLINUI_MENU, EXTENSIBLE_UI, DWIN_LCD_PROUI, DWIN_CREALITY_LCD_JYERSUI) || ALL(EMERGENCY_PARSER, HOST_PROMPT_SUPPORT) #define M600_PURGE_MORE_RESUMABLE 1 #endif #ifndef FILAMENT_CHANGE_SLOW_LOAD_LENGTH @@ -2996,7 +3002,7 @@ /** * Default mesh area is an area with an inset margin on the print area. */ -#if EITHER(MESH_BED_LEVELING, AUTO_BED_LEVELING_UBL) +#if ANY(MESH_BED_LEVELING, AUTO_BED_LEVELING_UBL) #if IS_KINEMATIC // Probing points may be verified at compile time within the radius // using static_assert(HYPOT2(X2-X1,Y2-Y1)<=sq(PRINTABLE_RADIUS),"bad probe point!") @@ -3046,7 +3052,7 @@ #if ANY(IS_TFTGLCD_PANEL, PCA9632_BUZZER, LCD_USE_I2C_BUZZER) #define USE_MARLINUI_BUZZER 1 #endif -#if EITHER(HAS_BEEPER, USE_MARLINUI_BUZZER) +#if ANY(HAS_BEEPER, USE_MARLINUI_BUZZER) #define HAS_SOUND 1 #endif @@ -3117,7 +3123,7 @@ // Define a starting height for measuring manual probe points #ifndef MANUAL_PROBE_START_Z - #if EITHER(MESH_BED_LEVELING, PROBE_MANUALLY) + #if ANY(MESH_BED_LEVELING, PROBE_MANUALLY) // Leave MANUAL_PROBE_START_Z undefined so the prior Z height will be used. // Note: If Z_CLEARANCE_BETWEEN_MANUAL_PROBES is 0 there will be no raise between points #elif ENABLED(AUTO_BED_LEVELING_UBL) && defined(Z_CLEARANCE_BETWEEN_PROBES) @@ -3143,7 +3149,7 @@ #endif #endif -#if EITHER(HAS_MARLINUI_MENU, TOUCH_UI_FTDI_EVE) +#if ANY(HAS_MARLINUI_MENU, TOUCH_UI_FTDI_EVE) // LCD timeout to status screen default is 15s #ifndef LCD_TIMEOUT_TO_STATUS #define LCD_TIMEOUT_TO_STATUS 15000 @@ -3196,7 +3202,7 @@ #define MAX_VFAT_ENTRIES 20 // by VFAT specs to fit LFN of length 255 // Nozzle park for Delta -#if BOTH(NOZZLE_PARK_FEATURE, DELTA) +#if ALL(NOZZLE_PARK_FEATURE, DELTA) #undef NOZZLE_PARK_Z_FEEDRATE #define NOZZLE_PARK_Z_FEEDRATE NOZZLE_PARK_XY_FEEDRATE #endif diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 78630051b67d..00b532120518 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -46,8 +46,8 @@ #if ENABLED(TEST0) || !ENABLED(TEST2) || ENABLED(TEST3) || !ENABLED(TEST1, TEST2, TEST4) #error "ENABLED is borked!" #endif -#if BOTH(TEST0, TEST1) - #error "BOTH is borked!" +#if ALL(TEST0, TEST1) + #error "ALL is borked!" #endif #if DISABLED(TEST1) || !DISABLED(TEST3) || DISABLED(TEST4) || DISABLED(TEST0, TEST1, TEST2, TEST4) || !DISABLED(TEST0, TEST3) #error "DISABLED is borked!" @@ -127,6 +127,17 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L #undef _ISMAX_1 #undef _ISSNS_1 +/** + * Heated Bed requirements + */ +#if HAS_HEATED_BED + #if !HAS_TEMP_BED + #error "The Heated Bed requires a TEMP_BED_PIN or Thermocouple." + #elif !HAS_HEATER_BED + #error "The Heated Bed requires HEATER_BED_PIN." + #endif +#endif + /** * Hephestos 2 Heated Bed Kit requirements */ @@ -289,45 +300,45 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L #endif #endif -#if BOTH(ENDSTOPPULLUPS, ENDSTOPPULLDOWNS) +#if ALL(ENDSTOPPULLUPS, ENDSTOPPULLDOWNS) #error "Enable only one of ENDSTOPPULLUPS or ENDSTOPPULLDOWNS." -#elif BOTH(FIL_RUNOUT_PULLUP, FIL_RUNOUT_PULLDOWN) +#elif ALL(FIL_RUNOUT_PULLUP, FIL_RUNOUT_PULLDOWN) #error "Enable only one of FIL_RUNOUT_PULLUP or FIL_RUNOUT_PULLDOWN." -#elif BOTH(ENDSTOPPULLUP_XMAX, ENDSTOPPULLDOWN_XMAX) +#elif ALL(ENDSTOPPULLUP_XMAX, ENDSTOPPULLDOWN_XMAX) #error "Enable only one of ENDSTOPPULLUP_X_MAX or ENDSTOPPULLDOWN_X_MAX." -#elif BOTH(ENDSTOPPULLUP_YMAX, ENDSTOPPULLDOWN_YMAX) +#elif ALL(ENDSTOPPULLUP_YMAX, ENDSTOPPULLDOWN_YMAX) #error "Enable only one of ENDSTOPPULLUP_Y_MAX or ENDSTOPPULLDOWN_Y_MAX." -#elif BOTH(ENDSTOPPULLUP_ZMAX, ENDSTOPPULLDOWN_ZMAX) +#elif ALL(ENDSTOPPULLUP_ZMAX, ENDSTOPPULLDOWN_ZMAX) #error "Enable only one of ENDSTOPPULLUP_Z_MAX or ENDSTOPPULLDOWN_Z_MAX." -#elif BOTH(ENDSTOPPULLUP_IMAX, ENDSTOPPULLDOWN_IMAX) +#elif ALL(ENDSTOPPULLUP_IMAX, ENDSTOPPULLDOWN_IMAX) #error "Enable only one of ENDSTOPPULLUP_I_MAX or ENDSTOPPULLDOWN_I_MAX." -#elif BOTH(ENDSTOPPULLUP_JMAX, ENDSTOPPULLDOWN_JMAX) +#elif ALL(ENDSTOPPULLUP_JMAX, ENDSTOPPULLDOWN_JMAX) #error "Enable only one of ENDSTOPPULLUP_J_MAX or ENDSTOPPULLDOWN_J_MAX." -#elif BOTH(ENDSTOPPULLUP_KMAX, ENDSTOPPULLDOWN_KMAX) +#elif ALL(ENDSTOPPULLUP_KMAX, ENDSTOPPULLDOWN_KMAX) #error "Enable only one of ENDSTOPPULLUP_K_MAX or ENDSTOPPULLDOWN_K_MAX." -#elif BOTH(ENDSTOPPULLUP_UMAX, ENDSTOPPULLDOWN_UMAX) +#elif ALL(ENDSTOPPULLUP_UMAX, ENDSTOPPULLDOWN_UMAX) #error "Enable only one of ENDSTOPPULLUP_U_MAX or ENDSTOPPULLDOWN_U_MAX." -#elif BOTH(ENDSTOPPULLUP_VMAX, ENDSTOPPULLDOWN_VMAX) +#elif ALL(ENDSTOPPULLUP_VMAX, ENDSTOPPULLDOWN_VMAX) #error "Enable only one of ENDSTOPPULLUP_V_MAX or ENDSTOPPULLDOWN_V_MAX." -#elif BOTH(ENDSTOPPULLUP_WMAX, ENDSTOPPULLDOWN_WMAX) +#elif ALL(ENDSTOPPULLUP_WMAX, ENDSTOPPULLDOWN_WMAX) #error "Enable only one of ENDSTOPPULLUP_W_MAX or ENDSTOPPULLDOWN_W_MAX." -#elif BOTH(ENDSTOPPULLUP_XMIN, ENDSTOPPULLDOWN_XMIN) +#elif ALL(ENDSTOPPULLUP_XMIN, ENDSTOPPULLDOWN_XMIN) #error "Enable only one of ENDSTOPPULLUP_X_MIN or ENDSTOPPULLDOWN_X_MIN." -#elif BOTH(ENDSTOPPULLUP_YMIN, ENDSTOPPULLDOWN_YMIN) +#elif ALL(ENDSTOPPULLUP_YMIN, ENDSTOPPULLDOWN_YMIN) #error "Enable only one of ENDSTOPPULLUP_Y_MIN or ENDSTOPPULLDOWN_Y_MIN." -#elif BOTH(ENDSTOPPULLUP_ZMIN, ENDSTOPPULLDOWN_ZMIN) +#elif ALL(ENDSTOPPULLUP_ZMIN, ENDSTOPPULLDOWN_ZMIN) #error "Enable only one of ENDSTOPPULLUP_Z_MIN or ENDSTOPPULLDOWN_Z_MIN." -#elif BOTH(ENDSTOPPULLUP_IMIN, ENDSTOPPULLDOWN_IMIN) +#elif ALL(ENDSTOPPULLUP_IMIN, ENDSTOPPULLDOWN_IMIN) #error "Enable only one of ENDSTOPPULLUP_I_MIN or ENDSTOPPULLDOWN_I_MIN." -#elif BOTH(ENDSTOPPULLUP_JMIN, ENDSTOPPULLDOWN_JMIN) +#elif ALL(ENDSTOPPULLUP_JMIN, ENDSTOPPULLDOWN_JMIN) #error "Enable only one of ENDSTOPPULLUP_J_MIN or ENDSTOPPULLDOWN_J_MIN." -#elif BOTH(ENDSTOPPULLUP_KMIN, ENDSTOPPULLDOWN_KMIN) +#elif ALL(ENDSTOPPULLUP_KMIN, ENDSTOPPULLDOWN_KMIN) #error "Enable only one of ENDSTOPPULLUP_K_MIN or ENDSTOPPULLDOWN_K_MIN." -#elif BOTH(ENDSTOPPULLUP_UMIN, ENDSTOPPULLDOWN_UMIN) +#elif ALL(ENDSTOPPULLUP_UMIN, ENDSTOPPULLDOWN_UMIN) #error "Enable only one of ENDSTOPPULLUP_U_MIN or ENDSTOPPULLDOWN_U_MIN." -#elif BOTH(ENDSTOPPULLUP_VMIN, ENDSTOPPULLDOWN_VMIN) +#elif ALL(ENDSTOPPULLUP_VMIN, ENDSTOPPULLDOWN_VMIN) #error "Enable only one of ENDSTOPPULLUP_V_MIN or ENDSTOPPULLDOWN_V_MIN." -#elif BOTH(ENDSTOPPULLUP_WMIN, ENDSTOPPULLDOWN_WMIN) +#elif ALL(ENDSTOPPULLUP_WMIN, ENDSTOPPULLDOWN_WMIN) #error "Enable only one of ENDSTOPPULLUP_W_MIN or ENDSTOPPULLDOWN_W_MIN." #endif @@ -444,7 +455,7 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L * I2C Position Encoders */ #if ENABLED(I2C_POSITION_ENCODERS) - #if !BOTH(BABYSTEPPING, BABYSTEP_XY) + #if !ALL(BABYSTEPPING, BABYSTEP_XY) #error "I2C_POSITION_ENCODERS requires BABYSTEPPING and BABYSTEP_XY." #elif !WITHIN(I2CPE_ENCODER_CNT, 1, 5) #error "I2CPE_ENCODER_CNT must be between 1 and 5." @@ -457,11 +468,11 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L #if ENABLED(BABYSTEPPING) #if ENABLED(SCARA) #error "BABYSTEPPING is not implemented for SCARA yet." - #elif ENABLED(BABYSTEP_XY) && EITHER(MARKFORGED_XY, MARKFORGED_YX) + #elif ENABLED(BABYSTEP_XY) && ANY(MARKFORGED_XY, MARKFORGED_YX) #error "BABYSTEPPING only implemented for Z axis on MarkForged." - #elif BOTH(DELTA, BABYSTEP_XY) + #elif ALL(DELTA, BABYSTEP_XY) #error "BABYSTEPPING only implemented for Z axis on deltabots." - #elif BOTH(BABYSTEP_ZPROBE_OFFSET, MESH_BED_LEVELING) + #elif ALL(BABYSTEP_ZPROBE_OFFSET, MESH_BED_LEVELING) #error "MESH_BED_LEVELING and BABYSTEP_ZPROBE_OFFSET is not a valid combination" #elif ENABLED(BABYSTEP_ZPROBE_OFFSET) && !HAS_BED_PROBE #error "BABYSTEP_ZPROBE_OFFSET requires a probe." @@ -471,7 +482,7 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L #error "BABYSTEP_GFX_OVERLAY requires a BABYSTEP_ZPROBE_OFFSET." #elif ENABLED(BABYSTEP_HOTEND_Z_OFFSET) && !HAS_HOTEND_OFFSET #error "BABYSTEP_HOTEND_Z_OFFSET requires 2 or more HOTENDS." - #elif BOTH(BABYSTEP_ALWAYS_AVAILABLE, MOVE_Z_WHEN_IDLE) + #elif ALL(BABYSTEP_ALWAYS_AVAILABLE, MOVE_Z_WHEN_IDLE) #error "BABYSTEP_ALWAYS_AVAILABLE and MOVE_Z_WHEN_IDLE are incompatible." #elif !defined(BABYSTEP_MULTIPLICATOR_Z) #error "BABYSTEPPING requires BABYSTEP_MULTIPLICATOR_Z." @@ -509,21 +520,21 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L #error "FIL_RUNOUT3_PIN is required with NUM_RUNOUT_SENSORS >= 3." #elif NUM_RUNOUT_SENSORS >= 2 && !PIN_EXISTS(FIL_RUNOUT2) #error "FIL_RUNOUT2_PIN is required with NUM_RUNOUT_SENSORS >= 2." - #elif BOTH(FIL_RUNOUT1_PULLUP, FIL_RUNOUT1_PULLDOWN) + #elif ALL(FIL_RUNOUT1_PULLUP, FIL_RUNOUT1_PULLDOWN) #error "You can't enable FIL_RUNOUT1_PULLUP and FIL_RUNOUT1_PULLDOWN at the same time." - #elif BOTH(FIL_RUNOUT2_PULLUP, FIL_RUNOUT2_PULLDOWN) + #elif ALL(FIL_RUNOUT2_PULLUP, FIL_RUNOUT2_PULLDOWN) #error "You can't enable FIL_RUNOUT2_PULLUP and FIL_RUNOUT2_PULLDOWN at the same time." - #elif BOTH(FIL_RUNOUT3_PULLUP, FIL_RUNOUT3_PULLDOWN) + #elif ALL(FIL_RUNOUT3_PULLUP, FIL_RUNOUT3_PULLDOWN) #error "You can't enable FIL_RUNOUT3_PULLUP and FIL_RUNOUT3_PULLDOWN at the same time." - #elif BOTH(FIL_RUNOUT4_PULLUP, FIL_RUNOUT4_PULLDOWN) + #elif ALL(FIL_RUNOUT4_PULLUP, FIL_RUNOUT4_PULLDOWN) #error "You can't enable FIL_RUNOUT4_PULLUP and FIL_RUNOUT4_PULLDOWN at the same time." - #elif BOTH(FIL_RUNOUT5_PULLUP, FIL_RUNOUT5_PULLDOWN) + #elif ALL(FIL_RUNOUT5_PULLUP, FIL_RUNOUT5_PULLDOWN) #error "You can't enable FIL_RUNOUT5_PULLUP and FIL_RUNOUT5_PULLDOWN at the same time." - #elif BOTH(FIL_RUNOUT6_PULLUP, FIL_RUNOUT6_PULLDOWN) + #elif ALL(FIL_RUNOUT6_PULLUP, FIL_RUNOUT6_PULLDOWN) #error "You can't enable FIL_RUNOUT6_PULLUP and FIL_RUNOUT6_PULLDOWN at the same time." - #elif BOTH(FIL_RUNOUT7_PULLUP, FIL_RUNOUT7_PULLDOWN) + #elif ALL(FIL_RUNOUT7_PULLUP, FIL_RUNOUT7_PULLDOWN) #error "You can't enable FIL_RUNOUT7_PULLUP and FIL_RUNOUT7_PULLDOWN at the same time." - #elif BOTH(FIL_RUNOUT8_PULLUP, FIL_RUNOUT8_PULLDOWN) + #elif ALL(FIL_RUNOUT8_PULLUP, FIL_RUNOUT8_PULLDOWN) #error "You can't enable FIL_RUNOUT8_PULLUP and FIL_RUNOUT8_PULLDOWN at the same time." #elif FILAMENT_RUNOUT_DISTANCE_MM < 0 #error "FILAMENT_RUNOUT_DISTANCE_MM must be greater than or equal to zero." @@ -576,7 +587,7 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L /** * Individual axis homing is useless for DELTAS */ -#if BOTH(INDIVIDUAL_AXIS_HOMING_MENU, DELTA) +#if ALL(INDIVIDUAL_AXIS_HOMING_MENU, DELTA) #error "INDIVIDUAL_AXIS_HOMING_MENU is incompatible with DELTA kinematics." #endif @@ -680,7 +691,7 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L /** * A Dual Nozzle carriage with switching servo */ -#if BOTH(SWITCHING_NOZZLE, MECHANICAL_SWITCHING_NOZZLE) +#if ALL(SWITCHING_NOZZLE, MECHANICAL_SWITCHING_NOZZLE) #error "Enable only one of SWITCHING_NOZZLE or MECHANICAL_SWITCHING_NOZZLE." #elif ENABLED(MECHANICAL_SWITCHING_NOZZLE) #if EXTRUDERS != 2 @@ -736,7 +747,7 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L /** * Single Stepper Dual Extruder with switching servo */ -#if BOTH(SWITCHING_EXTRUDER, MECHANICAL_SWITCHING_EXTRUDER) +#if ALL(SWITCHING_EXTRUDER, MECHANICAL_SWITCHING_EXTRUDER) #error "Enable only one of SWITCHING_EXTRUDER or MECHANICAL_SWITCHING_EXTRUDER." #elif ENABLED(MECHANICAL_SWITCHING_EXTRUDER) #if EXTRUDERS < 2 @@ -844,7 +855,7 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L /** * (Magnetic) Parking Extruder requirements */ -#if EITHER(PARKING_EXTRUDER, MAGNETIC_PARKING_EXTRUDER) +#if ANY(PARKING_EXTRUDER, MAGNETIC_PARKING_EXTRUDER) #if ENABLED(EXT_SOLENOID) #error "(MAGNETIC_)PARKING_EXTRUDER and EXT_SOLENOID are incompatible. (Pins are used twice.)" #elif EXTRUDERS != 2 @@ -902,7 +913,7 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L /** * Magnetic / Electromagnetic Switching Toolhead requirements */ -#if EITHER(MAGNETIC_SWITCHING_TOOLHEAD, ELECTROMAGNETIC_SWITCHING_TOOLHEAD) +#if ANY(MAGNETIC_SWITCHING_TOOLHEAD, ELECTROMAGNETIC_SWITCHING_TOOLHEAD) #ifndef SWITCHING_TOOLHEAD_Y_POS #error "(ELECTRO)?MAGNETIC_SWITCHING_TOOLHEAD requires SWITCHING_TOOLHEAD_Y_POS" #elif !defined(SWITCHING_TOOLHEAD_X_POS) @@ -972,7 +983,7 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L /** * Extruder temperature control algorithm - There can be only one! */ -#if BOTH(PIDTEMP, MPCTEMP) +#if ALL(PIDTEMP, MPCTEMP) #error "Only enable PIDTEMP or MPCTEMP, but not both." #undef MPCTEMP #undef MPC_AUTOTUNE @@ -996,7 +1007,7 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L /** * Bed Heating Options - PID vs Limit Switching */ -#if BOTH(PIDTEMPBED, BED_LIMIT_SWITCHING) +#if ALL(PIDTEMPBED, BED_LIMIT_SWITCHING) #error "To use BED_LIMIT_SWITCHING you must disable PIDTEMPBED." #endif @@ -1019,7 +1030,7 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L /** * Chamber Heating Options - PID vs Limit Switching */ -#if BOTH(PIDTEMPCHAMBER, CHAMBER_LIMIT_SWITCHING) +#if ALL(PIDTEMPCHAMBER, CHAMBER_LIMIT_SWITCHING) #error "To use CHAMBER_LIMIT_SWITCHING you must disable PIDTEMPCHAMBER." #endif @@ -1185,7 +1196,7 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L /** * Some things should not be used on Belt Printers */ -#if BOTH(BELTPRINTER, HAS_LEVELING) +#if ALL(BELTPRINTER, HAS_LEVELING) #error "Bed Leveling is not compatible with BELTPRINTER." #endif @@ -1207,7 +1218,7 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L /** * Z_PROBE_SLED is incompatible with DELTA */ - #if BOTH(Z_PROBE_SLED, DELTA) + #if ALL(Z_PROBE_SLED, DELTA) #error "You cannot use Z_PROBE_SLED with DELTA." #endif @@ -1350,7 +1361,7 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L /** * Mag mounted probe requirements */ - #if BOTH(MAG_MOUNTED_PROBE, USE_PROBE_FOR_Z_HOMING) && DISABLED(Z_SAFE_HOMING) + #if ALL(MAG_MOUNTED_PROBE, USE_PROBE_FOR_Z_HOMING) && DISABLED(Z_SAFE_HOMING) #error "MAG_MOUNTED_PROBE requires Z_SAFE_HOMING if it's being used to home Z." #endif @@ -1575,7 +1586,7 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L #endif #endif -#if BOTH(PREHEAT_BEFORE_PROBING, PREHEAT_BEFORE_LEVELING) +#if ALL(PREHEAT_BEFORE_PROBING, PREHEAT_BEFORE_LEVELING) #error "Disable PREHEAT_BEFORE_LEVELING when using PREHEAT_BEFORE_PROBING." #endif @@ -1692,7 +1703,7 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L /** * Make sure DISABLE_[XYZ] compatible with selected homing options */ -#if HAS_DISABLE_MAIN_AXES && EITHER(HOME_AFTER_DEACTIVATE, Z_SAFE_HOMING) +#if HAS_DISABLE_MAIN_AXES && ANY(HOME_AFTER_DEACTIVATE, Z_SAFE_HOMING) #error "DISABLE_[XYZIJKUVW] is not compatible with HOME_AFTER_DEACTIVATE or Z_SAFE_HOMING." #endif @@ -1714,7 +1725,7 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L #error "POWER_MONITOR_CURRENT requires a valid POWER_MONITOR_CURRENT_PIN." #elif ENABLED(POWER_MONITOR_VOLTAGE) && !PIN_EXISTS(POWER_MONITOR_VOLTAGE) #error "POWER_MONITOR_VOLTAGE requires POWER_MONITOR_VOLTAGE_PIN to be defined." -#elif BOTH(POWER_MONITOR_CURRENT, POWER_MONITOR_VOLTAGE) && POWER_MONITOR_CURRENT_PIN == POWER_MONITOR_VOLTAGE_PIN +#elif ALL(POWER_MONITOR_CURRENT, POWER_MONITOR_VOLTAGE) && POWER_MONITOR_CURRENT_PIN == POWER_MONITOR_VOLTAGE_PIN #error "POWER_MONITOR_CURRENT_PIN and POWER_MONITOR_VOLTAGE_PIN must be different." #endif @@ -1746,7 +1757,7 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L #if ENABLED(SAV_3DGLCD) #if NONE(U8GLIB_SSD1306, U8GLIB_SH1106) #error "Enable a SAV_3DGLCD display type: U8GLIB_SSD1306 or U8GLIB_SH1106." - #elif BOTH(U8GLIB_SSD1306, U8GLIB_SH1106) + #elif ALL(U8GLIB_SSD1306, U8GLIB_SH1106) #error "Only enable one SAV_3DGLCD display type: U8GLIB_SSD1306 or U8GLIB_SH1106." #endif #endif @@ -1830,7 +1841,7 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L /** * Make sure FAN_*_PWM values are sensible */ -#if EITHER(HAS_FAN, USE_CONTROLLER_FAN) +#if ANY(HAS_FAN, USE_CONTROLLER_FAN) #if !WITHIN(FAN_MIN_PWM, 0, 255) #error "FAN_MIN_PWM must be a value from 0 to 255." #elif !WITHIN(FAN_MAX_PWM, 0, 255) @@ -2036,7 +2047,7 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L #elif !ANY_PIN(TEMP_0, TEMP_0_CS) && !TEMP_SENSOR_0_IS_DUMMY #error "TEMP_0_PIN or TEMP_0_CS_PIN not defined for this board." #endif - #if EITHER(HAS_MULTI_HOTEND, HEATERS_PARALLEL) && !HAS_HEATER_1 + #if ANY(HAS_MULTI_HOTEND, HEATERS_PARALLEL) && !HAS_HEATER_1 #error "HEATER_1_PIN is not defined. TEMP_SENSOR_1 might not be set, or the board (not EEB / EEF?) doesn't define a pin." #endif #if HAS_MULTI_HOTEND @@ -2219,7 +2230,7 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L /** * FYSETC/MKS/BTT Mini Panel Requirements */ -#if EITHER(FYSETC_242_OLED_12864, FYSETC_MINI_12864_2_1) +#if ANY(FYSETC_242_OLED_12864, FYSETC_MINI_12864_2_1) #ifndef NEO_RGB #define NEO_RGB 123 #define FAUX_RGB 1 @@ -2233,7 +2244,7 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L #undef NEO_RGB #undef FAUX_RGB #endif -#elif EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) && DISABLED(RGB_LED) +#elif ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) && DISABLED(RGB_LED) #error "Your FYSETC Mini Panel requires RGB_LED." #endif @@ -2343,12 +2354,12 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L // Z homing requirements #if Z_HOME_TO_MAX && ENABLED(USE_PROBE_FOR_Z_HOMING) #error "Z_HOME_DIR must be -1 when homing Z with the probe." - #elif BOTH(HOMING_Z_WITH_PROBE, Z_MULTI_ENDSTOPS) + #elif ALL(HOMING_Z_WITH_PROBE, Z_MULTI_ENDSTOPS) #error "Z_MULTI_ENDSTOPS is incompatible with USE_PROBE_FOR_Z_HOMING." #endif #endif -#if BOTH(HOME_Z_FIRST, USE_PROBE_FOR_Z_HOMING) +#if ALL(HOME_Z_FIRST, USE_PROBE_FOR_Z_HOMING) #error "HOME_Z_FIRST can't be used when homing Z with a probe." #endif @@ -2487,21 +2498,21 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L * Fan check */ #if HAS_FANCHECK - #if BOTH(E0_FAN_TACHO_PULLUP, E0_FAN_TACHO_PULLDOWN) + #if ALL(E0_FAN_TACHO_PULLUP, E0_FAN_TACHO_PULLDOWN) #error "Enable only one of E0_FAN_TACHO_PULLUP or E0_FAN_TACHO_PULLDOWN." - #elif BOTH(E1_FAN_TACHO_PULLUP, E1_FAN_TACHO_PULLDOWN) + #elif ALL(E1_FAN_TACHO_PULLUP, E1_FAN_TACHO_PULLDOWN) #error "Enable only one of E1_FAN_TACHO_PULLUP or E1_FAN_TACHO_PULLDOWN." - #elif BOTH(E2_FAN_TACHO_PULLUP, E2_FAN_TACHO_PULLDOWN) + #elif ALL(E2_FAN_TACHO_PULLUP, E2_FAN_TACHO_PULLDOWN) #error "Enable only one of E2_FAN_TACHO_PULLUP or E2_FAN_TACHO_PULLDOWN." - #elif BOTH(E3_FAN_TACHO_PULLUP, E3_FAN_TACHO_PULLDOWN) + #elif ALL(E3_FAN_TACHO_PULLUP, E3_FAN_TACHO_PULLDOWN) #error "Enable only one of E3_FAN_TACHO_PULLUP or E3_FAN_TACHO_PULLDOWN." - #elif BOTH(E4_FAN_TACHO_PULLUP, E4_FAN_TACHO_PULLDOWN) + #elif ALL(E4_FAN_TACHO_PULLUP, E4_FAN_TACHO_PULLDOWN) #error "Enable only one of E4_FAN_TACHO_PULLUP or E4_FAN_TACHO_PULLDOWN." - #elif BOTH(E5_FAN_TACHO_PULLUP, E5_FAN_TACHO_PULLDOWN) + #elif ALL(E5_FAN_TACHO_PULLUP, E5_FAN_TACHO_PULLDOWN) #error "Enable only one of E5_FAN_TACHO_PULLUP or E5_FAN_TACHO_PULLDOWN." - #elif BOTH(E6_FAN_TACHO_PULLUP, E6_FAN_TACHO_PULLDOWN) + #elif ALL(E6_FAN_TACHO_PULLUP, E6_FAN_TACHO_PULLDOWN) #error "Enable only one of E6_FAN_TACHO_PULLUP or E6_FAN_TACHO_PULLDOWN." - #elif BOTH(E7_FAN_TACHO_PULLUP, E7_FAN_TACHO_PULLDOWN) + #elif ALL(E7_FAN_TACHO_PULLUP, E7_FAN_TACHO_PULLDOWN) #error "Enable only one of E7_FAN_TACHO_PULLUP or E7_FAN_TACHO_PULLDOWN." #endif #elif ENABLED(AUTO_REPORT_FANS) @@ -2629,7 +2640,7 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L #if ENABLED(TFT_GENERIC) && NONE(TFT_INTERFACE_FSMC, TFT_INTERFACE_SPI) #error "TFT_GENERIC requires either TFT_INTERFACE_FSMC or TFT_INTERFACE_SPI interface." -#elif BOTH(TFT_INTERFACE_FSMC, TFT_INTERFACE_SPI) +#elif ALL(TFT_INTERFACE_FSMC, TFT_INTERFACE_SPI) #error "Please enable only one of TFT_INTERFACE_FSMC or TFT_INTERFACE_SPI." #endif @@ -2653,7 +2664,7 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L #error "GRAPHICAL_TFT_UPSCALE must be between 2 and 8." #endif -#if BOTH(CHIRON_TFT_STANDARD, CHIRON_TFT_NEW) +#if ALL(CHIRON_TFT_STANDARD, CHIRON_TFT_NEW) #error "Please select only one of CHIRON_TFT_STANDARD or CHIRON_TFT_NEW." #endif @@ -2675,7 +2686,7 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L static_assert(strcmp(STRINGIFY(LCD_LANGUAGE_2), "zh_CN") == 0, "LCD_LANGUAGE_2 must be set to zh_CN for ANYCUBIC_LCD_VYPER."); #endif -#if EITHER(MKS_TS35_V2_0, BTT_TFT35_SPI_V1_0) && SD_CONNECTION_IS(LCD) +#if ANY(MKS_TS35_V2_0, BTT_TFT35_SPI_V1_0) && SD_CONNECTION_IS(LCD) #error "SDCARD_CONNECTION cannot be set to LCD for the enabled TFT. No available SD card reader." #endif @@ -2685,25 +2696,25 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L #if ENABLED(DWIN_CREALITY_LCD) #if !HAS_MEDIA #error "DWIN_CREALITY_LCD requires SDSUPPORT to be enabled." - #elif EITHER(PID_EDIT_MENU, PID_AUTOTUNE_MENU) + #elif ANY(PID_EDIT_MENU, PID_AUTOTUNE_MENU) #error "DWIN_CREALITY_LCD does not support PID_EDIT_MENU or PID_AUTOTUNE_MENU." - #elif EITHER(MPC_EDIT_MENU, MPC_AUTOTUNE_MENU) + #elif ANY(MPC_EDIT_MENU, MPC_AUTOTUNE_MENU) #error "DWIN_CREALITY_LCD does not support MPC_EDIT_MENU or MPC_AUTOTUNE_MENU." #elif ENABLED(LCD_BED_TRAMMING) #error "DWIN_CREALITY_LCD does not support LCD_BED_TRAMMING." - #elif BOTH(LCD_BED_LEVELING, PROBE_MANUALLY) + #elif ALL(LCD_BED_LEVELING, PROBE_MANUALLY) #error "DWIN_CREALITY_LCD does not support LCD_BED_LEVELING with PROBE_MANUALLY." #endif #elif ENABLED(DWIN_LCD_PROUI) #if !HAS_MEDIA #error "DWIN_LCD_PROUI requires SDSUPPORT to be enabled." - #elif EITHER(PID_EDIT_MENU, PID_AUTOTUNE_MENU) + #elif ANY(PID_EDIT_MENU, PID_AUTOTUNE_MENU) #error "DWIN_LCD_PROUI does not support PID_EDIT_MENU or PID_AUTOTUNE_MENU." - #elif EITHER(MPC_EDIT_MENU, MPC_AUTOTUNE_MENU) + #elif ANY(MPC_EDIT_MENU, MPC_AUTOTUNE_MENU) #error "DWIN_LCD_PROUI does not support MPC_EDIT_MENU or MPC_AUTOTUNE_MENU." #elif ENABLED(LCD_BED_TRAMMING) #error "DWIN_LCD_PROUI does not support LCD_BED_TRAMMING." - #elif BOTH(LCD_BED_LEVELING, PROBE_MANUALLY) + #elif ALL(LCD_BED_LEVELING, PROBE_MANUALLY) #error "DWIN_LCD_PROUI does not support LCD_BED_LEVELING with PROBE_MANUALLY." #endif #endif @@ -2724,9 +2735,9 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L // Startup Tune requirements #ifdef STARTUP_TUNE - #if EITHER(ANYCUBIC_LCD_CHIRON, ANYCUBIC_LCD_VYPER) + #if ANY(ANYCUBIC_LCD_CHIRON, ANYCUBIC_LCD_VYPER) #error "STARTUP_TUNE should be disabled with ANYCUBIC_LCD_CHIRON or ANYCUBIC_LCD_VYPER." - #elif !(BOTH(HAS_BEEPER, SPEAKER) || USE_MARLINUI_BUZZER) + #elif !(ALL(HAS_BEEPER, SPEAKER) || USE_MARLINUI_BUZZER) #error "STARTUP_TUNE requires a BEEPER_PIN with SPEAKER or USE_MARLINUI_BUZZER." #undef STARTUP_TUNE #endif @@ -3221,7 +3232,7 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L #endif // !SPI_ENDSTOPS - #if ENABLED(DELTA) && !BOTH(STEALTHCHOP_XY, STEALTHCHOP_Z) + #if ENABLED(DELTA) && !ALL(STEALTHCHOP_XY, STEALTHCHOP_Z) #error "SENSORLESS_HOMING on DELTA currently requires STEALTHCHOP_XY and STEALTHCHOP_Z." #elif ENDSTOP_NOISE_THRESHOLD #error "SENSORLESS_HOMING is incompatible with ENDSTOP_NOISE_THRESHOLD." @@ -3251,7 +3262,7 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L #error "CoreXZ requires both X and Z to use sensorless homing if either one does." #elif CORE_IS_YZ && Y_SENSORLESS != Z_SENSORLESS && !HOMING_Z_WITH_PROBE #error "CoreYZ requires both Y and Z to use sensorless homing if either one does." -#elif EITHER(MARKFORGED_XY, MARKFORGED_YX) && X_SENSORLESS != Y_SENSORLESS +#elif ANY(MARKFORGED_XY, MARKFORGED_YX) && X_SENSORLESS != Y_SENSORLESS #error "MARKFORGED requires both X and Y to use sensorless homing if either one does." #endif @@ -3339,7 +3350,7 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L * Digipot requirement */ #if HAS_MOTOR_CURRENT_I2C - #if BOTH(DIGIPOT_MCP4018, DIGIPOT_MCP4451) + #if ALL(DIGIPOT_MCP4018, DIGIPOT_MCP4451) #error "Enable only one of DIGIPOT_MCP4018 or DIGIPOT_MCP4451." #elif !MB(MKS_SBASE, AZTEEG_X5_GT, AZTEEG_X5_MINI, AZTEEG_X5_MINI_WIFI) \ && (!defined(DIGIPOTS_I2C_SDA_X) || !defined(DIGIPOTS_I2C_SDA_Y) || !defined(DIGIPOTS_I2C_SDA_Z) || !defined(DIGIPOTS_I2C_SDA_E0) || !defined(DIGIPOTS_I2C_SDA_E1)) @@ -3412,7 +3423,7 @@ static_assert(_PLUS_TEST(3), "DEFAULT_MAX_ACCELERATION values must be positive." #undef _PLUS_TEST #undef _EXTRA_NOTE -#if BOTH(CNC_COORDINATE_SYSTEMS, NO_WORKSPACE_OFFSETS) +#if ALL(CNC_COORDINATE_SYSTEMS, NO_WORKSPACE_OFFSETS) #error "CNC_COORDINATE_SYSTEMS is incompatible with NO_WORKSPACE_OFFSETS." #endif @@ -3448,18 +3459,18 @@ static_assert(_PLUS_TEST(3), "DEFAULT_MAX_ACCELERATION values must be positive." #endif #endif -#if BOTH(X_AXIS_TWIST_COMPENSATION, NOZZLE_AS_PROBE) +#if ALL(X_AXIS_TWIST_COMPENSATION, NOZZLE_AS_PROBE) #error "X_AXIS_TWIST_COMPENSATION is incompatible with NOZZLE_AS_PROBE." #endif #if ENABLED(POWER_LOSS_RECOVERY) #if ENABLED(BACKUP_POWER_SUPPLY) && !PIN_EXISTS(POWER_LOSS) #error "BACKUP_POWER_SUPPLY requires a POWER_LOSS_PIN." - #elif BOTH(POWER_LOSS_PULLUP, POWER_LOSS_PULLDOWN) + #elif ALL(POWER_LOSS_PULLUP, POWER_LOSS_PULLDOWN) #error "You can't enable POWER_LOSS_PULLUP and POWER_LOSS_PULLDOWN at the same time." #elif ENABLED(POWER_LOSS_RECOVER_ZHOME) && Z_HOME_TO_MAX #error "POWER_LOSS_RECOVER_ZHOME is not needed on a machine that homes to ZMAX." - #elif BOTH(IS_CARTESIAN, POWER_LOSS_RECOVER_ZHOME) && Z_HOME_TO_MIN && !defined(POWER_LOSS_ZHOME_POS) + #elif ALL(IS_CARTESIAN, POWER_LOSS_RECOVER_ZHOME) && Z_HOME_TO_MIN && !defined(POWER_LOSS_ZHOME_POS) #error "POWER_LOSS_RECOVER_ZHOME requires POWER_LOSS_ZHOME_POS for a Cartesian that homes to ZMIN." #endif #endif @@ -3521,7 +3532,7 @@ static_assert(_PLUS_TEST(3), "DEFAULT_MAX_ACCELERATION values must be positive." #error "BACKLASH_COMPENSATION requires BACKLASH_DISTANCE_MM." #elif !defined(BACKLASH_CORRECTION) #error "BACKLASH_COMPENSATION requires BACKLASH_CORRECTION." - #elif EITHER(MARKFORGED_XY, MARKFORGED_YX) + #elif ANY(MARKFORGED_XY, MARKFORGED_YX) constexpr float backlash_arr[] = BACKLASH_DISTANCE_MM; static_assert(!backlash_arr[CORE_AXIS_1] && !backlash_arr[CORE_AXIS_2], "BACKLASH_COMPENSATION can only apply to " STRINGIFY(NORMAL_AXIS) " on a MarkForged system."); @@ -3571,7 +3582,7 @@ static_assert(_PLUS_TEST(3), "DEFAULT_MAX_ACCELERATION values must be positive." /** * Require soft endstops for certain setups */ -#if !BOTH(MIN_SOFTWARE_ENDSTOPS, MAX_SOFTWARE_ENDSTOPS) +#if !ALL(MIN_SOFTWARE_ENDSTOPS, MAX_SOFTWARE_ENDSTOPS) #if ENABLED(DUAL_X_CARRIAGE) #error "DUAL_X_CARRIAGE requires both MIN_ and MAX_SOFTWARE_ENDSTOPS." #elif HAS_HOTEND_OFFSET @@ -3632,7 +3643,7 @@ static_assert(_PLUS_TEST(3), "DEFAULT_MAX_ACCELERATION values must be positive." #endif #define _PIN_CONFLICT(P) (PIN_EXISTS(P) && P##_PIN == SPINDLE_LASER_PWM_PIN) - #if BOTH(SPINDLE_FEATURE, LASER_FEATURE) + #if ALL(SPINDLE_FEATURE, LASER_FEATURE) #error "Enable only one of SPINDLE_FEATURE or LASER_FEATURE." #elif NONE(SPINDLE_SERVO, SPINDLE_LASER_USE_PWM) && !PIN_EXISTS(SPINDLE_LASER_ENA) #error "(SPINDLE|LASER)_FEATURE requires SPINDLE_LASER_ENA_PIN, SPINDLE_LASER_USE_PWM, or SPINDLE_SERVO to control the power." @@ -3781,7 +3792,7 @@ static_assert(_PLUS_TEST(3), "DEFAULT_MAX_ACCELERATION values must be positive." #error "ESP3D_WIFISUPPORT requires an ESP32 MOTHERBOARD." #elif ENABLED(WEBSUPPORT) && NONE(ARDUINO_ARCH_ESP32, WIFISUPPORT) #error "WEBSUPPORT requires WIFISUPPORT and an ESP32 MOTHERBOARD." -#elif BOTH(ESP3D_WIFISUPPORT, WIFISUPPORT) +#elif ALL(ESP3D_WIFISUPPORT, WIFISUPPORT) #error "Enable only one of ESP3D_WIFISUPPORT or WIFISUPPORT." #endif @@ -3799,14 +3810,14 @@ static_assert(_PLUS_TEST(3), "DEFAULT_MAX_ACCELERATION values must be positive." /** * Sanity Check for MEATPACK and BINARY_FILE_TRANSFER Features */ -#if BOTH(HAS_MEATPACK, BINARY_FILE_TRANSFER) +#if ALL(HAS_MEATPACK, BINARY_FILE_TRANSFER) #error "Either enable MEATPACK_ON_SERIAL_PORT_* or BINARY_FILE_TRANSFER, not both." #endif /** * Sanity Check for Slim LCD Menus and Probe Offset Wizard */ -#if BOTH(SLIM_LCD_MENUS, PROBE_OFFSET_WIZARD) +#if ALL(SLIM_LCD_MENUS, PROBE_OFFSET_WIZARD) #error "SLIM_LCD_MENUS disables \"Advanced Settings > Probe Offsets > PROBE_OFFSET_WIZARD.\"" #endif @@ -3843,7 +3854,7 @@ static_assert(_PLUS_TEST(3), "DEFAULT_MAX_ACCELERATION values must be positive." /** * Sanity check for MIXING_EXTRUDER & DISTINCT_E_FACTORS these are not compatible */ -#if BOTH(MIXING_EXTRUDER, DISTINCT_E_FACTORS) +#if ALL(MIXING_EXTRUDER, DISTINCT_E_FACTORS) #error "MIXING_EXTRUDER can't be used with DISTINCT_E_FACTORS. But you may use SINGLENOZZLE with DISTINCT_E_FACTORS." #endif @@ -3977,7 +3988,7 @@ static_assert(_PLUS_TEST(3), "DEFAULT_MAX_ACCELERATION values must be positive." #endif // Check requirements for upload.py -#if ENABLED(XFER_BUILD) && !BOTH(BINARY_FILE_TRANSFER, CUSTOM_FIRMWARE_UPLOAD) +#if ENABLED(XFER_BUILD) && !ALL(BINARY_FILE_TRANSFER, CUSTOM_FIRMWARE_UPLOAD) #error "BINARY_FILE_TRANSFER and CUSTOM_FIRMWARE_UPLOAD are required for custom upload." #endif @@ -3997,12 +4008,12 @@ static_assert(_PLUS_TEST(3), "DEFAULT_MAX_ACCELERATION values must be positive." #error "Input Shaping is not compatible with POLARGRAPH kinematics." #elif ENABLED(DIRECT_STEPPING) #error "Input Shaping is not compatible with DIRECT_STEPPING." - #elif BOTH(INPUT_SHAPING_X, CORE_IS_XZ) + #elif ALL(INPUT_SHAPING_X, CORE_IS_XZ) #error "INPUT_SHAPING_X is not supported with COREXZ." - #elif BOTH(INPUT_SHAPING_Y, CORE_IS_YZ) + #elif ALL(INPUT_SHAPING_Y, CORE_IS_YZ) #error "INPUT_SHAPING_Y is not supported with COREYZ." #elif ANY(CORE_IS_XY, MARKFORGED_XY, MARKFORGED_YX) - #if !BOTH(INPUT_SHAPING_X, INPUT_SHAPING_Y) + #if !ALL(INPUT_SHAPING_X, INPUT_SHAPING_Y) #error "INPUT_SHAPING_X and INPUT_SHAPING_Y must both be enabled for COREXY, COREYX, or MARKFORGED_*." #else static_assert(SHAPING_FREQ_X == SHAPING_FREQ_Y, "SHAPING_FREQ_X and SHAPING_FREQ_Y must be the same for COREXY / COREYX / MARKFORGED_*."); diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 0bb7faffe2a6..af412a701a91 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2023-05-27" + #define STRING_DISTRIBUTION_DATE "2023-06-06" #endif /** diff --git a/Marlin/src/inc/Warnings.cpp b/Marlin/src/inc/Warnings.cpp index 5c6297ba6019..34c63239e5c6 100644 --- a/Marlin/src/inc/Warnings.cpp +++ b/Marlin/src/inc/Warnings.cpp @@ -687,17 +687,17 @@ /** * FYSETC/MKS/BTT Mini Panel backlighting */ -#if EITHER(FYSETC_242_OLED_12864, FYSETC_MINI_12864_2_1) && !ALL(NEOPIXEL_LED, LED_CONTROL_MENU, LED_USER_PRESET_STARTUP, LED_COLOR_PRESETS) +#if ANY(FYSETC_242_OLED_12864, FYSETC_MINI_12864_2_1) && !ALL(NEOPIXEL_LED, LED_CONTROL_MENU, LED_USER_PRESET_STARTUP, LED_COLOR_PRESETS) #warning "Your FYSETC/MKS/BTT Mini Panel works best with NEOPIXEL_LED, LED_CONTROL_MENU, LED_USER_PRESET_STARTUP, and LED_COLOR_PRESETS." #endif -#if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) && DISABLED(RGB_LED) +#if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) && DISABLED(RGB_LED) #warning "Your FYSETC Mini Panel works best with RGB_LED." -#elif EITHER(FYSETC_MINI_12864_2_0, FYSETC_MINI_12864_2_1) && DISABLED(LED_USER_PRESET_STARTUP) +#elif ANY(FYSETC_MINI_12864_2_0, FYSETC_MINI_12864_2_1) && DISABLED(LED_USER_PRESET_STARTUP) #warning "Your FYSETC Mini Panel works best with LED_USER_PRESET_STARTUP." #endif -#if EITHER(FYSETC_242_OLED_12864, FYSETC_MINI_12864) && BOTH(PSU_CONTROL, HAS_COLOR_LEDS) && !LED_POWEROFF_TIMEOUT +#if ANY(FYSETC_242_OLED_12864, FYSETC_MINI_12864) && ALL(PSU_CONTROL, HAS_COLOR_LEDS) && !LED_POWEROFF_TIMEOUT #warning "Your FYSETC display with PSU_CONTROL works best with LED_POWEROFF_TIMEOUT." #endif @@ -739,7 +739,7 @@ /** * POLAR warnings */ -#if BOTH(POLAR, S_CURVE_ACCELERATION) +#if ALL(POLAR, S_CURVE_ACCELERATION) #warning "POLAR kinematics may not work well with S_CURVE_ACCELERATION." #endif diff --git a/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp b/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp index b03ff8a9f533..ba467d1a61c1 100644 --- a/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp +++ b/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp @@ -41,12 +41,12 @@ #include "../../module/planner.h" #include "../../module/motion.h" -#if DISABLED(LCD_PROGRESS_BAR) && BOTH(FILAMENT_LCD_DISPLAY, HAS_MEDIA) +#if DISABLED(LCD_PROGRESS_BAR) && ALL(FILAMENT_LCD_DISPLAY, HAS_MEDIA) #include "../../feature/filwidth.h" #include "../../gcode/parser.h" #endif -#if EITHER(HAS_COOLER, LASER_COOLANT_FLOW_METER) +#if ANY(HAS_COOLER, LASER_COOLANT_FLOW_METER) #include "../../feature/cooler.h" #endif @@ -70,7 +70,7 @@ LCD_CLASS lcd(LCD_I2C_ADDRESS, LCD_I2C_PIN_EN, LCD_I2C_PIN_RW, LCD_I2C_PIN_RS, LCD_I2C_PIN_D4, LCD_I2C_PIN_D5, LCD_I2C_PIN_D6, LCD_I2C_PIN_D7); -#elif EITHER(LCD_I2C_TYPE_MCP23017, LCD_I2C_TYPE_MCP23008) +#elif ANY(LCD_I2C_TYPE_MCP23017, LCD_I2C_TYPE_MCP23008) LCD_CLASS lcd(LCD_I2C_ADDRESS OPTARG(DETECT_I2C_LCD_DEVICE, 1)); @@ -130,7 +130,7 @@ static void createChar_P(const char c, const byte * const ptr) { byte temp[8]; - LOOP_L_N(i, 8) + for (uint8_t i = 0; i < 8; ++i) temp[i] = pgm_read_byte(&ptr[i]); lcd.createChar(c, temp); } @@ -305,7 +305,7 @@ void MarlinUI::set_custom_characters(const HD44780CharSet screen_charset/*=CHARS #endif // LCD_PROGRESS_BAR - #if BOTH(HAS_MEDIA, HAS_MARLINUI_MENU) + #if ALL(HAS_MEDIA, HAS_MARLINUI_MENU) // CHARSET_MENU const static PROGMEM byte refresh[8] = { @@ -355,7 +355,7 @@ void MarlinUI::set_custom_characters(const HD44780CharSet screen_charset/*=CHARS #endif { createChar_P(LCD_STR_UPLEVEL[0], uplevel); - #if BOTH(HAS_MEDIA, HAS_MARLINUI_MENU) + #if ALL(HAS_MEDIA, HAS_MARLINUI_MENU) // SD Card sub-menu special characters createChar_P(LCD_STR_REFRESH[0], refresh); createChar_P(LCD_STR_FOLDER[0], folder); @@ -440,7 +440,7 @@ void MarlinUI::clear_lcd() { lcd.clear(); } else { PGM_P p = FTOP(ftxt); int dly = time / _MAX(slen, 1); - LOOP_LE_N(i, slen) { + for (uint8_t i = 0; i <= slen; ++i) { // Print the text at the correct place lcd_put_u8str_max_P(col, line, p, len); @@ -713,7 +713,7 @@ void MarlinUI::draw_status_message(const bool blink) { if (progress > 2) return draw_progress_bar(progress); } - #elif BOTH(FILAMENT_LCD_DISPLAY, HAS_MEDIA) + #elif ALL(FILAMENT_LCD_DISPLAY, HAS_MEDIA) // Alternate Status message and Filament display if (ELAPSED(millis(), next_filament_display)) { @@ -973,20 +973,20 @@ void MarlinUI::draw_status_screen() { // Two-component mix / gradient instead of XY - char mixer_messages[12]; - const char *mix_label; + char mixer_messages[15]; + PGM_P mix_label; #if ENABLED(GRADIENT_MIX) if (mixer.gradient.enabled) { mixer.update_mix_from_gradient(); - mix_label = "Gr"; + mix_label = PSTR("Gr"); } else #endif { mixer.update_mix_from_vtool(); - mix_label = "Mx"; + mix_label = PSTR("Mx"); } - sprintf_P(mixer_messages, PSTR("%s %d;%d%% "), mix_label, int(mixer.mix[0]), int(mixer.mix[1])); + sprintf_P(mixer_messages, PSTR(S_FMT " %d;%d%% "), mix_label, int(mixer.mix[0]), int(mixer.mix[1])); lcd_put_u8str(mixer_messages); #else // !HAS_DUAL_MIXING @@ -1046,7 +1046,7 @@ void MarlinUI::draw_status_screen() { uint16_t per; #if HAS_FAN0 if (true - #if BOTH(HAS_EXTRUDERS, ADAPTIVE_FAN_SLOWING) + #if ALL(HAS_EXTRUDERS, ADAPTIVE_FAN_SLOWING) && (blink || thermalManager.fan_speed_scaler[0] < 128) #endif ) { diff --git a/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp b/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp index f7e9ff3e4564..ee7154ae417c 100644 --- a/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp +++ b/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp @@ -52,12 +52,12 @@ #include "../../module/planner.h" #include "../../module/motion.h" -#if DISABLED(LCD_PROGRESS_BAR) && BOTH(FILAMENT_LCD_DISPLAY, HAS_MEDIA) +#if DISABLED(LCD_PROGRESS_BAR) && ALL(FILAMENT_LCD_DISPLAY, HAS_MEDIA) #include "../../feature/filwidth.h" #include "../../gcode/parser.h" #endif -#if EITHER(HAS_COOLER, LASER_COOLANT_FLOW_METER) +#if ANY(HAS_COOLER, LASER_COOLANT_FLOW_METER) #include "../../feature/cooler.h" #endif @@ -141,7 +141,7 @@ static uint8_t PanelDetected = 0; #if ANY(__AVR__, TARGET_LPC1768, __STM32F1__, ARDUINO_ARCH_SAM, __SAMD51__, __MK20DX256__, __MK64FX512__) #define SPI_SEND_ONE(V) SPI.transfer(V); #define SPI_SEND_TWO(V) SPI.transfer16(V); -#elif EITHER(STM32F4xx, STM32F1xx) +#elif ANY(STM32F4xx, STM32F1xx) #define SPI_SEND_ONE(V) SPI.transfer(V, SPI_CONTINUE); #define SPI_SEND_TWO(V) SPI.transfer16(V, SPI_CONTINUE); #elif defined(ARDUINO_ARCH_ESP32) @@ -151,7 +151,7 @@ static uint8_t PanelDetected = 0; #if ANY(__AVR__, ARDUINO_ARCH_SAM, __SAMD51__, __MK20DX256__, __MK64FX512__) #define SPI_SEND_SOME(V,L,Z) SPI.transfer(&V[Z], L); -#elif EITHER(STM32F4xx, STM32F1xx) +#elif ANY(STM32F4xx, STM32F1xx) #define SPI_SEND_SOME(V,L,Z) SPI.transfer(&V[Z], L, SPI_CONTINUE); #elif ANY(TARGET_LPC1768, __STM32F1__, ARDUINO_ARCH_ESP32) #define SPI_SEND_SOME(V,L,Z) do{ for (uint16_t i = 0; i < L; i++) SPI_SEND_ONE(V[(Z)+i]); }while(0) @@ -290,7 +290,7 @@ uint8_t MarlinUI::read_slow_buttons() { Wire.requestFrom((uint8_t)LCD_I2C_ADDRESS, 2, 0, 0, 1); #elif defined(STM32F1) Wire.requestFrom((uint8_t)LCD_I2C_ADDRESS, (uint8_t)2); - #elif EITHER(STM32F4xx, TARGET_LPC1768) + #elif ANY(STM32F4xx, TARGET_LPC1768) Wire.requestFrom(LCD_I2C_ADDRESS, 2); #endif encoderDiff += Wire.read(); @@ -672,7 +672,7 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const void MarlinUI::draw_status_message(const bool blink) { if (!PanelDetected) return; lcd_moveto(0, 3); - #if BOTH(FILAMENT_LCD_DISPLAY, HAS_MEDIA) + #if ALL(FILAMENT_LCD_DISPLAY, HAS_MEDIA) // Alternate Status message and Filament display if (ELAPSED(millis(), next_filament_display)) { @@ -866,23 +866,23 @@ void MarlinUI::draw_status_screen() { // #if HOTENDS <= 1 || (HOTENDS <= 2 && !HAS_HEATED_BED) - #if DUAL_MIXING_EXTRUDER + #if HAS_DUAL_MIXING lcd_moveto(0, 4); // Two-component mix / gradient instead of XY - char mixer_messages[12]; - const char *mix_label; + char mixer_messages[15]; + PGM_P mix_label; #if ENABLED(GRADIENT_MIX) if (mixer.gradient.enabled) { mixer.update_mix_from_gradient(); - mix_label = "Gr"; + mix_label = PSTR("Gr"); } else #endif { mixer.update_mix_from_vtool(); - mix_label = "Mx"; + mix_label = PSTR("Mx"); } - sprintf_P(mixer_messages, PSTR("%s %d;%d%% "), mix_label, int(mixer.mix[0]), int(mixer.mix[1])); + sprintf_P(mixer_messages, PSTR(S_FMT " %d;%d%% "), mix_label, int(mixer.mix[0]), int(mixer.mix[1])); lcd_put_u8str(mixer_messages); #endif #endif diff --git a/Marlin/src/lcd/buttons.h b/Marlin/src/lcd/buttons.h index 58471239bbfb..601e8a70ae05 100644 --- a/Marlin/src/lcd/buttons.h +++ b/Marlin/src/lcd/buttons.h @@ -38,7 +38,7 @@ #define HAS_SLOW_BUTTONS 1 #endif -#if EITHER(HAS_DIGITAL_BUTTONS, HAS_DWIN_E3V2) +#if ANY(HAS_DIGITAL_BUTTONS, HAS_DWIN_E3V2) // Wheel spin pins where BA is 00, 10, 11, 01 (1 bit always changes) #define BLEN_A 0 #define BLEN_B 1 @@ -149,7 +149,7 @@ #ifndef EN_C #define EN_C 0 #endif -#if BUTTON_EXISTS(BACK) || EITHER(HAS_TOUCH_BUTTONS, IS_TFTGLCD_PANEL) +#if BUTTON_EXISTS(BACK) || ANY(HAS_TOUCH_BUTTONS, IS_TFTGLCD_PANEL) #define BLEN_D 3 #define EN_D _BV(BLEN_D) #else diff --git a/Marlin/src/lcd/dogm/dogm_Statusscreen.h b/Marlin/src/lcd/dogm/dogm_Statusscreen.h index 8d0ab4efbe46..9eec9d198717 100644 --- a/Marlin/src/lcd/dogm/dogm_Statusscreen.h +++ b/Marlin/src/lcd/dogm/dogm_Statusscreen.h @@ -143,7 +143,7 @@ // Can also be overridden in Configuration_adv.h // If you can afford it, try the 3-frame fan animation! // Don't compile in the fan animation with no fan -#if !HAS_FAN0 || (HOTENDS == 5 || (HOTENDS == 4 && BED_OR_CHAMBER) || BOTH(STATUS_COMBINE_HEATERS, HAS_HEATED_CHAMBER)) +#if !HAS_FAN0 || (HOTENDS == 5 || (HOTENDS == 4 && BED_OR_CHAMBER) || ALL(STATUS_COMBINE_HEATERS, HAS_HEATED_CHAMBER)) #undef STATUS_FAN_FRAMES #elif !STATUS_FAN_FRAMES #define STATUS_FAN_FRAMES 2 @@ -253,7 +253,7 @@ ((STATUS_CHAMBER_WIDTH || STATUS_FAN_WIDTH || STATUS_BED_WIDTH) && STATUS_HOTEND_BITMAPS == 4) #define STATUS_HEATERS_X 5 #else - #if BOTH(STATUS_COMBINE_HEATERS, HAS_HEATED_BED) && HOTENDS <= 4 + #if ALL(STATUS_COMBINE_HEATERS, HAS_HEATED_BED) && HOTENDS <= 4 #define STATUS_HEATERS_X 5 #else #define STATUS_HEATERS_X 8 // Like the included bitmaps @@ -742,22 +742,22 @@ #if HAS_FAN0 && STATUS_FAN_WIDTH && HOTENDS <= 4 && defined(STATUS_FAN_FRAMES) #define DO_DRAW_FAN 1 #endif -#if BOTH(HAS_HOTEND, STATUS_HOTEND_ANIM) +#if ALL(HAS_HOTEND, STATUS_HOTEND_ANIM) #define ANIM_HOTEND 1 #endif -#if BOTH(DO_DRAW_BED, STATUS_BED_ANIM) +#if ALL(DO_DRAW_BED, STATUS_BED_ANIM) #define ANIM_BED 1 #endif -#if BOTH(DO_DRAW_CHAMBER, STATUS_CHAMBER_ANIM) +#if ALL(DO_DRAW_CHAMBER, STATUS_CHAMBER_ANIM) #define ANIM_CHAMBER 1 #endif -#if BOTH(DO_DRAW_CUTTER, STATUS_CUTTER_ANIM) +#if ALL(DO_DRAW_CUTTER, STATUS_CUTTER_ANIM) #define ANIM_CUTTER 1 #endif -#if BOTH(DO_DRAW_COOLER, STATUS_COOLER_ANIM) +#if ALL(DO_DRAW_COOLER, STATUS_COOLER_ANIM) #define ANIM_COOLER 1 #endif -#if BOTH(DO_DRAW_FLOWMETER, STATUS_FLOWMETER_ANIM) +#if ALL(DO_DRAW_FLOWMETER, STATUS_FLOWMETER_ANIM) #define ANIM_FLOWMETER 1 #endif #if ANIM_HOTEND || ANIM_BED || ANIM_CHAMBER || ANIM_CUTTER diff --git a/Marlin/src/lcd/dogm/marlinui_DOGM.cpp b/Marlin/src/lcd/dogm/marlinui_DOGM.cpp index 2552df3b88f4..5b2db31fbbd2 100644 --- a/Marlin/src/lcd/dogm/marlinui_DOGM.cpp +++ b/Marlin/src/lcd/dogm/marlinui_DOGM.cpp @@ -155,7 +155,7 @@ bool MarlinUI::detected() { return true; } #if DISABLED(CUSTOM_BOOTSCREEN_ANIMATED_FRAME_TIME) constexpr millis_t frame_time = CUSTOM_BOOTSCREEN_FRAME_TIME; #endif - LOOP_L_N(f, COUNT(custom_bootscreen_animation)) + for (uint8_t f = 0; f < COUNT(custom_bootscreen_animation); ++f) #endif { #if ENABLED(CUSTOM_BOOTSCREEN_ANIMATED_FRAME_TIME) @@ -228,7 +228,7 @@ bool MarlinUI::detected() { return true; } draw_bootscreen_bmp(start_bmp); #else constexpr millis_t frame_time = MARLIN_BOOTSCREEN_FRAME_TIME; - LOOP_L_N(f, COUNT(marlin_bootscreen_animation)) { + for (uint8_t f = 0; f < COUNT(marlin_bootscreen_animation); ++f) { draw_bootscreen_bmp((uint8_t*)pgm_read_ptr(&marlin_bootscreen_animation[f])); if (frame_time) safe_delay(frame_time); } @@ -645,7 +645,7 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop #endif // AUTO_BED_LEVELING_UBL - #if EITHER(BABYSTEP_GFX_OVERLAY, MESH_EDIT_GFX_OVERLAY) + #if ANY(BABYSTEP_GFX_OVERLAY, MESH_EDIT_GFX_OVERLAY) // // Draw knob rotation => Z motion key for: diff --git a/Marlin/src/lcd/dogm/marlinui_DOGM.h b/Marlin/src/lcd/dogm/marlinui_DOGM.h index afdda5ac5bf5..414508b1294c 100644 --- a/Marlin/src/lcd/dogm/marlinui_DOGM.h +++ b/Marlin/src/lcd/dogm/marlinui_DOGM.h @@ -127,7 +127,7 @@ #define U8G_CLASS U8GLIB_SSD1306_128X64 // 8 stripes #endif -#elif EITHER(FYSETC_242_OLED_12864, K3D_242_OLED_CONTROLLER) +#elif ANY(FYSETC_242_OLED_12864, K3D_242_OLED_CONTROLLER) // FYSETC OLED 2.42" 128 Γ— 64 Full Graphics Controller // or K3D OLED 2.42" 128 Γ— 64 Full Graphics Controller @@ -151,7 +151,7 @@ #define U8G_CLASS U8GLIB_SH1306_128X64 // 8 stripes #endif -#elif EITHER(MKS_12864OLED, ZONESTAR_12864OLED) +#elif ANY(MKS_12864OLED, ZONESTAR_12864OLED) // MKS 128x64 (SH1106) OLED I2C LCD // - or - diff --git a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp index 7d1f090d1e3f..12cee1fc80d4 100644 --- a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp +++ b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp @@ -55,7 +55,7 @@ #include "../../feature/spindle_laser.h" #endif -#if EITHER(HAS_COOLER, LASER_COOLANT_FLOW_METER) +#if ANY(HAS_COOLER, LASER_COOLANT_FLOW_METER) #include "../../feature/cooler.h" #endif @@ -127,7 +127,7 @@ #define MAX_HOTEND_DRAW _MIN(HOTENDS, ((LCD_PIXEL_WIDTH - (STATUS_LOGO_BYTEWIDTH + STATUS_FAN_BYTEWIDTH) * 8) / (STATUS_HEATERS_XSPACE))) #endif -#if EITHER(DO_DRAW_BED, DO_DRAW_HOTENDS) +#if ANY(DO_DRAW_BED, DO_DRAW_HOTENDS) #define STATUS_HEATERS_BOT (STATUS_HEATERS_Y + STATUS_HEATERS_HEIGHT - 1) #endif @@ -457,7 +457,7 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const } // Prepare strings for progress display -#if EITHER(HAS_EXTRA_PROGRESS, HAS_PRINT_PROGRESS) +#if ANY(HAS_EXTRA_PROGRESS, HAS_PRINT_PROGRESS) static MarlinUI::progress_t progress = 0; static char bufferc[13]; #endif @@ -512,7 +512,7 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const void MarlinUI::draw_status_screen() { #if NUM_AXES constexpr int xystorage = TERN(INCH_MODE_SUPPORT, 8, 5); - #if EITHER(HAS_X_AXIS, LCD_SHOW_E_TOTAL) + #if ANY(HAS_X_AXIS, LCD_SHOW_E_TOTAL) static char xstring[TERN(LCD_SHOW_E_TOTAL, 12, xystorage)]; #endif #if HAS_Y_AXIS @@ -612,7 +612,7 @@ void MarlinUI::draw_status_screen() { #if DO_DRAW_BED && DISABLED(STATUS_COMBINE_HEATERS) #if ANIM_BED - #if BOTH(HAS_LEVELING, STATUS_ALT_BED_BITMAP) + #if ALL(HAS_LEVELING, STATUS_ALT_BED_BITMAP) #define BED_BITMAP(S) ((S) \ ? (planner.leveling_active ? status_bed_leveled_on_bmp : status_bed_on_bmp) \ : (planner.leveling_active ? status_bed_leveled_bmp : status_bed_bmp)) @@ -672,7 +672,7 @@ void MarlinUI::draw_status_screen() { if (PAGE_UNDER(6 + 1 + 12 + 1 + 6 + 1)) { // Extruders #if DO_DRAW_HOTENDS - LOOP_L_N(e, MAX_HOTEND_DRAW) _draw_hotend_status((heater_id_t)e, blink); + for (uint8_t e = 0; e < MAX_HOTEND_DRAW; ++e) _draw_hotend_status((heater_id_t)e, blink); #endif // Laser / Spindle @@ -783,7 +783,7 @@ void MarlinUI::draw_status_screen() { // XYZ Coordinates // - #if EITHER(XYZ_NO_FRAME, XYZ_HOLLOW_FRAME) + #if ANY(XYZ_NO_FRAME, XYZ_HOLLOW_FRAME) #define XYZ_FRAME_TOP 29 #define XYZ_FRAME_HEIGHT INFO_FONT_ASCENT + 3 #else @@ -890,7 +890,7 @@ void MarlinUI::draw_status_screen() { if (PAGE_CONTAINS(STATUS_BASELINE - INFO_FONT_ASCENT, STATUS_BASELINE + INFO_FONT_DESCENT)) { lcd_moveto(0, STATUS_BASELINE); - #if BOTH(FILAMENT_LCD_DISPLAY, HAS_MEDIA) + #if ALL(FILAMENT_LCD_DISPLAY, HAS_MEDIA) // Alternate Status message and Filament display if (ELAPSED(millis(), next_filament_display)) { lcd_put_u8str(F(LCD_STR_FILAM_DIA)); diff --git a/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp b/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp index bc961dbf15d4..8e709416288f 100644 --- a/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp +++ b/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp @@ -237,7 +237,7 @@ void ST7920_Lite_Status_Screen::clear_ddram() { /* This fills the entire graphics buffer with zeros */ void ST7920_Lite_Status_Screen::clear_gdram() { - LOOP_L_N(y, BUFFER_HEIGHT) { + for (uint8_t y = 0; y < BUFFER_HEIGHT; ++y) { set_gdram_address(0, y); begin_data(); for (uint8_t i = (BUFFER_WIDTH) / 16; i--;) write_word(0); @@ -435,7 +435,7 @@ void ST7920_Lite_Status_Screen::draw_degree_symbol(uint8_t x, uint8_t y, const b const uint8_t x_word = x >> 1, y_top = degree_symbol_y_top, y_bot = y_top + COUNT(degree_symbol); - LOOP_S_L_N(i, y_top, y_bot) { + for (uint8_t i = y_top; i < y_bot; ++i) { uint8_t byte = pgm_read_byte(p_bytes++); set_gdram_address(x_word, i + y * 16); begin_data(); @@ -754,10 +754,10 @@ bool ST7920_Lite_Status_Screen::indicators_changed() { // This drawing is a mess and only produce readable result around 25% steps // i.e. 74-76% look fine [|||||||||||||||||||||||| ], but 73% look like this: [|||||||||||||||| | ] // meaning partially filled bytes produce only single vertical line, and i bet they're not supposed to! - LOOP_S_LE_N(y, top, bottom) { + for (uint8_t y = top; y <= bottom; ++y) { set_gdram_address(left, y); begin_data(); - LOOP_L_N(x, width) { + for (uint8_t x = 0; x < width; ++x) { uint16_t gfx_word = 0x0000; if ((x + 1) * char_pcnt <= value) gfx_word = 0xFFFF; // Draw completely filled bytes diff --git a/Marlin/src/lcd/dogm/u8g_dev_st7920_128x64_HAL.cpp b/Marlin/src/lcd/dogm/u8g_dev_st7920_128x64_HAL.cpp index fde6e41792dc..ae1531e9f8df 100644 --- a/Marlin/src/lcd/dogm/u8g_dev_st7920_128x64_HAL.cpp +++ b/Marlin/src/lcd/dogm/u8g_dev_st7920_128x64_HAL.cpp @@ -87,11 +87,11 @@ void clear_graphics_DRAM(u8g_t *u8g, u8g_dev_t *dev) { u8g_SetAddress(u8g, dev, 0); // cmd mode u8g_WriteByte(u8g, dev, 0x08); //display off, cursor+blink off u8g_WriteByte(u8g, dev, 0x3E); //extended mode + GDRAM active - LOOP_L_N(y, (LCD_PIXEL_HEIGHT) / 2) { //clear GDRAM + for (uint8_t y = 0; y < (LCD_PIXEL_HEIGHT) / 2; ++y) { //clear GDRAM u8g_WriteByte(u8g, dev, 0x80 | y); //set y u8g_WriteByte(u8g, dev, 0x80); //set x = 0 u8g_SetAddress(u8g, dev, 1); /* data mode */ - LOOP_L_N(i, 2 * (LCD_PIXEL_WIDTH) / 8) //2x width clears both segments + for (uint8_t i = 0; i < 2 * (LCD_PIXEL_WIDTH) / 8; ++i) //2x width clears both segments u8g_WriteByte(u8g, dev, 0); u8g_SetAddress(u8g, dev, 0); /* cmd mode */ } diff --git a/Marlin/src/lcd/dogm/u8g_dev_tft_upscale_from_128x64.cpp b/Marlin/src/lcd/dogm/u8g_dev_tft_upscale_from_128x64.cpp index e51767f96a90..3e173aab6cec 100644 --- a/Marlin/src/lcd/dogm/u8g_dev_tft_upscale_from_128x64.cpp +++ b/Marlin/src/lcd/dogm/u8g_dev_tft_upscale_from_128x64.cpp @@ -298,10 +298,10 @@ static void setWindow(u8g_t *u8g, u8g_dev_t *dev, uint16_t Xmin, uint16_t Ymin, v = color; else v = TFT_MARLINBG_COLOR; - LOOP_L_N(n, GRAPHICAL_TFT_UPSCALE) buffer[k++] = v; + for (uint8_t n = 0; n < GRAPHICAL_TFT_UPSCALE; ++n) buffer[k++] = v; } #if HAS_LCD_IO - LOOP_S_L_N(n, 1, GRAPHICAL_TFT_UPSCALE) + for (uint8_t n = 1; n < GRAPHICAL_TFT_UPSCALE; ++n) for (uint16_t l = 0; l < UPSCALE0(length); l++) buffer[l + n * UPSCALE0(length)] = buffer[l]; @@ -412,16 +412,16 @@ uint8_t u8g_dev_tft_320x240_upscale_from_128x64_fn(u8g_t *u8g, u8g_dev_t *dev, u if (TERN0(HAS_TOUCH_BUTTONS_SLEEP, touchBt.isSleeping())) break; if (++page > (HEIGHT / PAGE_HEIGHT)) return 1; - LOOP_L_N(y, PAGE_HEIGHT) { + for (uint8_t y = 0; y < PAGE_HEIGHT; ++y) { uint32_t k = 0; TERN_(HAS_LCD_IO, buffer = (y & 1) ? bufferB : bufferA); for (uint16_t i = 0; i < (uint32_t)pb->width; i++) { const uint8_t b = *(((uint8_t *)pb->buf) + i); const uint16_t c = TEST(b, y) ? TFT_MARLINUI_COLOR : TFT_MARLINBG_COLOR; - LOOP_L_N(n, GRAPHICAL_TFT_UPSCALE) buffer[k++] = c; + for (uint8_t n = 0; n < GRAPHICAL_TFT_UPSCALE; ++n) buffer[k++] = c; } #if HAS_LCD_IO - LOOP_S_L_N(n, 1, GRAPHICAL_TFT_UPSCALE) + for (uint8_t n = 1; n < GRAPHICAL_TFT_UPSCALE; ++n) for (uint16_t l = 0; l < UPSCALE0(WIDTH); l++) buffer[l + n * UPSCALE0(WIDTH)] = buffer[l]; @@ -429,7 +429,7 @@ uint8_t u8g_dev_tft_320x240_upscale_from_128x64_fn(u8g_t *u8g, u8g_dev_t *dev, u #else uint8_t *bufptr = (uint8_t*) buffer; for (uint8_t i = GRAPHICAL_TFT_UPSCALE; i--;) { - LOOP_S_L_N(n, 0, GRAPHICAL_TFT_UPSCALE * 2) { + for (uint8_t n = 0; n < GRAPHICAL_TFT_UPSCALE * 2; ++n) { u8g_WriteSequence(u8g, dev, WIDTH, &bufptr[WIDTH * n]); } } diff --git a/Marlin/src/lcd/e3v2/common/dwin_api.cpp b/Marlin/src/lcd/e3v2/common/dwin_api.cpp index f3abaf25c96b..319c861ea4ff 100644 --- a/Marlin/src/lcd/e3v2/common/dwin_api.cpp +++ b/Marlin/src/lcd/e3v2/common/dwin_api.cpp @@ -38,8 +38,8 @@ uint8_t databuf[26] = { 0 }; // Send the data in the buffer plus the packet tail void DWIN_Send(size_t &i) { ++i; - LOOP_L_N(n, i) { LCD_SERIAL.write(DWIN_SendBuf[n]); delayMicroseconds(1); } - LOOP_L_N(n, 4) { LCD_SERIAL.write(DWIN_BufTail[n]); delayMicroseconds(1); } + for (uint8_t n = 0; n < i; ++n) { LCD_SERIAL.write(DWIN_SendBuf[n]); delayMicroseconds(1); } + for (uint8_t n = 0; n < 4; ++n) { LCD_SERIAL.write(DWIN_BufTail[n]); delayMicroseconds(1); } } /*-------------------------------------- System variable function --------------------------------------*/ diff --git a/Marlin/src/lcd/e3v2/creality/dwin.cpp b/Marlin/src/lcd/e3v2/creality/dwin.cpp index 9ae1cf1e0626..af3d1eaeb8fa 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin.cpp +++ b/Marlin/src/lcd/e3v2/creality/dwin.cpp @@ -76,7 +76,7 @@ #include "../../../module/probe.h" #endif -#if EITHER(BABYSTEP_ZPROBE_OFFSET, JUST_BABYSTEP) +#if ANY(BABYSTEP_ZPROBE_OFFSET, JUST_BABYSTEP) #include "../../../feature/babystep.h" #endif @@ -201,7 +201,7 @@ void HMI_SetLanguageCache() { } void HMI_SetLanguage() { - #if BOTH(EEPROM_SETTINGS, IIC_BL24CXX_EEPROM) + #if ALL(EEPROM_SETTINGS, IIC_BL24CXX_EEPROM) BL24CXX::read(DWIN_LANGUAGE_EEPROM_ADDRESS, (uint8_t*)&HMI_flag.language, sizeof(HMI_flag.language)); #endif HMI_SetLanguageCache(); @@ -210,7 +210,7 @@ void HMI_SetLanguage() { void HMI_ToggleLanguage() { HMI_flag.language = HMI_IsChinese() ? DWIN_ENGLISH : DWIN_CHINESE; HMI_SetLanguageCache(); - #if BOTH(EEPROM_SETTINGS, IIC_BL24CXX_EEPROM) + #if ALL(EEPROM_SETTINGS, IIC_BL24CXX_EEPROM) BL24CXX::write(DWIN_LANGUAGE_EEPROM_ADDRESS, (uint8_t*)&HMI_flag.language, sizeof(HMI_flag.language)); #endif } @@ -475,7 +475,7 @@ void Draw_Back_First(const bool is_sel=true) { #define PREPARE_CASE_ZOFF (PREPARE_CASE_HOME + ENABLED(HAS_ZOFFSET_ITEM)) #define PREPARE_CASE_PLA (PREPARE_CASE_ZOFF + ENABLED(HAS_PREHEAT)) #define PREPARE_CASE_ABS (PREPARE_CASE_PLA + (TERN0(HAS_PREHEAT, PREHEAT_COUNT > 1))) -#define PREPARE_CASE_COOL (PREPARE_CASE_ABS + EITHER(HAS_HOTEND, HAS_HEATED_BED)) +#define PREPARE_CASE_COOL (PREPARE_CASE_ABS + ANY(HAS_HOTEND, HAS_HEATED_BED)) #define PREPARE_CASE_LANG (PREPARE_CASE_COOL + 1) #define PREPARE_CASE_TOTAL PREPARE_CASE_LANG @@ -1375,7 +1375,7 @@ void HMI_Move_Z() { LIMIT(HMI_ValueStruct.offset_value, (Z_PROBE_OFFSET_RANGE_MIN) * 100, (Z_PROBE_OFFSET_RANGE_MAX) * 100); last_zoffset = dwin_zoffset; dwin_zoffset = HMI_ValueStruct.offset_value / 100.0f; - #if EITHER(BABYSTEP_ZPROBE_OFFSET, JUST_BABYSTEP) + #if ANY(BABYSTEP_ZPROBE_OFFSET, JUST_BABYSTEP) if (BABYSTEP_ALLOWED()) babystep.add_mm(Z_AXIS, dwin_zoffset - last_zoffset); #endif Draw_Edit_Signed_Float2(zoff_line, HMI_ValueStruct.offset_value, true); @@ -1891,7 +1891,7 @@ void Redraw_SD_List() { if (card.isMounted()) { // As many files as will fit - LOOP_L_N(i, _MIN(nr_sd_menu_items(), MROWS)) + for (uint8_t i = 0; i < _MIN(nr_sd_menu_items(), MROWS); ++i) Draw_SDItem(i, i + 1); TERN_(SCROLL_LONG_FILENAMES, Init_SDItem_Shift()); @@ -2038,7 +2038,7 @@ void Draw_Info_Menu() { DWIN_Draw_String(false, font8x16, Color_White, Color_Bg_Black, (DWIN_WIDTH - strlen(CORP_WEBSITE) * MENU_CHR_W) / 2, 268, F(CORP_WEBSITE)); Draw_Back_First(); - LOOP_L_N(i, 3) { + for (uint8_t i = 0; i < 3; ++i) { DWIN_ICON_Show(ICON, ICON_PrintSize + i, 26, 99 + i * 73); DWIN_Draw_Line(Line_Color, 16, MBASE(2) + i * 73, 256, 156 + i * 73); } @@ -2291,10 +2291,10 @@ void HMI_Printing() { char cmd[40]; cmd[0] = '\0'; - #if BOTH(HAS_HEATED_BED, PAUSE_HEAT) + #if ALL(HAS_HEATED_BED, PAUSE_HEAT) if (resume_bed_temp) sprintf_P(cmd, PSTR("M190 S%i\n"), resume_bed_temp); #endif - #if BOTH(HAS_HOTEND, PAUSE_HEAT) + #if ALL(HAS_HOTEND, PAUSE_HEAT) if (resume_hotend_temp) sprintf_P(&cmd[strlen(cmd)], PSTR("M109 S%i\n"), resume_hotend_temp); #endif @@ -2390,7 +2390,7 @@ void Draw_Move_Menu() { if (select_axis.now != CASE_BACK) Draw_Menu_Cursor(select_axis.now); // Draw separators and icons - LOOP_L_N(i, 3 + ENABLED(HAS_HOTEND)) Draw_Menu_Line(i + 1, ICON_MoveX + i); + for (uint8_t i = 0; i < 3 + ENABLED(HAS_HOTEND); ++i) Draw_Menu_Line(i + 1, ICON_MoveX + i); } void Item_Adv_HomeOffsets(const uint8_t row) { @@ -2701,7 +2701,7 @@ void HMI_Prepare() { #if HAS_ZOFFSET_ITEM case PREPARE_CASE_ZOFF: - #if EITHER(HAS_BED_PROBE, BABYSTEPPING) + #if ANY(HAS_BED_PROBE, BABYSTEPPING) checkkey = Homeoffset; HMI_ValueStruct.show_mode = -4; HMI_ValueStruct.offset_value = BABY_Z_VAR * 100; @@ -3264,7 +3264,7 @@ void Draw_Max_Speed_Menu() { } Draw_Back_First(); - LOOP_L_N(i, 3 + ENABLED(HAS_HOTEND)) Draw_Menu_Line(i + 1, ICON_MaxSpeedX + i); + for (uint8_t i = 0; i < 3 + ENABLED(HAS_HOTEND); ++i) Draw_Menu_Line(i + 1, ICON_MaxSpeedX + i); Draw_Edit_Integer4(1, planner.settings.max_feedrate_mm_s[X_AXIS]); Draw_Edit_Integer4(2, planner.settings.max_feedrate_mm_s[Y_AXIS]); Draw_Edit_Integer4(3, planner.settings.max_feedrate_mm_s[Z_AXIS]); @@ -3318,7 +3318,7 @@ void Draw_Max_Accel_Menu() { } Draw_Back_First(); - LOOP_L_N(i, 3 + ENABLED(HAS_HOTEND)) Draw_Menu_Line(i + 1, ICON_MaxAccX + i); + for (uint8_t i = 0; i < 3 + ENABLED(HAS_HOTEND); ++i) Draw_Menu_Line(i + 1, ICON_MaxAccX + i); Draw_Edit_Integer4(1, planner.settings.max_acceleration_mm_per_s2[X_AXIS]); Draw_Edit_Integer4(2, planner.settings.max_acceleration_mm_per_s2[Y_AXIS]); Draw_Edit_Integer4(3, planner.settings.max_acceleration_mm_per_s2[Z_AXIS]); @@ -3377,7 +3377,7 @@ void Draw_Max_Accel_Menu() { } Draw_Back_First(); - LOOP_L_N(i, 3 + ENABLED(HAS_HOTEND)) Draw_Menu_Line(i + 1, ICON_MaxSpeedJerkX + i); + for (uint8_t i = 0; i < 3 + ENABLED(HAS_HOTEND); ++i) Draw_Menu_Line(i + 1, ICON_MaxSpeedJerkX + i); Draw_Edit_Float3(1, planner.max_jerk.x * MINUNITMULT); Draw_Edit_Float3(2, planner.max_jerk.y * MINUNITMULT); Draw_Edit_Float3(3, planner.max_jerk.z * MINUNITMULT); @@ -3428,7 +3428,7 @@ void Draw_Steps_Menu() { } Draw_Back_First(); - LOOP_L_N(i, 3 + ENABLED(HAS_HOTEND)) Draw_Menu_Line(i + 1, ICON_StepX + i); + for (uint8_t i = 0; i < 3 + ENABLED(HAS_HOTEND); ++i) Draw_Menu_Line(i + 1, ICON_StepX + i); Draw_Edit_Float3(1, planner.settings.axis_steps_per_mm[X_AXIS] * MINUNITMULT); Draw_Edit_Float3(2, planner.settings.axis_steps_per_mm[Y_AXIS] * MINUNITMULT); Draw_Edit_Float3(3, planner.settings.axis_steps_per_mm[Z_AXIS] * MINUNITMULT); @@ -3780,7 +3780,7 @@ void HMI_Tune() { #endif #if HAS_ZOFFSET_ITEM case TUNE_CASE_ZOFF: // Z-offset - #if EITHER(HAS_BED_PROBE, BABYSTEPPING) + #if ANY(HAS_BED_PROBE, BABYSTEPPING) checkkey = Homeoffset; HMI_ValueStruct.offset_value = BABY_Z_VAR * 100; Draw_Edit_Signed_Float2(TUNE_CASE_ZOFF + MROWS - index_tune, HMI_ValueStruct.offset_value, true); @@ -4240,7 +4240,7 @@ void DWIN_HandleScreen() { case Extruder: HMI_Move_E(); break; case ETemp: HMI_ETemp(); break; #endif - #if EITHER(HAS_BED_PROBE, BABYSTEPPING) + #if ANY(HAS_BED_PROBE, BABYSTEPPING) case Homeoffset: HMI_Zoffset(); break; #endif #if HAS_HEATED_BED diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp index 53e4466bf811..1ef9ee8517f8 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp @@ -594,7 +594,7 @@ void CrealityDWINClass::Draw_Menu(const uint8_t menu, const uint8_t select/*=0*/ active_menu = menu; Clear_Screen(); Draw_Title(Get_Menu_Title(menu)); - LOOP_L_N(i, TROWS) Menu_Item_Handler(menu, i + scrollpos); + for (uint8_t i = 0; i < TROWS; ++i) Menu_Item_Handler(menu, i + scrollpos); DWIN_Draw_Rectangle(1, GetColor(eeprom_settings.cursor_color, Rectangle_Color), 0, MBASE(selection - scrollpos) - 18, 14, MBASE(selection - scrollpos) + 33); } @@ -814,9 +814,9 @@ void CrealityDWINClass::Draw_SD_Item(const uint8_t item, const uint8_t row) { len = pos; if (len > max) len = max; char name[len + 1]; - LOOP_L_N(i, len) name[i] = filename[i]; + for (uint8_t i = 0; i < len; ++i) name[i] = filename[i]; if (pos > max) - LOOP_S_L_N(i, len - 3, len) name[i] = '.'; + for (uint8_t i = len - 3; i < len; ++i) name[i] = '.'; name[len] = '\0'; Draw_Menu_Item(row, card.flag.filenameIsDir ? ICON_More : ICON_File, name); } @@ -829,7 +829,7 @@ void CrealityDWINClass::Draw_SD_List(const bool removed/*=false*/) { scrollpos = 0; process = File; if (card.isMounted() && !removed) { - LOOP_L_N(i, _MIN(card.get_num_items() + 1, TROWS)) + for (uint8_t i = 0; i < _MIN(card.get_num_items() + 1, TROWS); ++i) Draw_SD_Item(i, i); } else { @@ -1104,7 +1104,7 @@ void CrealityDWINClass::Menu_Item_Handler(const uint8_t menu, const uint8_t item #define PREPARE_MANUALLEVEL (PREPARE_HOME + 1) #define PREPARE_ZOFFSET (PREPARE_MANUALLEVEL + ENABLED(HAS_ZOFFSET_ITEM)) #define PREPARE_PREHEAT (PREPARE_ZOFFSET + ENABLED(HAS_PREHEAT)) - #define PREPARE_COOLDOWN (PREPARE_PREHEAT + EITHER(HAS_HOTEND, HAS_HEATED_BED)) + #define PREPARE_COOLDOWN (PREPARE_PREHEAT + ANY(HAS_HOTEND, HAS_HEATED_BED)) #define PREPARE_CHANGEFIL (PREPARE_COOLDOWN + ENABLED(ADVANCED_PAUSE_FEATURE)) #define PREPARE_CUSTOM_MENU (PREPARE_CHANGEFIL + ENABLED(HAS_CUSTOM_MENU)) #define PREPARE_TOTAL PREPARE_CUSTOM_MENU @@ -1392,7 +1392,7 @@ void CrealityDWINClass::Menu_Item_Handler(const uint8_t menu, const uint8_t item break; } break; - case ManualLevel: + case ManualLevel: { #define MLEVEL_BACK 0 #define MLEVEL_PROBE (MLEVEL_BACK + ENABLED(HAS_BED_PROBE)) @@ -1408,10 +1408,10 @@ void CrealityDWINClass::Menu_Item_Handler(const uint8_t menu, const uint8_t item static bool use_probe = false; #if HAS_BED_PROBE - constexpr float probe_x_min = _MAX(0 + corner_pos, X_MIN_POS + probe.offset.x, X_MIN_POS + PROBING_MARGIN) - probe.offset.x, - probe_x_max = _MIN((X_BED_SIZE + X_MIN_POS) - corner_pos, X_MAX_POS + probe.offset.x, X_MAX_POS - PROBING_MARGIN) - probe.offset.x, - probe_y_min = _MAX(0 + corner_pos, Y_MIN_POS + probe.offset.y, Y_MIN_POS + PROBING_MARGIN) - probe.offset.y, - probe_y_max = _MIN((Y_BED_SIZE + Y_MIN_POS) - corner_pos, Y_MAX_POS + probe.offset.y, Y_MAX_POS - PROBING_MARGIN) - probe.offset.y; + const float probe_x_min = _MAX(0 + corner_pos, X_MIN_POS + probe.offset.x, X_MIN_POS + PROBING_MARGIN) - probe.offset.x, + probe_x_max = _MIN((X_BED_SIZE + X_MIN_POS) - corner_pos, X_MAX_POS + probe.offset.x, X_MAX_POS - PROBING_MARGIN) - probe.offset.x, + probe_y_min = _MAX(0 + corner_pos, Y_MIN_POS + probe.offset.y, Y_MIN_POS + PROBING_MARGIN) - probe.offset.y, + probe_y_max = _MIN((Y_BED_SIZE + Y_MIN_POS) - corner_pos, Y_MAX_POS + probe.offset.y, Y_MAX_POS - PROBING_MARGIN) - probe.offset.y; #endif switch (item) { @@ -1423,6 +1423,7 @@ void CrealityDWINClass::Menu_Item_Handler(const uint8_t menu, const uint8_t item Draw_Menu(Prepare, PREPARE_MANUALLEVEL); } break; + #if HAS_BED_PROBE case MLEVEL_PROBE: if (draw) { @@ -1434,7 +1435,7 @@ void CrealityDWINClass::Menu_Item_Handler(const uint8_t menu, const uint8_t item Draw_Checkbox(row, use_probe); if (use_probe) { Popup_Handler(Level); - constexpr struct { xy_pos_t p, ProbePtRaise r } points[] = { + const struct { xy_pos_t p; ProbePtRaise r; } points[] = { { { probe_x_min, probe_y_min }, PROBE_PT_RAISE }, { { probe_x_min, probe_y_max }, PROBE_PT_RAISE }, { { probe_x_max, probe_y_max }, PROBE_PT_RAISE }, @@ -1452,6 +1453,7 @@ void CrealityDWINClass::Menu_Item_Handler(const uint8_t menu, const uint8_t item } break; #endif + case MLEVEL_BL: if (draw) Draw_Menu_Item(row, ICON_AxisBL, F("Bottom Left")); @@ -1566,7 +1568,9 @@ void CrealityDWINClass::Menu_Item_Handler(const uint8_t menu, const uint8_t item Modify_Value(mlev_z_pos, 0, MAX_Z_OFFSET, 100); break; } - break; + + } break; + #if HAS_ZOFFSET_ITEM case ZOffset: @@ -3081,7 +3085,7 @@ void CrealityDWINClass::Menu_Item_Handler(const uint8_t menu, const uint8_t item #define LEVELING_BACK 0 #define LEVELING_ACTIVE (LEVELING_BACK + 1) - #define LEVELING_GET_TILT (LEVELING_ACTIVE + BOTH(HAS_BED_PROBE, AUTO_BED_LEVELING_UBL)) + #define LEVELING_GET_TILT (LEVELING_ACTIVE + ALL(HAS_BED_PROBE, AUTO_BED_LEVELING_UBL)) #define LEVELING_GET_MESH (LEVELING_GET_TILT + 1) #define LEVELING_MANUAL (LEVELING_GET_MESH + 1) #define LEVELING_VIEW (LEVELING_MANUAL + 1) @@ -3116,7 +3120,7 @@ void CrealityDWINClass::Menu_Item_Handler(const uint8_t menu, const uint8_t item Draw_Checkbox(row, planner.leveling_active); } break; - #if BOTH(HAS_BED_PROBE, AUTO_BED_LEVELING_UBL) + #if ALL(HAS_BED_PROBE, AUTO_BED_LEVELING_UBL) case LEVELING_GET_TILT: if (draw) Draw_Menu_Item(row, ICON_Tilt, F("Autotilt Current Mesh")); @@ -4664,12 +4668,12 @@ void CrealityDWINClass::Modify_Option(const uint8_t value, const char * const * void CrealityDWINClass::Update_Status(const char * const text) { if (strncmp_P(text, PSTR(""), 3) == 0) { - LOOP_L_N(i, _MIN((size_t)LONG_FILENAME_LENGTH, strlen(text))) filename[i] = text[i + 3]; + for (uint8_t i = 0; i < _MIN((size_t)LONG_FILENAME_LENGTH, strlen(text)); ++i) filename[i] = text[i + 3]; filename[_MIN((size_t)LONG_FILENAME_LENGTH - 1, strlen(text))] = '\0'; Draw_Print_Filename(true); } else { - LOOP_L_N(i, _MIN((size_t)64, strlen(text))) statusmsg[i] = text[i]; + for (uint8_t i = 0; i < _MIN((size_t)64, strlen(text)); ++i) statusmsg[i] = text[i]; statusmsg[_MIN((size_t)64, strlen(text))] = '\0'; } } diff --git a/Marlin/src/lcd/e3v2/marlinui/ui_common.cpp b/Marlin/src/lcd/e3v2/marlinui/ui_common.cpp index 58a84ac34e51..5d6e238fe1d2 100644 --- a/Marlin/src/lcd/e3v2/marlinui/ui_common.cpp +++ b/Marlin/src/lcd/e3v2/marlinui/ui_common.cpp @@ -582,7 +582,7 @@ void MarlinUI::draw_status_message(const bool blink) { #endif // AUTO_BED_LEVELING_UBL - #if EITHER(BABYSTEP_GFX_OVERLAY, MESH_EDIT_GFX_OVERLAY) + #if ANY(BABYSTEP_GFX_OVERLAY, MESH_EDIT_GFX_OVERLAY) void MarlinUI::zoffset_overlay(const int8_t dir) { const int rot_up = TERN(OVERLAY_GFX_REVERSE, ICON_RotateCCW, ICON_RotateCW), diff --git a/Marlin/src/lcd/e3v2/marlinui/ui_status_480x272.cpp b/Marlin/src/lcd/e3v2/marlinui/ui_status_480x272.cpp index 5cfeb6488f92..b66750bd8812 100644 --- a/Marlin/src/lcd/e3v2/marlinui/ui_status_480x272.cpp +++ b/Marlin/src/lcd/e3v2/marlinui/ui_status_480x272.cpp @@ -192,7 +192,7 @@ FORCE_INLINE void _draw_heater_status(const heater_id_t heater, const uint16_t x #endif celsius_float_t tc = 0, tt = 0; - bool isBed = (DISABLED(HAS_HOTEND) && ENABLED(HAS_HEATED_BED)) || (BOTH(HAS_HOTEND, HAS_HEATED_BED) && heater < 0), + bool isBed = (DISABLED(HAS_HOTEND) && ENABLED(HAS_HEATED_BED)) || (ALL(HAS_HOTEND, HAS_HEATED_BED) && heater < 0), ta = false, c_draw, t_draw, i_draw; c_draw = t_draw = i_draw = !ui.did_first_redraw; if (isBed) { diff --git a/Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp b/Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp index 47b104c5ba47..48e07cc20793 100644 --- a/Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp +++ b/Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp @@ -46,7 +46,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if BOTH(DWIN_LCD_PROUI, HAS_LEVELING) +#if ALL(DWIN_LCD_PROUI, HAS_LEVELING) #include "../../marlinui.h" #include "../../../core/types.h" diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index 6730c026c59a..293e6c2d5cf1 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -233,7 +233,7 @@ MenuClass *MaxAccelMenu = nullptr; MenuClass *MaxJerkMenu = nullptr; #endif MenuClass *StepsMenu = nullptr; -#if EITHER(MPC_EDIT_MENU, MPC_AUTOTUNE_MENU) +#if ANY(MPC_EDIT_MENU, MPC_AUTOTUNE_MENU) MenuClass *HotendMPCMenu = nullptr; #endif #if ENABLED(PIDTEMP) @@ -285,7 +285,7 @@ void HMI_SetLanguageCache() { } void HMI_SetLanguage() { - #if BOTH(EEPROM_SETTINGS, IIC_BL24CXX_EEPROM) + #if ALL(EEPROM_SETTINGS, IIC_BL24CXX_EEPROM) BL24CXX::read(DWIN_LANGUAGE_EEPROM_ADDRESS, (uint8_t*)&HMI_flag.language, sizeof(HMI_flag.language)); #endif HMI_SetLanguageCache(); @@ -294,7 +294,7 @@ void HMI_SetLanguage() { void HMI_ToggleLanguage() { HMI_flag.language = HMI_IsChinese() ? DWIN_ENGLISH : DWIN_CHINESE; HMI_SetLanguageCache(); - #if BOTH(EEPROM_SETTINGS, IIC_BL24CXX_EEPROM) + #if ALL(EEPROM_SETTINGS, IIC_BL24CXX_EEPROM) BL24CXX::write(DWIN_LANGUAGE_EEPROM_ADDRESS, (uint8_t*)&HMI_flag.language, sizeof(HMI_flag.language)); #endif } @@ -569,7 +569,7 @@ void DWIN_Print_Header(const char *text = nullptr) { static char headertxt[31] = ""; // Print header text if (text) { const int8_t size = _MIN(30U, strlen_P(text)); - LOOP_L_N(i, size) headertxt[i] = text[i]; + for (uint8_t i = 0; i < size; ++i) headertxt[i] = text[i]; headertxt[size] = '\0'; } if (checkkey == PrintProcess || checkkey == PrintDone) { @@ -938,7 +938,7 @@ void Draw_Print_File_Menu() { if (card.isMounted()) { if (SET_MENU(FileMenu, MSG_MEDIA_MENU, nr_sd_menu_items() + 1)) { BACK_ITEM(Goto_Main_Menu); - LOOP_L_N(i, nr_sd_menu_items()) { + for (uint8_t i = 0; i < nr_sd_menu_items(); ++i) { MenuItemAdd(onDrawFileName, onClickSDItem); } } @@ -1040,7 +1040,7 @@ void Draw_Info_Menu() { DWINUI::Draw_CenteredString(122, F(MACHINE_SIZE)); DWINUI::Draw_CenteredString(195, F(SHORT_BUILD_VERSION)); - LOOP_L_N(i, 3) { + for (uint8_t i = 0; i < 3; ++i) { DWINUI::Draw_Icon(ICON_PrintSize + i, ICOX, 99 + i * 73); DWIN_Draw_HLine(HMI_data.SplitLine_Color, 16, MBASE(2) + i * 73, 240); } @@ -1410,7 +1410,7 @@ void DWIN_LevelingStart() { HMI_SaveProcessID(Leveling); Title.ShowCaption(GET_TEXT_F(MSG_BED_LEVELING)); DWIN_Show_Popup(ICON_AutoLeveling, GET_TEXT_F(MSG_BED_LEVELING), GET_TEXT_F(MSG_PLEASE_WAIT)); - #if BOTH(AUTO_BED_LEVELING_UBL, PREHEAT_BEFORE_LEVELING) + #if ALL(AUTO_BED_LEVELING_UBL, PREHEAT_BEFORE_LEVELING) #if HAS_HOTEND if (thermalManager.degTargetHotend(0) < LEVELING_NOZZLE_TEMP) thermalManager.setTargetHotend(LEVELING_NOZZLE_TEMP, 0); @@ -1460,7 +1460,7 @@ void DWIN_LevelingDone() { DWINUI::Draw_String(HMI_data.PopupTxt_Color, gfrm.x, gfrm.y - DWINUI::fontHeight() - 4, F("MPC target: Celsius")); break; #endif - #if EITHER(PIDTEMP, PIDTEMPBED) + #if ANY(PIDTEMP, PIDTEMPBED) TERN_(PIDTEMP, case PIDTEMP_START:) TERN_(PIDTEMPBED, case PIDTEMPBED_START:) DWINUI::Draw_CenteredString(HMI_data.PopupTxt_Color, 100, GET_TEXT_F(MSG_PID_AUTOTUNE)); @@ -1471,7 +1471,7 @@ void DWIN_LevelingDone() { switch (HMI_value.pidresult) { default: break; - #if EITHER(PIDTEMP, MPC_AUTOTUNE) + #if ANY(PIDTEMP, MPC_AUTOTUNE) TERN_(PIDTEMP, case PIDTEMP_START:) TERN_(MPC_AUTOTUNE, case MPCTEMP_START:) DWINUI::Draw_CenteredString(HMI_data.PopupTxt_Color, 120, F("for Nozzle is running.")); @@ -1705,10 +1705,10 @@ void DWIN_SetDataDefaults() { TERN_(BAUD_RATE_GCODE, SetBaud250K()); HMI_data.FullManualTramming = false; HMI_data.MediaAutoMount = ENABLED(HAS_SD_EXTENDER); - #if BOTH(INDIVIDUAL_AXIS_HOMING_SUBMENU, MESH_BED_LEVELING) + #if ALL(INDIVIDUAL_AXIS_HOMING_SUBMENU, MESH_BED_LEVELING) HMI_data.z_after_homing = DEF_Z_AFTER_HOMING; #endif - #if BOTH(LED_CONTROL_MENU, HAS_COLOR_LEDS) + #if ALL(LED_CONTROL_MENU, HAS_COLOR_LEDS) TERN_(LED_COLOR_PRESETS, leds.set_default()); ApplyLEDColor(); #endif @@ -1725,7 +1725,7 @@ void DWIN_CopySettingsFrom(const char * const buff) { TERN_(PREVENT_COLD_EXTRUSION, ApplyExtMinT()); feedrate_percentage = 100; TERN_(BAUD_RATE_GCODE, HMI_SetBaudRate()); - #if BOTH(LED_CONTROL_MENU, HAS_COLOR_LEDS) + #if ALL(LED_CONTROL_MENU, HAS_COLOR_LEDS) leds.set_color( HMI_data.Led_Color.r, HMI_data.Led_Color.g, @@ -1983,7 +1983,7 @@ void AutoHome() { queue.inject_P(G28_STR); } void HomeX() { queue.inject(F("G28X")); } void HomeY() { queue.inject(F("G28Y")); } void HomeZ() { queue.inject(F("G28Z")); } - #if BOTH(INDIVIDUAL_AXIS_HOMING_SUBMENU, MESH_BED_LEVELING) + #if ALL(INDIVIDUAL_AXIS_HOMING_SUBMENU, MESH_BED_LEVELING) void ApplyZAfterHoming() { HMI_data.z_after_homing = MenuData.Value; }; void SetZAfterHoming() { SetIntOnClick(0, 20, HMI_data.z_after_homing, ApplyZAfterHoming); } #endif @@ -2001,13 +2001,13 @@ void AutoHome() { queue.inject_P(G28_STR); } void ApplyZOffset() { TERN_(EEPROM_SETTINGS, settings.save()); } void LiveZOffset() { - #if EITHER(BABYSTEP_ZPROBE_OFFSET, JUST_BABYSTEP) + #if ANY(BABYSTEP_ZPROBE_OFFSET, JUST_BABYSTEP) const_float_t step_zoffset = round((MenuData.Value / 100.0f) * planner.settings.axis_steps_per_mm[Z_AXIS]) - babystep.accum; if (BABYSTEP_ALLOWED()) babystep.add_steps(Z_AXIS, step_zoffset); #endif } void SetZOffset() { - #if EITHER(BABYSTEP_ZPROBE_OFFSET, JUST_BABYSTEP) + #if ANY(BABYSTEP_ZPROBE_OFFSET, JUST_BABYSTEP) babystep.accum = round(planner.settings.axis_steps_per_mm[Z_AXIS] * BABY_Z_VAR); #endif SetPFloatOnClick(Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX, 2, ApplyZOffset, LiveZOffset); @@ -2135,7 +2135,7 @@ void SetMoveZ() { HMI_value.axis = Z_AXIS; SetPFloatOnClick(Z_MIN_POS, Z_MAX_POS #endif #if ENABLED(LED_CONTROL_MENU) - #if !BOTH(CASE_LIGHT_MENU, CASE_LIGHT_USE_NEOPIXEL) + #if !ALL(CASE_LIGHT_MENU, CASE_LIGHT_USE_NEOPIXEL) void SetLedStatus() { leds.toggle(); Show_Chkb_Line(leds.lights_on); @@ -2413,9 +2413,9 @@ void TramC () { Tram(4); } DWINUI::Draw_CenteredString(160, F("and relative heights")); safe_delay(1000); float avg = 0.0f; - LOOP_L_N(x, 2) LOOP_L_N(y, 2) avg += zval[x][y]; + for (uint8_t x = 0; x < 2; ++x) for (uint8_t y = 0; y < 2; ++y) avg += zval[x][y]; avg /= 4.0f; - LOOP_L_N(x, 2) LOOP_L_N(y, 2) zval[x][y] -= avg; + for (uint8_t x = 0; x < 2; ++x) for (uint8_t y = 0; y < 2; ++y) zval[x][y] -= avg; MeshViewer.DrawMesh(zval, 2, 2); ui.reset_status(); @@ -2428,7 +2428,7 @@ void TramC () { Tram(4); } float max = 0; FSTR_P plabel; bool s = true; - LOOP_L_N(x, 2) LOOP_L_N(y, 2) { + for (uint8_t x = 0; x < 2; ++x) for (uint8_t y = 0; y < 2; ++y) { const float d = ABS(zval[x][y]); if (max < d) { s = (zval[x][y] >= 0); @@ -2675,7 +2675,7 @@ void onDrawAutoHome(MenuItemClass* menuitem, int8_t line) { } #if HAS_ZOFFSET_ITEM - #if EITHER(BABYSTEP_ZPROBE_OFFSET, JUST_BABYSTEP) + #if ANY(BABYSTEP_ZPROBE_OFFSET, JUST_BABYSTEP) void onDrawZOffset(MenuItemClass* menuitem, int8_t line) { if (HMI_IsChinese()) menuitem->SetFrame(1, 174, 164, 223, 177); onDrawPFloat2Menu(menuitem, line); @@ -3118,7 +3118,7 @@ void Draw_AdvancedSettings_Menu() { #if ENABLED(PIDTEMP) MENU_ITEM_F(ICON_PIDNozzle, STR_HOTEND_PID " Settings", onDrawSubMenu, Draw_HotendPID_Menu); #endif - #if EITHER(MPC_EDIT_MENU, MPC_AUTOTUNE_MENU) + #if ANY(MPC_EDIT_MENU, MPC_AUTOTUNE_MENU) MENU_ITEM_F(ICON_MPCNozzle, "MPC Settings", onDrawSubMenu, Draw_HotendMPC_Menu); #endif #if ENABLED(PIDTEMPBED) @@ -3292,7 +3292,7 @@ void Draw_GetColor_Menu() { DWIN_Draw_Rectangle(1, *MenuData.P_Int, 20, 315, DWIN_WIDTH - 20, 335); } -#if BOTH(CASE_LIGHT_MENU, CASELIGHT_USES_BRIGHTNESS) +#if ALL(CASE_LIGHT_MENU, CASELIGHT_USES_BRIGHTNESS) void Draw_CaseLight_Menu() { checkkey = Menu; @@ -3312,7 +3312,7 @@ void Draw_GetColor_Menu() { checkkey = Menu; if (SET_MENU(LedControlMenu, MSG_LED_CONTROL, 10)) { BACK_ITEM(Draw_Control_Menu); - #if !BOTH(CASE_LIGHT_MENU, CASE_LIGHT_USE_NEOPIXEL) + #if !ALL(CASE_LIGHT_MENU, CASE_LIGHT_USE_NEOPIXEL) EDIT_ITEM(ICON_LedControl, MSG_LEDS, onDrawChkbMenu, SetLedStatus, &leds.lights_on); #endif #if HAS_COLOR_LEDS @@ -3594,7 +3594,7 @@ void Draw_Steps_Menu() { #endif -#if EITHER(MPC_EDIT_MENU, MPC_AUTOTUNE_MENU) +#if ANY(MPC_EDIT_MENU, MPC_AUTOTUNE_MENU) #if ENABLED(MPC_AUTOTUNE_MENU) void HotendMPC() { thermalManager.MPC_autotune(active_extruder); } @@ -3771,7 +3771,7 @@ void Draw_Steps_Menu() { } void UBLSmartFillMesh() { - LOOP_L_N(x, GRID_MAX_POINTS_Y) bedlevel.smart_fill_mesh(); + for (uint8_t x = 0; x < GRID_MAX_POINTS_Y; ++x) bedlevel.smart_fill_mesh(); LCD_MESSAGE(MSG_UBL_MESH_FILLED); } diff --git a/Marlin/src/lcd/e3v2/proui/dwin.h b/Marlin/src/lcd/e3v2/proui/dwin.h index 0057a8639234..2e967bc15f6f 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.h +++ b/Marlin/src/lcd/e3v2/proui/dwin.h @@ -36,7 +36,7 @@ #include "../common/limits.h" #include "../../../libs/BL24CXX.h" -#if EITHER(BABYSTEPPING, HAS_BED_PROBE) +#if ANY(BABYSTEPPING, HAS_BED_PROBE) #define HAS_ZOFFSET_ITEM 1 #if !HAS_BED_PROBE #define JUST_BABYSTEP 1 @@ -75,7 +75,7 @@ enum processID : uint8_t { NothingToDo }; -#if EITHER(DWIN_PID_TUNE, MPC_AUTOTUNE) +#if ANY(DWIN_PID_TUNE, MPC_AUTOTUNE) enum tempcontrol_t : uint8_t { #if DWIN_PID_TUNE @@ -142,10 +142,10 @@ typedef struct { bool FullManualTramming = false; bool MediaAutoMount = ENABLED(HAS_SD_EXTENDER); - #if BOTH(INDIVIDUAL_AXIS_HOMING_SUBMENU, MESH_BED_LEVELING) + #if ALL(INDIVIDUAL_AXIS_HOMING_SUBMENU, MESH_BED_LEVELING) uint8_t z_after_homing = DEF_Z_AFTER_HOMING; #endif - #if BOTH(LED_CONTROL_MENU, HAS_COLOR_LEDS) + #if ALL(LED_CONTROL_MENU, HAS_COLOR_LEDS) LEDColor Led_Color = Def_Leds_Color; #endif } HMI_data_t; @@ -225,7 +225,7 @@ void ParkHead(); #if HAS_ONESTEP_LEVELING void Trammingwizard(); #endif -#if BOTH(LED_CONTROL_MENU, HAS_COLOR_LEDS) +#if ALL(LED_CONTROL_MENU, HAS_COLOR_LEDS) void ApplyLEDColor(); #endif #if ENABLED(AUTO_BED_LEVELING_UBL) @@ -333,7 +333,7 @@ void Draw_FilSet_Menu(); void Draw_PhySet_Menu(); void Draw_SelectColors_Menu(); void Draw_GetColor_Menu(); -#if BOTH(CASE_LIGHT_MENU, CASELIGHT_USES_BRIGHTNESS) +#if ALL(CASE_LIGHT_MENU, CASELIGHT_USES_BRIGHTNESS) void Draw_CaseLight_Menu(); #endif #if ENABLED(LED_CONTROL_MENU) @@ -354,7 +354,7 @@ void Draw_MaxAccel_Menu(); void Draw_MaxJerk_Menu(); #endif void Draw_Steps_Menu(); -#if EITHER(HAS_BED_PROBE, BABYSTEPPING) +#if ANY(HAS_BED_PROBE, BABYSTEPPING) void Draw_ZOffsetWiz_Menu(); #endif #if ENABLED(INDIVIDUAL_AXIS_HOMING_SUBMENU) @@ -384,7 +384,7 @@ void Draw_Steps_Menu(); #endif // MPC -#if EITHER(MPC_EDIT_MENU, MPC_AUTOTUNE_MENU) +#if ANY(MPC_EDIT_MENU, MPC_AUTOTUNE_MENU) void Draw_HotendMPC_Menu(); #endif #if ENABLED(MPC_AUTOTUNE) diff --git a/Marlin/src/lcd/e3v2/proui/dwin_defines.h b/Marlin/src/lcd/e3v2/proui/dwin_defines.h index 164fd00fe6da..6f4520e23bc0 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin_defines.h +++ b/Marlin/src/lcd/e3v2/proui/dwin_defines.h @@ -65,7 +65,7 @@ #define Def_Indicator_Color Color_White #define Def_Coordinate_Color Color_White #define Def_Button_Color RGB( 0, 23, 16) -#if BOTH(LED_CONTROL_MENU, HAS_COLOR_LEDS) +#if ALL(LED_CONTROL_MENU, HAS_COLOR_LEDS) #define Def_Leds_Color LEDColorWhite() #endif #if ENABLED(CASELIGHT_USES_BRIGHTNESS) diff --git a/Marlin/src/lcd/e3v2/proui/dwin_lcd.cpp b/Marlin/src/lcd/e3v2/proui/dwin_lcd.cpp index 6cdafc8a935f..ad2cd2709348 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin_lcd.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin_lcd.cpp @@ -126,9 +126,9 @@ void DWIN_WriteToMem(uint8_t mem, uint16_t addr, uint16_t length, uint8_t *data) DWIN_Byte(i, mem); DWIN_Word(i, addr + indx); // start address of the data block ++i; - LOOP_L_N(j, i) { LCD_SERIAL.write(DWIN_SendBuf[j]); delayMicroseconds(1); } // Buf header + for (uint8_t j = 0; j < i; ++j) { LCD_SERIAL.write(DWIN_SendBuf[j]); delayMicroseconds(1); } // Buf header for (uint16_t j = indx; j <= indx + to_send - 1; j++) LCD_SERIAL.write(*(data + j)); delayMicroseconds(1); // write block of data - LOOP_L_N(j, 4) { LCD_SERIAL.write(DWIN_BufTail[j]); delayMicroseconds(1); } + for (uint8_t j = 0; j < 4; ++j) { LCD_SERIAL.write(DWIN_BufTail[j]); delayMicroseconds(1); } block++; pending -= to_send; } diff --git a/Marlin/src/lcd/e3v2/proui/endstop_diag.cpp b/Marlin/src/lcd/e3v2/proui/endstop_diag.cpp index 7ec088e240c4..860bad74f3f4 100644 --- a/Marlin/src/lcd/e3v2/proui/endstop_diag.cpp +++ b/Marlin/src/lcd/e3v2/proui/endstop_diag.cpp @@ -29,7 +29,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if BOTH(DWIN_LCD_PROUI, HAS_ESDIAG) +#if ALL(DWIN_LCD_PROUI, HAS_ESDIAG) #include "endstop_diag.h" diff --git a/Marlin/src/lcd/e3v2/proui/gcode_preview.cpp b/Marlin/src/lcd/e3v2/proui/gcode_preview.cpp index f8bcda83530a..6cf3e9e135f5 100644 --- a/Marlin/src/lcd/e3v2/proui/gcode_preview.cpp +++ b/Marlin/src/lcd/e3v2/proui/gcode_preview.cpp @@ -29,7 +29,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if BOTH(DWIN_LCD_PROUI, HAS_GCODE_PREVIEW) +#if ALL(DWIN_LCD_PROUI, HAS_GCODE_PREVIEW) #include "../../../core/types.h" #include "../../marlinui.h" diff --git a/Marlin/src/lcd/e3v2/proui/lockscreen.cpp b/Marlin/src/lcd/e3v2/proui/lockscreen.cpp index 85f35582b268..abf67ad9aff4 100644 --- a/Marlin/src/lcd/e3v2/proui/lockscreen.cpp +++ b/Marlin/src/lcd/e3v2/proui/lockscreen.cpp @@ -29,7 +29,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if BOTH(DWIN_LCD_PROUI, HAS_LOCKSCREEN) +#if ALL(DWIN_LCD_PROUI, HAS_LOCKSCREEN) #include "dwin_defines.h" #include "dwinui.h" diff --git a/Marlin/src/lcd/e3v2/proui/meshviewer.cpp b/Marlin/src/lcd/e3v2/proui/meshviewer.cpp index 69d21c044ce9..80f1d35f4034 100644 --- a/Marlin/src/lcd/e3v2/proui/meshviewer.cpp +++ b/Marlin/src/lcd/e3v2/proui/meshviewer.cpp @@ -29,7 +29,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if BOTH(DWIN_LCD_PROUI, HAS_MESH) +#if ALL(DWIN_LCD_PROUI, HAS_MESH) #include "../../../core/types.h" #include "../../marlinui.h" @@ -60,7 +60,7 @@ void MeshViewerClass::DrawMesh(bed_mesh_t zval, const uint8_t sizex, const uint8 #define DrawMeshHLine(yp) DWIN_Draw_HLine(HMI_data.SplitLine_Color, px(0), py(yp), DWIN_WIDTH - 2 * mx) #define DrawMeshVLine(xp) DWIN_Draw_VLine(HMI_data.SplitLine_Color, px(xp), py(sizey - 1), DWIN_WIDTH - 2 * my) int16_t maxz =-32000; int16_t minz = 32000; - LOOP_L_N(y, sizey) LOOP_L_N(x, sizex) { + for (uint8_t y = 0; y < sizey; ++y) for (uint8_t x = 0; x < sizex; ++x) { const float v = isnan(zval[x][y]) ? 0 : round(zval[x][y] * 100); zmesh[x][y] = v; NOLESS(maxz, v); @@ -70,11 +70,11 @@ void MeshViewerClass::DrawMesh(bed_mesh_t zval, const uint8_t sizex, const uint8 min = (float)minz / 100; DWINUI::ClearMainArea(); DWIN_Draw_Rectangle(0, HMI_data.SplitLine_Color, px(0), py(0), px(sizex - 1), py(sizey - 1)); - LOOP_S_L_N(x, 1, sizex - 1) DrawMeshVLine(x); - LOOP_S_L_N(y, 1, sizey - 1) DrawMeshHLine(y); - LOOP_L_N(y, sizey) { + for (uint8_t x = 1; x < sizex - 1; ++x) DrawMeshVLine(x); + for (uint8_t y = 1; y < sizey - 1; ++y) DrawMeshHLine(y); + for (uint8_t y = 0; y < sizey; ++y) { hal.watchdog_refresh(); - LOOP_L_N(x, sizex) { + for (uint8_t x = 0; x < sizex; ++x) { uint16_t color = DWINUI::RainbowInt(zmesh[x][y], _MIN(-5, minz), _MAX(5, maxz)); uint8_t radius = rm(zmesh[x][y]); DWINUI::Draw_FillCircle(color, px(x), py(y), radius); diff --git a/Marlin/src/lcd/e3v2/proui/plot.cpp b/Marlin/src/lcd/e3v2/proui/plot.cpp index fddaf3963ae1..627dc39223cf 100644 --- a/Marlin/src/lcd/e3v2/proui/plot.cpp +++ b/Marlin/src/lcd/e3v2/proui/plot.cpp @@ -29,7 +29,7 @@ #include "../../../inc/MarlinConfig.h" -#if BOTH(DWIN_LCD_PROUI, SHOW_TUNING_GRAPH) +#if ALL(DWIN_LCD_PROUI, SHOW_TUNING_GRAPH) #include "plot.h" #include "../../../core/types.h" diff --git a/Marlin/src/lcd/e3v2/proui/printstats.cpp b/Marlin/src/lcd/e3v2/proui/printstats.cpp index 638cd3420809..7f45fa71ef1b 100644 --- a/Marlin/src/lcd/e3v2/proui/printstats.cpp +++ b/Marlin/src/lcd/e3v2/proui/printstats.cpp @@ -29,7 +29,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if BOTH(DWIN_LCD_PROUI, PRINTCOUNTER) +#if ALL(DWIN_LCD_PROUI, PRINTCOUNTER) #include "printstats.h" diff --git a/Marlin/src/lcd/extui/anycubic/Tunes.cpp b/Marlin/src/lcd/extui/anycubic/Tunes.cpp index d1fb888d17a2..8a9e84f0001d 100644 --- a/Marlin/src/lcd/extui/anycubic/Tunes.cpp +++ b/Marlin/src/lcd/extui/anycubic/Tunes.cpp @@ -31,7 +31,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if EITHER(ANYCUBIC_LCD_CHIRON, ANYCUBIC_LCD_VYPER) +#if ANY(ANYCUBIC_LCD_CHIRON, ANYCUBIC_LCD_VYPER) #include "Tunes.h" #include "../../../libs/buzzer.h" diff --git a/Marlin/src/lcd/extui/anycubic_chiron/chiron_extui.cpp b/Marlin/src/lcd/extui/anycubic_chiron/chiron_extui.cpp index 27ee4689ba12..4ed0461afe0e 100644 --- a/Marlin/src/lcd/extui/anycubic_chiron/chiron_extui.cpp +++ b/Marlin/src/lcd/extui/anycubic_chiron/chiron_extui.cpp @@ -104,10 +104,12 @@ namespace ExtUI { // whether successful or not. } - #if HAS_MESH + #if HAS_LEVELING void onLevelingStart() {} void onLevelingDone() {} + #endif + #if HAS_MESH void onMeshUpdate(const int8_t xpos, const int8_t ypos, const_float_t zval) { // Called when any mesh points are updated //SERIAL_ECHOLNPGM("onMeshUpdate() x:", xpos, " y:", ypos, " z:", zval); diff --git a/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_extui.cpp b/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_extui.cpp index 0df3bde89d50..2bd2a458b879 100644 --- a/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_extui.cpp +++ b/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_extui.cpp @@ -91,11 +91,12 @@ namespace ExtUI { // whether successful or not. } - #if HAS_MESH - + #if HAS_LEVELING void onLevelingStart() {} void onLevelingDone() {} + #endif + #if HAS_MESH void onMeshUpdate(const int8_t xpos, const int8_t ypos, const_float_t zval) { // Called when any mesh points are updated } diff --git a/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.cpp b/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.cpp index dca0f2e85da4..a560e5e9a078 100644 --- a/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.cpp +++ b/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.cpp @@ -885,7 +885,7 @@ void AnycubicTFTClass::getCommandFromTFT() { } void AnycubicTFTClass::doSDCardStateCheck() { - #if BOTH(HAS_MEDIA, HAS_SD_DETECT) + #if ALL(HAS_MEDIA, HAS_SD_DETECT) bool isInserted = isMediaInserted(); if (isInserted) SENDLINE_DBG_PGM("J00", "TFT Serial Debug: SD card state changed... isInserted"); diff --git a/Marlin/src/lcd/extui/anycubic_vyper/dgus_tft.cpp b/Marlin/src/lcd/extui/anycubic_vyper/dgus_tft.cpp index 49609ada329a..518bda73f3f6 100644 --- a/Marlin/src/lcd/extui/anycubic_vyper/dgus_tft.cpp +++ b/Marlin/src/lcd/extui/anycubic_vyper/dgus_tft.cpp @@ -160,7 +160,7 @@ namespace Anycubic { tftSendLn(AC_msg_ready); } - void DgusTFT::ParamInit() { + void DgusTFT::paramInit() { #if ACDEBUG(AC_MARLIN) DEBUG_ECHOLNPGM("DgusTFT::ParamInit()"); @@ -668,11 +668,11 @@ namespace Anycubic { #if ENABLED(POWER_LOSS_RECOVERY) - void DgusTFT::PowerLoss() { + void DgusTFT::powerLoss() { // On: 5A A5 05 82 00 82 00 00 // Off: 5A A5 05 82 00 82 00 64 uint8_t data[] = { 0x5A, 0xA5, 0x05, 0x82, 0x00, 0x82, 0x00, uint8_t(recovery.enabled ? 0x00 : 0x64) }; - LOOP_L_N(i, COUNT(data)) TFTSer.write(data[i]); + for (uint8_t i = 0; i < COUNT(data); ++i) TFTSer.write(data[i]); } void DgusTFT::powerLossRecovery() { @@ -681,12 +681,12 @@ namespace Anycubic { #endif // POWER_LOSS_RECOVERY - void DgusTFT::HomingStart() { + void DgusTFT::homingStart() { if (!isPrintingFromMedia()) ChangePageOfTFT(PAGE_CHS_HOMING); } - void DgusTFT::HomingComplete() { + void DgusTFT::homingComplete() { if (lcd_info.language == ENG && page_index_last > 120) page_index_last -= 120; @@ -720,35 +720,35 @@ namespace Anycubic { TFTSer.println(); } - void DgusTFT::SendValueToTFT(const uint16_t value, const uint16_t address) { + void DgusTFT::sendValueToTFT(const uint16_t value, const uint16_t address) { uint8_t data[] = { 0x5A, 0xA5, 0x05, 0x82, uint8_t(address >> 8), uint8_t(address & 0xFF), uint8_t(value >> 8), uint8_t(value & 0xFF) }; - LOOP_L_N(i, COUNT(data)) TFTSer.write(data[i]); + for (uint8_t i = 0; i < COUNT(data); ++i) TFTSer.write(data[i]); } - void DgusTFT::RequestValueFromTFT(const uint16_t address) { + void DgusTFT::requestValueFromTFT(const uint16_t address) { uint8_t data[] = { 0x5A, 0xA5, 0x04, 0x83, uint8_t(address >> 8), uint8_t(address & 0xFF), 0x01 }; - LOOP_L_N(i, COUNT(data)) TFTSer.write(data[i]); + for (uint8_t i = 0; i < COUNT(data); ++i) TFTSer.write(data[i]); } - void DgusTFT::SendTxtToTFT(const char *pdata, const uint16_t address) { + void DgusTFT::sendTxtToTFT(const char *pdata, const uint16_t address) { uint8_t data_len = strlen(pdata); uint8_t data[] = { 0x5A, 0xA5, uint8_t(data_len + 5), 0x82, uint8_t(address >> 8), uint8_t(address & 0xFF) }; - LOOP_L_N(i, COUNT(data)) TFTSer.write(data[i]); - LOOP_L_N(i, data_len) TFTSer.write(pdata[i]); + for (uint8_t i = 0; i < COUNT(data); ++i) TFTSer.write(data[i]); + for (uint8_t i = 0; i < data_len; ++i) TFTSer.write(pdata[i]); TFTSer.write(0xFF); TFTSer.write(0xFF); } - void DgusTFT::SendColorToTFT(const uint16_t color, const uint16_t address) { + void DgusTFT::sendColorToTFT(const uint16_t color, const uint16_t address) { uint8_t data[] = { 0x5A, 0xA5, 0x05, 0x82, uint8_t(address >> 8), uint8_t(address & 0xFF), uint8_t(color >> 8), uint8_t(color & 0xFF) }; - LOOP_L_N(i, COUNT(data)) TFTSer.write(data[i]); + for (uint8_t i = 0; i < COUNT(data); ++i) TFTSer.write(data[i]); } - void DgusTFT::SendReadNumOfTxtToTFT(const uint8_t number, const uint16_t address) { + void DgusTFT::sendReadNumOfTxtToTFT(const uint8_t number, const uint16_t address) { uint8_t data[] = { 0x5A, 0xA5, 0x04, 0x83, uint8_t(address >> 8), uint8_t(address & 0xFF), number }; - LOOP_L_N(i, COUNT(data)) TFTSer.write(data[i]); + for (uint8_t i = 0; i < COUNT(data); ++i) TFTSer.write(data[i]); } - void DgusTFT::ChangePageOfTFT(const uint16_t page_index, const bool no_send/*=false*/) { + void DgusTFT::changePageOfTFT(const uint16_t page_index, const bool no_send/*=false*/) { #if ACDEBUG(AC_MARLIN) DEBUG_ECHOLNPGM("ChangePageOfTFT: ", page_index); #endif @@ -775,7 +775,7 @@ namespace Anycubic { if (!no_send) { uint8_t data[] = { 0x5A, 0xA5, 0x07, 0x82, 0x00, 0x84, 0x5A, 0x01, uint8_t(data_temp >> 8), uint8_t(data_temp & 0xFF) }; - LOOP_L_N(i, COUNT(data)) TFTSer.write(data[i]); + for (uint8_t i = 0; i < COUNT(data); ++i) TFTSer.write(data[i]); } page_index_last_2 = page_index_last; @@ -789,7 +789,7 @@ namespace Anycubic { #endif } - void DgusTFT::FakeChangePageOfTFT(const uint16_t page_index) { + void DgusTFT::fakeChangePageOfTFT(const uint16_t page_index) { #if ACDEBUG(AC_MARLIN) if (page_index_saved != page_index_now) DEBUG_ECHOLNPGM("FakeChangePageOfTFT: ", page_index); @@ -797,11 +797,11 @@ namespace Anycubic { ChangePageOfTFT(page_index, true); } - void DgusTFT::LcdAudioSet(const bool audio_on) { + void DgusTFT::lcdAudioSet(const bool audio_on) { // On: 5A A5 07 82 00 80 5A 00 00 1A // Off: 5A A5 07 82 00 80 5A 00 00 12 uint8_t data[] = { 0x5A, 0xA5, 0x07, 0x82, 0x00, 0x80, 0x5A, 0x00, 0x00, uint8_t(audio_on ? 0x1A : 0x12) }; - LOOP_L_N(i, 10) TFTSer.write(data[i]); + for (uint8_t i = 0; i < 10; ++i) TFTSer.write(data[i]); } bool DgusTFT::readTFTCommand() { diff --git a/Marlin/src/lcd/extui/anycubic_vyper/dgus_tft.h b/Marlin/src/lcd/extui/anycubic_vyper/dgus_tft.h index 747193dd77f5..63803d209fba 100644 --- a/Marlin/src/lcd/extui/anycubic_vyper/dgus_tft.h +++ b/Marlin/src/lcd/extui/anycubic_vyper/dgus_tft.h @@ -357,7 +357,7 @@ namespace Anycubic { static uint16_t page_index_now; static void startup(); - static void ParamInit(); + static void paramInit(); static void idleLoop(); static void printerKilled(FSTR_P,FSTR_P); static void mediaEvent(media_event_t); @@ -365,10 +365,10 @@ namespace Anycubic { static void filamentRunout(); static void confirmationRequest(const char * const); static void statusChange(const char * const); - static void PowerLoss(); + static void powerLoss(); static void powerLossRecovery(); - static void HomingStart(); - static void HomingComplete(); + static void homingStart(); + static void homingComplete(); static void set_descript_color(const uint16_t color, const uint8_t index=lcd_txtbox_index); static void set_language(language_t); @@ -462,14 +462,14 @@ namespace Anycubic { static void panelAction(uint8_t); static void panelProcess(uint8_t); - static void SendValueToTFT(const uint16_t value, const uint16_t address); - static void RequestValueFromTFT(const uint16_t address); - static void SendTxtToTFT(const char *pdata, const uint16_t address); - static void SendColorToTFT(const uint16_t color, const uint16_t address); - static void SendReadNumOfTxtToTFT(const uint8_t number, const uint16_t address); - static void ChangePageOfTFT(const uint16_t page_index, const bool no_send=false); - static void FakeChangePageOfTFT(const uint16_t page_index); - static void LcdAudioSet(const bool audio_on); + static void sendValueToTFT(const uint16_t value, const uint16_t address); + static void requestValueFromTFT(const uint16_t address); + static void sendTxtToTFT(const char *pdata, const uint16_t address); + static void sendColorToTFT(const uint16_t color, const uint16_t address); + static void sendReadNumOfTxtToTFT(const uint8_t number, const uint16_t address); + static void changePageOfTFT(const uint16_t page_index, const bool no_send=false); + static void fakeChangePageOfTFT(const uint16_t page_index); + static void lcdAudioSet(const bool audio_on); private: diff --git a/Marlin/src/lcd/extui/anycubic_vyper/vyper_extui.cpp b/Marlin/src/lcd/extui/anycubic_vyper/vyper_extui.cpp index 80e1746a2f9f..6990a23f7b72 100644 --- a/Marlin/src/lcd/extui/anycubic_vyper/vyper_extui.cpp +++ b/Marlin/src/lcd/extui/anycubic_vyper/vyper_extui.cpp @@ -108,10 +108,12 @@ namespace ExtUI { // whether successful or not. } - #if HAS_MESH + #if HAS_LEVELING void onLevelingStart() {} void onLevelingDone() {} + #endif + #if HAS_MESH void onMeshUpdate(const int8_t xpos, const int8_t ypos, const_float_t zval) { // Called when any mesh points are updated //SERIAL_ECHOLNPGM("onMeshUpdate() x:", xpos, " y:", ypos, " z:", zval); diff --git a/Marlin/src/lcd/extui/dgus/DGUSDisplay.cpp b/Marlin/src/lcd/extui/dgus/DGUSDisplay.cpp index 876a88891875..8e54b20d99a1 100644 --- a/Marlin/src/lcd/extui/dgus/DGUSDisplay.cpp +++ b/Marlin/src/lcd/extui/dgus/DGUSDisplay.cpp @@ -44,9 +44,9 @@ #include "DGUSVPVariable.h" #include "DGUSDisplayDef.h" -DGUSDisplay dgusdisplay; +DGUSDisplay dgus; -#ifdef DEBUG_DGUSLCD_COMM +#ifdef DEBUG_DGUS_COMM #define DEBUGLCDCOMM_ECHOPGM DEBUG_ECHOPGM #else #define DEBUGLCDCOMM_ECHOPGM(...) NOOP @@ -63,7 +63,7 @@ constexpr uint8_t DGUS_CMD_READVAR = 0x83; bool dguslcd_local_debug; // = false; #endif -void DGUSDisplay::InitDisplay() { +void DGUSDisplay::initDisplay() { #ifndef LCD_BAUDRATE #define LCD_BAUDRATE 115200 #endif @@ -73,13 +73,13 @@ void DGUSDisplay::InitDisplay() { TERN_(DGUS_LCD_UI_MKS, delay(LOGO_TIME_DELAY)); // Show the logo for a little while } - RequestScreen(TERN(SHOW_BOOTSCREEN, DGUSLCD_SCREEN_BOOT, DGUSLCD_SCREEN_MAIN)); + requestScreen(TERN(SHOW_BOOTSCREEN, DGUS_SCREEN_BOOT, DGUS_SCREEN_MAIN)); } -void DGUSDisplay::WriteVariable(uint16_t adr, const void *values, uint8_t valueslen, bool isstr) { +void DGUSDisplay::writeVariable(uint16_t adr, const void *values, uint8_t valueslen, bool isstr) { const char* myvalues = static_cast(values); bool strend = !myvalues; - WriteHeader(adr, DGUS_CMD_WRITEVAR, valueslen); + writeHeader(adr, DGUS_CMD_WRITEVAR, valueslen); while (valueslen--) { char x; if (!strend) x = *myvalues++; @@ -91,25 +91,25 @@ void DGUSDisplay::WriteVariable(uint16_t adr, const void *values, uint8_t values } } -void DGUSDisplay::WriteVariable(uint16_t adr, uint16_t value) { +void DGUSDisplay::writeVariable(uint16_t adr, uint16_t value) { value = (value & 0xFFU) << 8U | (value >> 8U); - WriteVariable(adr, static_cast(&value), sizeof(uint16_t)); + writeVariable(adr, static_cast(&value), sizeof(uint16_t)); } -void DGUSDisplay::WriteVariable(uint16_t adr, int16_t value) { +void DGUSDisplay::writeVariable(uint16_t adr, int16_t value) { value = (value & 0xFFU) << 8U | (value >> 8U); - WriteVariable(adr, static_cast(&value), sizeof(uint16_t)); + writeVariable(adr, static_cast(&value), sizeof(uint16_t)); } -void DGUSDisplay::WriteVariable(uint16_t adr, uint8_t value) { - WriteVariable(adr, static_cast(&value), sizeof(uint8_t)); +void DGUSDisplay::writeVariable(uint16_t adr, uint8_t value) { + writeVariable(adr, static_cast(&value), sizeof(uint8_t)); } -void DGUSDisplay::WriteVariable(uint16_t adr, int8_t value) { - WriteVariable(adr, static_cast(&value), sizeof(int8_t)); +void DGUSDisplay::writeVariable(uint16_t adr, int8_t value) { + writeVariable(adr, static_cast(&value), sizeof(int8_t)); } -void DGUSDisplay::WriteVariable(uint16_t adr, long value) { +void DGUSDisplay::writeVariable(uint16_t adr, long value) { union { long l; char lb[4]; } endian; char tmp[4]; endian.l = value; @@ -117,13 +117,13 @@ void DGUSDisplay::WriteVariable(uint16_t adr, long value) { tmp[1] = endian.lb[2]; tmp[2] = endian.lb[1]; tmp[3] = endian.lb[0]; - WriteVariable(adr, static_cast(&tmp), sizeof(long)); + writeVariable(adr, static_cast(&tmp), sizeof(long)); } -void DGUSDisplay::WriteVariablePGM(uint16_t adr, const void *values, uint8_t valueslen, bool isstr) { +void DGUSDisplay::writeVariablePGM(uint16_t adr, const void *values, uint8_t valueslen, bool isstr) { const char* myvalues = static_cast(values); bool strend = !myvalues; - WriteHeader(adr, DGUS_CMD_WRITEVAR, valueslen); + writeHeader(adr, DGUS_CMD_WRITEVAR, valueslen); while (valueslen--) { char x; if (!strend) x = pgm_read_byte(myvalues++); @@ -135,7 +135,7 @@ void DGUSDisplay::WriteVariablePGM(uint16_t adr, const void *values, uint8_t val } } -void DGUSDisplay::ProcessRx() { +void DGUSDisplay::processRx() { #if ENABLED(SERIAL_STATS_RX_BUFFER_OVERRUNS) if (!LCD_SERIAL.available() && LCD_SERIAL.buffer_overruns()) { @@ -174,8 +174,8 @@ void DGUSDisplay::ProcessRx() { case DGUS_WAIT_TELEGRAM: // wait for complete datagram to arrive. if (LCD_SERIAL.available() < rx_datagram_len) return; - Initialized = true; // We've talked to it, so we defined it as initialized. - uint8_t command = LCD_SERIAL.read(); + initialized = true; // We've talked to it, so we defined it as initialized. + const uint8_t command = LCD_SERIAL.read(); //DEBUGLCDCOMM_ECHOPGM("# ", command); @@ -220,9 +220,9 @@ void DGUSDisplay::ProcessRx() { } } -size_t DGUSDisplay::GetFreeTxBuffer() { return LCD_SERIAL_TX_BUFFER_FREE(); } +size_t DGUSDisplay::getFreeTxBuffer() { return LCD_SERIAL_TX_BUFFER_FREE(); } -void DGUSDisplay::WriteHeader(uint16_t adr, uint8_t cmd, uint8_t payloadlen) { +void DGUSDisplay::writeHeader(uint16_t adr, uint8_t cmd, uint8_t payloadlen) { LCD_SERIAL.write(DGUS_HEADER1); LCD_SERIAL.write(DGUS_HEADER2); LCD_SERIAL.write(payloadlen + 3); @@ -231,29 +231,29 @@ void DGUSDisplay::WriteHeader(uint16_t adr, uint8_t cmd, uint8_t payloadlen) { LCD_SERIAL.write(adr & 0xFF); } -void DGUSDisplay::WritePGM(const char str[], uint8_t len) { +void DGUSDisplay::writePGM(const char str[], uint8_t len) { while (len--) LCD_SERIAL.write(pgm_read_byte(str++)); } void DGUSDisplay::loop() { - // Protect against recursion. ProcessRx() may indirectly call idle() when injecting G-code commands. + // Protect against recursion. processRx() may indirectly call idle() when injecting G-code commands. if (!no_reentrance) { no_reentrance = true; - ProcessRx(); + processRx(); no_reentrance = false; } } rx_datagram_state_t DGUSDisplay::rx_datagram_state = DGUS_IDLE; uint8_t DGUSDisplay::rx_datagram_len = 0; -bool DGUSDisplay::Initialized = false, +bool DGUSDisplay::initialized = false, DGUSDisplay::no_reentrance = false; // A SW memory barrier, to ensure GCC does not overoptimize loops #define sw_barrier() asm volatile("": : :"memory"); bool populate_VPVar(const uint16_t VP, DGUS_VP_Variable * const ramcopy) { - const DGUS_VP_Variable *pvp = DGUSLCD_FindVPVar(VP); + const DGUS_VP_Variable *pvp = findVPVar(VP); if (!pvp) return false; memcpy_P(ramcopy, pvp, sizeof(DGUS_VP_Variable)); return true; diff --git a/Marlin/src/lcd/extui/dgus/DGUSDisplay.h b/Marlin/src/lcd/extui/dgus/DGUSDisplay.h index c307ff44787e..d65c30fc16b6 100644 --- a/Marlin/src/lcd/extui/dgus/DGUSDisplay.h +++ b/Marlin/src/lcd/extui/dgus/DGUSDisplay.h @@ -30,14 +30,14 @@ #include // size_t //#define DEBUG_DGUSLCD -//#define DEBUG_DGUSLCD_COMM +//#define DEBUG_DGUS_COMM #if HAS_BED_PROBE #include "../../../module/probe.h" #endif #include "DGUSVPVariable.h" -enum DGUSLCD_Screens : uint8_t; +enum DGUS_ScreenID : uint8_t; #define DEBUG_OUT ENABLED(DEBUG_DGUSLCD) #include "../../../core/debug_out.h" @@ -57,25 +57,25 @@ class DGUSDisplay { DGUSDisplay() = default; - static void InitDisplay(); + static void initDisplay(); // Variable access. - static void WriteVariable(uint16_t adr, const void *values, uint8_t valueslen, bool isstr=false); - static void WriteVariablePGM(uint16_t adr, const void *values, uint8_t valueslen, bool isstr=false); - static void WriteVariable(uint16_t adr, int16_t value); - static void WriteVariable(uint16_t adr, uint16_t value); - static void WriteVariable(uint16_t adr, uint8_t value); - static void WriteVariable(uint16_t adr, int8_t value); - static void WriteVariable(uint16_t adr, long value); + static void writeVariable(uint16_t adr, const void *values, uint8_t valueslen, bool isstr=false); + static void writeVariablePGM(uint16_t adr, const void *values, uint8_t valueslen, bool isstr=false); + static void writeVariable(uint16_t adr, int16_t value); + static void writeVariable(uint16_t adr, uint16_t value); + static void writeVariable(uint16_t adr, uint8_t value); + static void writeVariable(uint16_t adr, int8_t value); + static void writeVariable(uint16_t adr, long value); // Utility functions for bridging ui_api and dbus template - static void SetVariable(DGUS_VP_Variable &var) { - WriteVariable(var.VP, (WireType)Getter(selector)); + static void setVariable(DGUS_VP_Variable &var) { + writeVariable(var.VP, (WireType)Getter(selector)); } template - static void GetVariable(DGUS_VP_Variable &var, void *val_ptr) { + static void getVariable(DGUS_VP_Variable &var, void *val_ptr) { uint16_t newvalue = swap16(*(uint16_t*)val_ptr); Setter(newvalue, selector); } @@ -86,39 +86,39 @@ class DGUSDisplay { // Force display into another screen. // (And trigger update of containing VPs) // (to implement a pop up message, which may not be nested) - static void RequestScreen(DGUSLCD_Screens screen); + static void requestScreen(const DGUS_ScreenID screenID); // Periodic tasks, eg. Rx-Queue handling. static void loop(); public: // Helper for users of this class to estimate if an interaction would be blocking. - static size_t GetFreeTxBuffer(); + static size_t getFreeTxBuffer(); // Checks two things: Can we confirm the presence of the display and has we initialized it. // (both boils down that the display answered to our chatting) - static bool isInitialized() { return Initialized; } + static bool isInitialized() { return initialized; } private: - static void WriteHeader(uint16_t adr, uint8_t cmd, uint8_t payloadlen); - static void WritePGM(const char str[], uint8_t len); - static void ProcessRx(); + static void writeHeader(uint16_t adr, uint8_t cmd, uint8_t payloadlen); + static void writePGM(const char str[], uint8_t len); + static void processRx(); static rx_datagram_state_t rx_datagram_state; static uint8_t rx_datagram_len; - static bool Initialized, no_reentrance; + static bool initialized, no_reentrance; }; -extern DGUSDisplay dgusdisplay; +extern DGUSDisplay dgus; // compile-time x^y constexpr float cpow(const float x, const int y) { return y == 0 ? 1.0 : x * cpow(x, y - 1); } /// -const uint16_t* DGUSLCD_FindScreenVPMapList(uint8_t screen); +const uint16_t* findScreenVPMapList(uint8_t screen); /// Find the flash address of a DGUS_VP_Variable for the VP. -const DGUS_VP_Variable* DGUSLCD_FindVPVar(const uint16_t vp); +const DGUS_VP_Variable* findVPVar(const uint16_t vp); /// Helper to populate a DGUS_VP_Variable for a given VP. Return false if not found. bool populate_VPVar(const uint16_t VP, DGUS_VP_Variable * const ramcopy); diff --git a/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp index e8abc259a21d..d440ea537539 100644 --- a/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp @@ -40,15 +40,15 @@ #include "../../../feature/powerloss.h" #endif -DGUSScreenHandlerClass ScreenHandler; +DGUSScreenHandlerClass screen; -uint16_t DGUSScreenHandler::ConfirmVP; +uint16_t DGUSScreenHandler::confirmVP; -DGUSLCD_Screens DGUSScreenHandler::current_screen; -DGUSLCD_Screens DGUSScreenHandler::past_screens[NUM_PAST_SCREENS]; +DGUS_ScreenID DGUSScreenHandler::current_screenID; +DGUS_ScreenID DGUSScreenHandler::past_screenIDs[NUM_PAST_SCREENS]; uint8_t DGUSScreenHandler::update_ptr; uint16_t DGUSScreenHandler::skipVP; -bool DGUSScreenHandler::ScreenComplete; +bool DGUSScreenHandler::screenComplete; void (*DGUSScreenHandler::confirm_action_cb)() = nullptr; @@ -62,42 +62,42 @@ void (*DGUSScreenHandler::confirm_action_cb)() = nullptr; filament_data_t filament_data; #endif -void DGUSScreenHandler::sendinfoscreen(PGM_P const line1, PGM_P const line2, PGM_P const line3, PGM_P const line4, bool l1inflash, bool l2inflash, bool l3inflash, bool l4inflash) { +void DGUSScreenHandler::sendInfoScreen(PGM_P const line1, PGM_P const line2, PGM_P const line3, PGM_P const line4, bool l1inflash, bool l2inflash, bool l3inflash, bool l4inflash) { DGUS_VP_Variable ramcopy; if (populate_VPVar(VP_MSGSTR1, &ramcopy)) { ramcopy.memadr = (void*) line1; - l1inflash ? DGUSScreenHandler::DGUSLCD_SendStringToDisplayPGM(ramcopy) : DGUSScreenHandler::DGUSLCD_SendStringToDisplay(ramcopy); + l1inflash ? DGUSScreenHandler::sendStringToDisplayPGM(ramcopy) : DGUSScreenHandler::sendStringToDisplay(ramcopy); } if (populate_VPVar(VP_MSGSTR2, &ramcopy)) { ramcopy.memadr = (void*) line2; - l2inflash ? DGUSScreenHandler::DGUSLCD_SendStringToDisplayPGM(ramcopy) : DGUSScreenHandler::DGUSLCD_SendStringToDisplay(ramcopy); + l2inflash ? DGUSScreenHandler::sendStringToDisplayPGM(ramcopy) : DGUSScreenHandler::sendStringToDisplay(ramcopy); } if (populate_VPVar(VP_MSGSTR3, &ramcopy)) { ramcopy.memadr = (void*) line3; - l3inflash ? DGUSScreenHandler::DGUSLCD_SendStringToDisplayPGM(ramcopy) : DGUSScreenHandler::DGUSLCD_SendStringToDisplay(ramcopy); + l3inflash ? DGUSScreenHandler::sendStringToDisplayPGM(ramcopy) : DGUSScreenHandler::sendStringToDisplay(ramcopy); } #ifdef VP_MSGSTR4 if (populate_VPVar(VP_MSGSTR4, &ramcopy)) { ramcopy.memadr = (void*) line4; - l4inflash ? DGUSScreenHandler::DGUSLCD_SendStringToDisplayPGM(ramcopy) : DGUSScreenHandler::DGUSLCD_SendStringToDisplay(ramcopy); + l4inflash ? DGUSScreenHandler::sendStringToDisplayPGM(ramcopy) : DGUSScreenHandler::sendStringToDisplay(ramcopy); } #endif } -void DGUSScreenHandler::HandleUserConfirmationPopUp(uint16_t VP, PGM_P const line1, PGM_P const line2, PGM_P const line3, PGM_P const line4, bool l1, bool l2, bool l3, bool l4) { - if (current_screen == DGUSLCD_SCREEN_CONFIRM) // Already showing a pop up, so we need to cancel that first. - PopToOldScreen(); +void DGUSScreenHandler::handleUserConfirmationPopUp(uint16_t VP, PGM_P const line1, PGM_P const line2, PGM_P const line3, PGM_P const line4, bool l1, bool l2, bool l3, bool l4) { + if (current_screenID == DGUS_SCREEN_CONFIRM) // Already showing a pop up, so we need to cancel that first. + popToOldScreen(); - ConfirmVP = VP; - sendinfoscreen(line1, line2, line3, line4, l1, l2, l3, l4); - GotoScreen(DGUSLCD_SCREEN_CONFIRM); + confirmVP = VP; + sendInfoScreen(line1, line2, line3, line4, l1, l2, l3, l4); + gotoScreen(DGUS_SCREEN_CONFIRM); } -void DGUSScreenHandler::setstatusmessage(const char *msg) { +void DGUSScreenHandler::setStatusMessage(const char *msg) { DGUS_VP_Variable ramcopy; if (populate_VPVar(VP_M117, &ramcopy)) { ramcopy.memadr = (void*) msg; - DGUSLCD_SendStringToDisplay(ramcopy); + sendStringToDisplay(ramcopy); } } @@ -105,46 +105,46 @@ void DGUSScreenHandler::setstatusmessagePGM(PGM_P const msg) { DGUS_VP_Variable ramcopy; if (populate_VPVar(VP_M117, &ramcopy)) { ramcopy.memadr = (void*) msg; - DGUSLCD_SendStringToDisplayPGM(ramcopy); + sendStringToDisplayPGM(ramcopy); } } // Send an 8 bit or 16 bit value to the display. -void DGUSScreenHandler::DGUSLCD_SendWordValueToDisplay(DGUS_VP_Variable &var) { +void DGUSScreenHandler::sendWordValueToDisplay(DGUS_VP_Variable &var) { if (var.memadr) { if (var.size > 1) - dgusdisplay.WriteVariable(var.VP, *(int16_t*)var.memadr); + dgus.writeVariable(var.VP, *(int16_t*)var.memadr); else - dgusdisplay.WriteVariable(var.VP, *(int8_t*)var.memadr); + dgus.writeVariable(var.VP, *(int8_t*)var.memadr); } } // Send an uint8_t between 0 and 255 to the display, but scale to a percentage (0..100) -void DGUSScreenHandler::DGUSLCD_SendPercentageToDisplay(DGUS_VP_Variable &var) { +void DGUSScreenHandler::sendPercentageToDisplay(DGUS_VP_Variable &var) { if (var.memadr) { uint16_t tmp = *(uint8_t *) var.memadr + 1; // +1 -> avoid rounding issues for the display. tmp = map(tmp, 0, 255, 0, 100); - dgusdisplay.WriteVariable(var.VP, tmp); + dgus.writeVariable(var.VP, tmp); } } // Send the current print progress to the display. -void DGUSScreenHandler::DGUSLCD_SendPrintProgressToDisplay(DGUS_VP_Variable &var) { +void DGUSScreenHandler::sendPrintProgressToDisplay(DGUS_VP_Variable &var) { uint16_t tmp = ExtUI::getProgress_percent(); - dgusdisplay.WriteVariable(var.VP, tmp); + dgus.writeVariable(var.VP, tmp); } // Send the current print time to the display. // It is using a hex display for that: It expects BSD coded data in the format xxyyzz -void DGUSScreenHandler::DGUSLCD_SendPrintTimeToDisplay(DGUS_VP_Variable &var) { +void DGUSScreenHandler::sendPrintTimeToDisplay(DGUS_VP_Variable &var) { duration_t elapsed = print_job_timer.duration(); char buf[32]; elapsed.toString(buf); - dgusdisplay.WriteVariable(VP_PrintTime, buf, var.size, true); + dgus.writeVariable(VP_PrintTime, buf, var.size, true); } // Send an uint8_t between 0 and 100 to a variable scale to 0..255 -void DGUSScreenHandler::DGUSLCD_PercentageToUint8(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandler::percentageToUint8(DGUS_VP_Variable &var, void *val_ptr) { if (var.memadr) { const uint16_t value = BE16_P(val_ptr); *(uint8_t*)var.memadr = map(constrain(value, 0, 100), 0, 100, 0, 255); @@ -154,21 +154,21 @@ void DGUSScreenHandler::DGUSLCD_PercentageToUint8(DGUS_VP_Variable &var, void *v // Sends a (RAM located) string to the DGUS Display // (Note: The DGUS Display does not clear after the \0, you have to // overwrite the remainings with spaces.// var.size has the display buffer size! -void DGUSScreenHandler::DGUSLCD_SendStringToDisplay(DGUS_VP_Variable &var) { +void DGUSScreenHandler::sendStringToDisplay(DGUS_VP_Variable &var) { char *tmp = (char*) var.memadr; - dgusdisplay.WriteVariable(var.VP, tmp, var.size, true); + dgus.writeVariable(var.VP, tmp, var.size, true); } // Sends a (flash located) string to the DGUS Display // (Note: The DGUS Display does not clear after the \0, you have to // overwrite the remainings with spaces.// var.size has the display buffer size! -void DGUSScreenHandler::DGUSLCD_SendStringToDisplayPGM(DGUS_VP_Variable &var) { +void DGUSScreenHandler::sendStringToDisplayPGM(DGUS_VP_Variable &var) { char *tmp = (char*) var.memadr; - dgusdisplay.WriteVariablePGM(var.VP, tmp, var.size, true); + dgus.writeVariablePGM(var.VP, tmp, var.size, true); } #if HAS_PID_HEATING - void DGUSScreenHandler::DGUSLCD_SendTemperaturePID(DGUS_VP_Variable &var) { + void DGUSScreenHandler::sendTemperaturePID(DGUS_VP_Variable &var) { float value = *(float *)var.memadr; value /= 10; float valuesend = 0; @@ -198,7 +198,7 @@ void DGUSScreenHandler::DGUSLCD_SendStringToDisplayPGM(DGUS_VP_Variable &var) { endian.i = valuesend; tmp[0] = endian.lb[1]; tmp[1] = endian.lb[0]; - dgusdisplay.WriteVariable(var.VP, tmp, 2); + dgus.writeVariable(var.VP, tmp, 2); } #endif @@ -206,19 +206,19 @@ void DGUSScreenHandler::DGUSLCD_SendStringToDisplayPGM(DGUS_VP_Variable &var) { // Send the accumulate print time to the display. // It is using a hex display for that: It expects BSD coded data in the format xxyyzz - void DGUSScreenHandler::DGUSLCD_SendPrintAccTimeToDisplay(DGUS_VP_Variable &var) { + void DGUSScreenHandler::sendPrintAccTimeToDisplay(DGUS_VP_Variable &var) { printStatistics state = print_job_timer.getStats(); char buf[22]; duration_t elapsed = state.printTime; elapsed.toString(buf); - dgusdisplay.WriteVariable(VP_PrintAccTime, buf, var.size, true); + dgus.writeVariable(VP_PrintAccTime, buf, var.size, true); } - void DGUSScreenHandler::DGUSLCD_SendPrintsTotalToDisplay(DGUS_VP_Variable &var) { + void DGUSScreenHandler::sendPrintsTotalToDisplay(DGUS_VP_Variable &var) { printStatistics state = print_job_timer.getStats(); char buf[10]; sprintf_P(buf, PSTR("%u"), state.totalPrints); - dgusdisplay.WriteVariable(VP_PrintsTotal, buf, var.size, true); + dgus.writeVariable(VP_PrintsTotal, buf, var.size, true); } #endif @@ -226,33 +226,33 @@ void DGUSScreenHandler::DGUSLCD_SendStringToDisplayPGM(DGUS_VP_Variable &var) { // Send fan status value to the display. #if HAS_FAN - void DGUSScreenHandler::DGUSLCD_SendFanStatusToDisplay(DGUS_VP_Variable &var) { + void DGUSScreenHandler::sendFanStatusToDisplay(DGUS_VP_Variable &var) { if (var.memadr) { uint16_t data_to_send = 0; if (*(uint8_t *) var.memadr) data_to_send = 1; - dgusdisplay.WriteVariable(var.VP, data_to_send); + dgus.writeVariable(var.VP, data_to_send); } } #endif // Send heater status value to the display. -void DGUSScreenHandler::DGUSLCD_SendHeaterStatusToDisplay(DGUS_VP_Variable &var) { +void DGUSScreenHandler::sendHeaterStatusToDisplay(DGUS_VP_Variable &var) { if (var.memadr) { uint16_t data_to_send = 0; if (*(int16_t *) var.memadr) data_to_send = 1; - dgusdisplay.WriteVariable(var.VP, data_to_send); + dgus.writeVariable(var.VP, data_to_send); } } #if ENABLED(DGUS_UI_WAITING) - void DGUSScreenHandler::DGUSLCD_SendWaitingStatusToDisplay(DGUS_VP_Variable &var) { + void DGUSScreenHandler::sendWaitingStatusToDisplay(DGUS_VP_Variable &var) { // In FYSETC UI design there are 10 statuses to loop static uint16_t period = 0; static uint16_t index = 0; if (period++ > DGUS_UI_WAITING_STATUS_PERIOD) { - dgusdisplay.WriteVariable(var.VP, index); + dgus.writeVariable(var.VP, index); if (++index >= DGUS_UI_WAITING_STATUS) index = 0; period = 0; } @@ -262,11 +262,11 @@ void DGUSScreenHandler::DGUSLCD_SendHeaterStatusToDisplay(DGUS_VP_Variable &var) #if HAS_MEDIA - void DGUSScreenHandler::ScreenChangeHookIfSD(DGUS_VP_Variable &var, void *val_ptr) { + void DGUSScreenHandler::screenChangeHookIfSD(DGUS_VP_Variable &var, void *val_ptr) { // default action executed when there is a SD card, but not printing if (ExtUI::isMediaInserted() && !ExtUI::isPrintingFromMedia()) { - ScreenChangeHook(var, val_ptr); - dgusdisplay.RequestScreen(current_screen); + screenChangeHook(var, val_ptr); + dgus.requestScreen(current_screenID); return; } @@ -274,22 +274,22 @@ void DGUSScreenHandler::DGUSLCD_SendHeaterStatusToDisplay(DGUS_VP_Variable &var) // This should host e.g a print pause / print abort / print resume dialog. // This concept allows to recycle this hook for other file if (ExtUI::isPrintingFromMedia() && !card.flag.abort_sd_printing) { - GotoScreen(DGUSLCD_SCREEN_SDPRINTMANIPULATION); + gotoScreen(DGUS_SCREEN_SDPRINTMANIPULATION); return; } // Don't let the user in the dark why there is no reaction. if (!ExtUI::isMediaInserted()) { - setstatusmessage(GET_TEXT_F(MSG_NO_MEDIA)); + setStatusMessage(GET_TEXT_F(MSG_NO_MEDIA)); return; } if (card.flag.abort_sd_printing) { - setstatusmessage(GET_TEXT_F(MSG_MEDIA_ABORTING)); + setStatusMessage(GET_TEXT_F(MSG_MEDIA_ABORTING)); return; } } - void DGUSScreenHandler::DGUSLCD_SD_ScrollFilelist(DGUS_VP_Variable& var, void *val_ptr) { + void DGUSScreenHandler::sdScrollFilelist(DGUS_VP_Variable& var, void *val_ptr) { auto old_top = top_file; const int16_t scroll = (int16_t)BE16_P(val_ptr); if (scroll) { @@ -306,38 +306,38 @@ void DGUSScreenHandler::DGUSLCD_SendHeaterStatusToDisplay(DGUS_VP_Variable &var) else if (!filelist.isAtRootDir()) { IF_DISABLED(DGUS_LCD_UI_MKS, filelist.upDir()); top_file = 0; - ForceCompleteUpdate(); + forceCompleteUpdate(); } - if (old_top != top_file) ForceCompleteUpdate(); + if (old_top != top_file) forceCompleteUpdate(); } - void DGUSScreenHandler::DGUSLCD_SD_ReallyAbort(DGUS_VP_Variable &var, void *val_ptr) { + void DGUSScreenHandler::sdReallyAbort(DGUS_VP_Variable &var, void *val_ptr) { ExtUI::stopPrint(); - GotoScreen(DGUSLCD_SCREEN_MAIN); + gotoScreen(DGUS_SCREEN_MAIN); } - void DGUSScreenHandler::DGUSLCD_SD_PrintTune(DGUS_VP_Variable &var, void *val_ptr) { + void DGUSScreenHandler::sdPrintTune(DGUS_VP_Variable &var, void *val_ptr) { if (!ExtUI::isPrintingFromMedia()) return; // avoid race condition when user stays in this menu and printer finishes. - GotoScreen(DGUSLCD_SCREEN_SDPRINTTUNE); + gotoScreen(DGUS_SCREEN_SDPRINTTUNE); } - void DGUSScreenHandler::SDCardError() { - DGUSScreenHandler::SDCardRemoved(); - sendinfoscreen(F("NOTICE"), nullptr, F("SD card error"), nullptr, true, true, true, true); - SetupConfirmAction(nullptr); - GotoScreen(DGUSLCD_SCREEN_POPUP); + void DGUSScreenHandler::sdCardError() { + DGUSScreenHandler::sdCardRemoved(); + sendInfoScreen(F("NOTICE"), nullptr, F("SD card error"), nullptr, true, true, true, true); + setupConfirmAction(nullptr); + gotoScreen(DGUS_SCREEN_POPUP); } #endif // HAS_MEDIA -void DGUSScreenHandler::ScreenConfirmedOK(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandler::screenConfirmedOK(DGUS_VP_Variable &var, void *val_ptr) { DGUS_VP_Variable ramcopy; - if (!populate_VPVar(ConfirmVP, &ramcopy)) return; + if (!populate_VPVar(confirmVP, &ramcopy)) return; if (ramcopy.set_by_display_handler) ramcopy.set_by_display_handler(ramcopy, val_ptr); } -const uint16_t* DGUSLCD_FindScreenVPMapList(uint8_t screen) { +const uint16_t* findScreenVPMapList(uint8_t screen) { const uint16_t *ret; const struct VPMapping *map = VPMap; while ((ret = (uint16_t*) pgm_read_ptr(&(map->VPList)))) { @@ -347,7 +347,7 @@ const uint16_t* DGUSLCD_FindScreenVPMapList(uint8_t screen) { return nullptr; } -const DGUS_VP_Variable* DGUSLCD_FindVPVar(const uint16_t vp) { +const DGUS_VP_Variable* findVPVar(const uint16_t vp) { const DGUS_VP_Variable *ret = ListOfVP; do { const uint16_t vpcheck = pgm_read_word(&(ret->VP)); @@ -359,19 +359,19 @@ const DGUS_VP_Variable* DGUSLCD_FindVPVar(const uint16_t vp) { return nullptr; } -void DGUSScreenHandler::ScreenChangeHookIfIdle(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandler::screenChangeHookIfIdle(DGUS_VP_Variable &var, void *val_ptr) { if (!ExtUI::isPrinting()) { - ScreenChangeHook(var, val_ptr); - dgusdisplay.RequestScreen(current_screen); + screenChangeHook(var, val_ptr); + dgus.requestScreen(current_screenID); } } -void DGUSScreenHandler::HandleAllHeatersOff(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandler::handleAllHeatersOff(DGUS_VP_Variable &var, void *val_ptr) { thermalManager.disable_all_heaters(); - ForceCompleteUpdate(); // hint to send all data. + forceCompleteUpdate(); // hint to send all data. } -void DGUSScreenHandler::HandleTemperatureChanged(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandler::handleTemperatureChanged(DGUS_VP_Variable &var, void *val_ptr) { celsius_t newvalue = BE16_P(val_ptr); celsius_t acceptedvalue; @@ -405,7 +405,7 @@ void DGUSScreenHandler::HandleTemperatureChanged(DGUS_VP_Variable &var, void *va skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel } -void DGUSScreenHandler::HandleFlowRateChanged(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandler::handleFlowRateChanged(DGUS_VP_Variable &var, void *val_ptr) { #if HAS_EXTRUDERS const uint16_t newvalue = BE16_P(val_ptr); uint8_t target_extruder; @@ -424,7 +424,7 @@ void DGUSScreenHandler::HandleFlowRateChanged(DGUS_VP_Variable &var, void *val_p #endif } -void DGUSScreenHandler::HandleManualExtrude(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandler::handleManualExtrude(DGUS_VP_Variable &var, void *val_ptr) { const int16_t movevalue = BE16_P(val_ptr); float target = movevalue * 0.01f; ExtUI::extruder_t target_extruder; @@ -445,17 +445,17 @@ void DGUSScreenHandler::HandleManualExtrude(DGUS_VP_Variable &var, void *val_ptr } #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) - void DGUSScreenHandler::HandleManualMoveOption(DGUS_VP_Variable &var, void *val_ptr) { + void DGUSScreenHandler::handleManualMoveOption(DGUS_VP_Variable &var, void *val_ptr) { *(uint16_t*)var.memadr = BE16_P(val_ptr); } #endif -void DGUSScreenHandler::HandleMotorLockUnlock(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandler::handleMotorLockUnlock(DGUS_VP_Variable &var, void *val_ptr) { const int16_t lock = BE16_P(val_ptr); queue.enqueue_one_now(lock ? F("M18") : F("M17")); } -void DGUSScreenHandler::HandleSettings(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandler::handleSettings(DGUS_VP_Variable &var, void *val_ptr) { const uint16_t value = BE16_P(val_ptr); switch (value) { default: break; @@ -469,7 +469,7 @@ void DGUSScreenHandler::HandleSettings(DGUS_VP_Variable &var, void *val_ptr) { } } -void DGUSScreenHandler::HandleStepPerMMChanged(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandler::handleStepPerMMChanged(DGUS_VP_Variable &var, void *val_ptr) { const uint16_t value_raw = BE16_P(val_ptr); const float value = (float)value_raw / 10; ExtUI::axis_t axis; @@ -483,7 +483,7 @@ void DGUSScreenHandler::HandleStepPerMMChanged(DGUS_VP_Variable &var, void *val_ skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel } -void DGUSScreenHandler::HandleStepPerMMExtruderChanged(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandler::handleStepPerMMExtruderChanged(DGUS_VP_Variable &var, void *val_ptr) { const uint16_t value_raw = BE16_P(val_ptr); const float value = (float)value_raw / 10; ExtUI::extruder_t extruder; @@ -501,7 +501,7 @@ void DGUSScreenHandler::HandleStepPerMMExtruderChanged(DGUS_VP_Variable &var, vo } #if HAS_PID_HEATING - void DGUSScreenHandler::HandlePIDAutotune(DGUS_VP_Variable &var, void *val_ptr) { + void DGUSScreenHandler::handlePIDAutotune(DGUS_VP_Variable &var, void *val_ptr) { char buf[32] = {0}; switch (var.VP) { @@ -528,14 +528,14 @@ void DGUSScreenHandler::HandleStepPerMMExtruderChanged(DGUS_VP_Variable &var, vo } #if ENABLED(DGUS_UI_WAITING) - sendinfoscreen(F("PID is autotuning"), F("please wait"), NUL_STR, NUL_STR, true, true, true, true); - GotoScreen(DGUSLCD_SCREEN_WAITING); + sendInfoScreen(F("PID is autotuning"), F("please wait"), NUL_STR, NUL_STR, true, true, true, true); + gotoScreen(DGUS_SCREEN_WAITING); #endif } #endif // HAS_PID_HEATING #if HAS_BED_PROBE - void DGUSScreenHandler::HandleProbeOffsetZChanged(DGUS_VP_Variable &var, void *val_ptr) { + void DGUSScreenHandler::handleProbeOffsetZChanged(DGUS_VP_Variable &var, void *val_ptr) { const float offset = float(int16_t(BE16_P(val_ptr))) / 100.0f; ExtUI::setZOffset_mm(offset); skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel @@ -544,12 +544,12 @@ void DGUSScreenHandler::HandleStepPerMMExtruderChanged(DGUS_VP_Variable &var, vo #endif #if HAS_FAN - void DGUSScreenHandler::HandleFanControl(DGUS_VP_Variable &var, void *val_ptr) { + void DGUSScreenHandler::handleFanControl(DGUS_VP_Variable &var, void *val_ptr) { *(uint8_t*)var.memadr = *(uint8_t*)var.memadr > 0 ? 0 : 255; } #endif -void DGUSScreenHandler::HandleHeaterControl(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandler::handleHeaterControl(DGUS_VP_Variable &var, void *val_ptr) { uint8_t preheat_temp = 0; switch (var.VP) { #if HAS_HOTEND @@ -576,7 +576,7 @@ void DGUSScreenHandler::HandleHeaterControl(DGUS_VP_Variable &var, void *val_ptr #if ENABLED(DGUS_PREHEAT_UI) - void DGUSScreenHandler::HandlePreheat(DGUS_VP_Variable &var, void *val_ptr) { + void DGUSScreenHandler::handlePreheat(DGUS_VP_Variable &var, void *val_ptr) { const uint16_t preheat_option = BE16_P(val_ptr); switch (preheat_option) { default: @@ -592,48 +592,48 @@ void DGUSScreenHandler::HandleHeaterControl(DGUS_VP_Variable &var, void *val_ptr } // Go to the preheat screen to show the heating progress - GotoScreen(DGUSLCD_SCREEN_PREHEAT); + gotoScreen(DGUS_SCREEN_PREHEAT); } #endif // DGUS_PREHEAT_UI #if ENABLED(POWER_LOSS_RECOVERY) - void DGUSScreenHandler::HandlePowerLossRecovery(DGUS_VP_Variable &var, void *val_ptr) { + void DGUSScreenHandler::handlePowerLossRecovery(DGUS_VP_Variable &var, void *val_ptr) { uint16_t value = BE16_P(val_ptr); if (value) { queue.inject(F("M1000")); - dgusdisplay.WriteVariable(VP_SD_Print_Filename, filelist.filename(), 32, true); - GotoScreen(PLR_SCREEN_RECOVER); + dgus.writeVariable(VP_SD_Print_Filename, filelist.filename(), 32, true); + gotoScreen(PLR_SCREEN_RECOVER); } else { recovery.cancel(); - GotoScreen(PLR_SCREEN_CANCEL); + gotoScreen(PLR_SCREEN_CANCEL); } } #endif -void DGUSScreenHandler::UpdateNewScreen(DGUSLCD_Screens newscreen, bool popup) { +void DGUSScreenHandler::updateNewScreen(const DGUS_ScreenID screenID, const bool popup) { if (!popup) { - memmove(&past_screens[1], &past_screens[0], sizeof(past_screens) - 1); - past_screens[0] = current_screen; + memmove(&past_screenIDs[1], &past_screenIDs[0], sizeof(past_screenIDs) - 1); + past_screenIDs[0] = current_screenID; } - current_screen = newscreen; + current_screenID = screenID; skipVP = 0; - ForceCompleteUpdate(); + forceCompleteUpdate(); } -void DGUSScreenHandler::PopToOldScreen() { - GotoScreen(past_screens[0], true); - memmove(&past_screens[0], &past_screens[1], sizeof(past_screens) - 1); - past_screens[sizeof(past_screens) - 1] = DGUSLCD_SCREEN_MAIN; +void DGUSScreenHandler::popToOldScreen() { + gotoScreen(past_screenIDs[0], true); + memmove(&past_screenIDs[0], &past_screenIDs[1], sizeof(past_screenIDs) - 1); + past_screenIDs[sizeof(past_screenIDs) - 1] = DGUS_SCREEN_MAIN; } -void DGUSScreenHandler::UpdateScreenVPData() { - const uint16_t *VPList = DGUSLCD_FindScreenVPMapList(current_screen); +void DGUSScreenHandler::updateScreenVPData() { + const uint16_t *VPList = findScreenVPMapList(current_screenID); if (!VPList) { - ScreenComplete = true; + screenComplete = true; return; // nothing to do, likely a bug or boring screen. } @@ -645,7 +645,7 @@ void DGUSScreenHandler::UpdateScreenVPData() { uint16_t VP = pgm_read_word(VPList); if (!VP) { update_ptr = 0; - ScreenComplete = true; + screenComplete = true; return; // Screen completed. } @@ -656,12 +656,12 @@ void DGUSScreenHandler::UpdateScreenVPData() { uint8_t expected_tx = 6 + rcpy.size; // expected overhead is 6 bytes + payload. // Send the VP to the display, but try to avoid overrunning the Tx Buffer. // But send at least one VP, to avoid getting stalled. - if (rcpy.send_to_display_handler && (!sent_one || expected_tx <= dgusdisplay.GetFreeTxBuffer())) { + if (rcpy.send_to_display_handler && (!sent_one || expected_tx <= dgus.getFreeTxBuffer())) { sent_one = true; rcpy.send_to_display_handler(rcpy); } else { - ScreenComplete = false; + screenComplete = false; return; // please call again! } } @@ -669,14 +669,14 @@ void DGUSScreenHandler::UpdateScreenVPData() { } while (++update_ptr, ++VPList, true); } -void DGUSScreenHandler::GotoScreen(DGUSLCD_Screens screen, bool ispopup) { - dgusdisplay.RequestScreen(screen); - UpdateNewScreen(screen, ispopup); +void DGUSScreenHandler::gotoScreen(const DGUS_ScreenID screenID, const bool popup/*=false*/) { + dgus.requestScreen(screenID); + updateNewScreen(screenID, popup); } -void DGUSDisplay::RequestScreen(DGUSLCD_Screens screen) { - const unsigned char gotoscreen[] = { 0x5A, 0x01, (unsigned char) (screen >> 8U), (unsigned char) (screen & 0xFFU) }; - WriteVariable(0x84, gotoscreen, sizeof(gotoscreen)); +void DGUSDisplay::requestScreen(const DGUS_ScreenID screenID) { + const unsigned char gotoscreen[] = { 0x5A, 0x01, (unsigned char) (screenID >> 8U), (unsigned char) (screenID & 0xFFU) }; + writeVariable(0x84, gotoscreen, sizeof(gotoscreen)); } #endif // HAS_DGUS_LCD_CLASSIC diff --git a/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.h index 4486105d3c4a..cb403dbdad76 100644 --- a/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.h +++ b/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.h @@ -56,7 +56,7 @@ #include "hiprecy/DGUSScreenHandler.h" #endif -extern DGUSScreenHandlerClass ScreenHandler; +extern DGUSScreenHandlerClass screen; // Helper to define a DGUS_VP_Variable for common use-cases. #define VPHELPER(VPADR, VPADRVAR, RXFPTR, TXFPTR) { \ diff --git a/Marlin/src/lcd/extui/dgus/DGUSScreenHandlerBase.h b/Marlin/src/lcd/extui/dgus/DGUSScreenHandlerBase.h index 9ebca87be1d9..c6dd270edf90 100644 --- a/Marlin/src/lcd/extui/dgus/DGUSScreenHandlerBase.h +++ b/Marlin/src/lcd/extui/dgus/DGUSScreenHandlerBase.h @@ -27,7 +27,7 @@ #include "../../../inc/MarlinConfig.h" -enum DGUSLCD_Screens : uint8_t; +enum DGUS_ScreenID : uint8_t; class DGUSScreenHandler { public: @@ -37,154 +37,154 @@ class DGUSScreenHandler { // Send all 4 strings that are displayed on the infoscreen, confirmation screen and kill screen // The bools specifying whether the strings are in RAM or FLASH. - static void sendinfoscreen(PGM_P const line1, PGM_P const line2, PGM_P const line3, PGM_P const line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); - static void sendinfoscreen(FSTR_P const line1, FSTR_P const line2, PGM_P const line3, PGM_P const line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash) { - sendinfoscreen(FTOP(line1), FTOP(line2), line3, line4, l1inflash, l2inflash, l3inflash, liinflash); + static void sendInfoScreen(PGM_P const line1, PGM_P const line2, PGM_P const line3, PGM_P const line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); + static void sendInfoScreen(FSTR_P const line1, FSTR_P const line2, PGM_P const line3, PGM_P const line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash) { + sendInfoScreen(FTOP(line1), FTOP(line2), line3, line4, l1inflash, l2inflash, l3inflash, liinflash); } - static void sendinfoscreen(FSTR_P const line1, FSTR_P const line2, FSTR_P const line3, FSTR_P const line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash) { - sendinfoscreen(FTOP(line1), FTOP(line2), FTOP(line3), FTOP(line4), l1inflash, l2inflash, l3inflash, liinflash); + static void sendInfoScreen(FSTR_P const line1, FSTR_P const line2, FSTR_P const line3, FSTR_P const line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash) { + sendInfoScreen(FTOP(line1), FTOP(line2), FTOP(line3), FTOP(line4), l1inflash, l2inflash, l3inflash, liinflash); } - static void HandleUserConfirmationPopUp(uint16_t ConfirmVP, PGM_P const line1, PGM_P const line2, PGM_P const line3, PGM_P const line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); + static void handleUserConfirmationPopUp(uint16_t confirmVP, PGM_P const line1, PGM_P const line2, PGM_P const line3, PGM_P const line4, bool l1inflash, bool l2inflash, bool l3inflash, bool liinflash); // "M117" Message -- msg is a RAM ptr. - static void setstatusmessage(const char *msg); + static void setStatusMessage(const char *msg); // The same for messages from Flash static void setstatusmessagePGM(PGM_P const msg); - static void setstatusmessage(FSTR_P const fmsg) { setstatusmessagePGM(FTOP(fmsg)); } + static void setStatusMessage(FSTR_P const fmsg) { setstatusmessagePGM(FTOP(fmsg)); } // Callback for VP "Display wants to change screen on idle printer" - static void ScreenChangeHookIfIdle(DGUS_VP_Variable &var, void *val_ptr); + static void screenChangeHookIfIdle(DGUS_VP_Variable &var, void *val_ptr); // Callback for VP "Screen has been changed" - static void ScreenChangeHook(DGUS_VP_Variable &var, void *val_ptr); + static void screenChangeHook(DGUS_VP_Variable &var, void *val_ptr); // Callback for VP "All Heaters Off" - static void HandleAllHeatersOff(DGUS_VP_Variable &var, void *val_ptr); + static void handleAllHeatersOff(DGUS_VP_Variable &var, void *val_ptr); // Hook for "Change this temperature" - static void HandleTemperatureChanged(DGUS_VP_Variable &var, void *val_ptr); + static void handleTemperatureChanged(DGUS_VP_Variable &var, void *val_ptr); // Hook for "Change Flowrate" - static void HandleFlowRateChanged(DGUS_VP_Variable &var, void *val_ptr); + static void handleFlowRateChanged(DGUS_VP_Variable &var, void *val_ptr); #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) // Hook for manual move option - static void HandleManualMoveOption(DGUS_VP_Variable &var, void *val_ptr); + static void handleManualMoveOption(DGUS_VP_Variable &var, void *val_ptr); #endif // Hook for manual move. - static void HandleManualMove(DGUS_VP_Variable &var, void *val_ptr); + static void handleManualMove(DGUS_VP_Variable &var, void *val_ptr); // Hook for manual extrude. - static void HandleManualExtrude(DGUS_VP_Variable &var, void *val_ptr); + static void handleManualExtrude(DGUS_VP_Variable &var, void *val_ptr); // Hook for motor lock and unlook - static void HandleMotorLockUnlock(DGUS_VP_Variable &var, void *val_ptr); + static void handleMotorLockUnlock(DGUS_VP_Variable &var, void *val_ptr); #if ENABLED(POWER_LOSS_RECOVERY) // Hook for power loss recovery. - static void HandlePowerLossRecovery(DGUS_VP_Variable &var, void *val_ptr); + static void handlePowerLossRecovery(DGUS_VP_Variable &var, void *val_ptr); #endif // Hook for settings - static void HandleSettings(DGUS_VP_Variable &var, void *val_ptr); - static void HandleStepPerMMChanged(DGUS_VP_Variable &var, void *val_ptr); - static void HandleStepPerMMExtruderChanged(DGUS_VP_Variable &var, void *val_ptr); + static void handleSettings(DGUS_VP_Variable &var, void *val_ptr); + static void handleStepPerMMChanged(DGUS_VP_Variable &var, void *val_ptr); + static void handleStepPerMMExtruderChanged(DGUS_VP_Variable &var, void *val_ptr); #if HAS_PID_HEATING // Hook for "Change this temperature PID para" - static void HandleTemperaturePIDChanged(DGUS_VP_Variable &var, void *val_ptr); + static void handleTemperaturePIDChanged(DGUS_VP_Variable &var, void *val_ptr); // Hook for PID autotune - static void HandlePIDAutotune(DGUS_VP_Variable &var, void *val_ptr); + static void handlePIDAutotune(DGUS_VP_Variable &var, void *val_ptr); #endif #if HAS_BED_PROBE // Hook for "Change probe offset z" - static void HandleProbeOffsetZChanged(DGUS_VP_Variable &var, void *val_ptr); + static void handleProbeOffsetZChanged(DGUS_VP_Variable &var, void *val_ptr); #endif #if ENABLED(BABYSTEPPING) // Hook for live z adjust action - static void HandleLiveAdjustZ(DGUS_VP_Variable &var, void *val_ptr); + static void handleLiveAdjustZ(DGUS_VP_Variable &var, void *val_ptr); #endif #if HAS_FAN // Hook for fan control - static void HandleFanControl(DGUS_VP_Variable &var, void *val_ptr); + static void handleFanControl(DGUS_VP_Variable &var, void *val_ptr); #endif // Hook for heater control - static void HandleHeaterControl(DGUS_VP_Variable &var, void *val_ptr); + static void handleHeaterControl(DGUS_VP_Variable &var, void *val_ptr); #if ENABLED(DGUS_PREHEAT_UI) // Hook for preheat - static void HandlePreheat(DGUS_VP_Variable &var, void *val_ptr); + static void handlePreheat(DGUS_VP_Variable &var, void *val_ptr); #endif #if ENABLED(DGUS_FILAMENT_LOADUNLOAD) // Hook for filament load and unload filament option - static void HandleFilamentOption(DGUS_VP_Variable &var, void *val_ptr); + static void handleFilamentOption(DGUS_VP_Variable &var, void *val_ptr); // Hook for filament load and unload - static void HandleFilamentLoadUnload(DGUS_VP_Variable &var); + static void handleFilamentLoadUnload(DGUS_VP_Variable &var); #endif #if HAS_MEDIA // Callback for VP "Display wants to change screen when there is a SD card" - static void ScreenChangeHookIfSD(DGUS_VP_Variable &var, void *val_ptr); + static void screenChangeHookIfSD(DGUS_VP_Variable &var, void *val_ptr); // Scroll buttons on the file listing screen. - static void DGUSLCD_SD_ScrollFilelist(DGUS_VP_Variable &var, void *val_ptr); + static void sdScrollFilelist(DGUS_VP_Variable &var, void *val_ptr); // File touched. - static void DGUSLCD_SD_FileSelected(DGUS_VP_Variable &var, void *val_ptr); + static void sdFileSelected(DGUS_VP_Variable &var, void *val_ptr); // start print after confirmation received. - static void DGUSLCD_SD_StartPrint(DGUS_VP_Variable &var, void *val_ptr); + static void sdStartPrint(DGUS_VP_Variable &var, void *val_ptr); // User hit the pause, resume or abort button. - static void DGUSLCD_SD_ResumePauseAbort(DGUS_VP_Variable &var, void *val_ptr); + static void sdResumePauseAbort(DGUS_VP_Variable &var, void *val_ptr); // User confirmed the abort action - static void DGUSLCD_SD_ReallyAbort(DGUS_VP_Variable &var, void *val_ptr); + static void sdReallyAbort(DGUS_VP_Variable &var, void *val_ptr); // User hit the tune button - static void DGUSLCD_SD_PrintTune(DGUS_VP_Variable &var, void *val_ptr); + static void sdPrintTune(DGUS_VP_Variable &var, void *val_ptr); // Send a single filename to the display. - static void DGUSLCD_SD_SendFilename(DGUS_VP_Variable &var); + static void sdSendFilename(DGUS_VP_Variable &var); // Marlin informed us that a new SD has been inserted. - static void SDCardInserted(); + static void sdCardInserted(); // Marlin informed us that the SD Card has been removed(). - static void SDCardRemoved(); + static void sdCardRemoved(); // Marlin informed us about a bad SD Card. - static void SDCardError(); + static void sdCardError(); #endif // OK Button on the Confirm screen. - static void ScreenConfirmedOK(DGUS_VP_Variable &var, void *val_ptr); + static void screenConfirmedOK(DGUS_VP_Variable &var, void *val_ptr); - // Update data after going to a new screen (by display or by GotoScreen) + // Update data after going to a new screen (by display or by gotoScreen) // remember to store the last-displayed screen so it can be restored. // (e.g., for popup messages) - static void UpdateNewScreen(DGUSLCD_Screens newscreen, bool popup=false); + static void updateNewScreen(const DGUS_ScreenID screenID, const bool popup=false); // Recall the remembered screen. - static void PopToOldScreen(); + static void popToOldScreen(); // Make the display show the screen and update all VPs in it. - static void GotoScreen(DGUSLCD_Screens screen, bool ispopup = false); + static void gotoScreen(const DGUS_ScreenID screenID, const bool popup=false); - static void UpdateScreenVPData(); + static void updateScreenVPData(); // Helpers to convert and transfer data to the display. - static void DGUSLCD_SendWordValueToDisplay(DGUS_VP_Variable &var); - static void DGUSLCD_SendStringToDisplay(DGUS_VP_Variable &var); - static void DGUSLCD_SendStringToDisplayPGM(DGUS_VP_Variable &var); - static void DGUSLCD_SendTemperaturePID(DGUS_VP_Variable &var); - static void DGUSLCD_SendPercentageToDisplay(DGUS_VP_Variable &var); - static void DGUSLCD_SendPrintProgressToDisplay(DGUS_VP_Variable &var); - static void DGUSLCD_SendPrintTimeToDisplay(DGUS_VP_Variable &var); + static void sendWordValueToDisplay(DGUS_VP_Variable &var); + static void sendStringToDisplay(DGUS_VP_Variable &var); + static void sendStringToDisplayPGM(DGUS_VP_Variable &var); + static void sendTemperaturePID(DGUS_VP_Variable &var); + static void sendPercentageToDisplay(DGUS_VP_Variable &var); + static void sendPrintProgressToDisplay(DGUS_VP_Variable &var); + static void sendPrintTimeToDisplay(DGUS_VP_Variable &var); #if ENABLED(PRINTCOUNTER) - static void DGUSLCD_SendPrintAccTimeToDisplay(DGUS_VP_Variable &var); - static void DGUSLCD_SendPrintsTotalToDisplay(DGUS_VP_Variable &var); + static void sendPrintAccTimeToDisplay(DGUS_VP_Variable &var); + static void sendPrintsTotalToDisplay(DGUS_VP_Variable &var); #endif #if HAS_FAN - static void DGUSLCD_SendFanStatusToDisplay(DGUS_VP_Variable &var); + static void sendFanStatusToDisplay(DGUS_VP_Variable &var); #endif - static void DGUSLCD_SendHeaterStatusToDisplay(DGUS_VP_Variable &var); + static void sendHeaterStatusToDisplay(DGUS_VP_Variable &var); #if ENABLED(DGUS_UI_WAITING) - static void DGUSLCD_SendWaitingStatusToDisplay(DGUS_VP_Variable &var); + static void sendWaitingStatusToDisplay(DGUS_VP_Variable &var); #endif // Send a value from 0..100 to a variable with a range from 0..255 - static void DGUSLCD_PercentageToUint8(DGUS_VP_Variable &var, void *val_ptr); + static void percentageToUint8(DGUS_VP_Variable &var, void *val_ptr); template - static void DGUSLCD_SetValueDirectly(DGUS_VP_Variable &var, void *val_ptr) { + static void setValueDirectly(DGUS_VP_Variable &var, void *val_ptr) { if (!var.memadr) return; union { unsigned char tmp[sizeof(T)]; T t; } x; unsigned char *ptr = (unsigned char*)val_ptr; - LOOP_L_N(i, sizeof(T)) x.tmp[i] = ptr[sizeof(T) - i - 1]; + for (uint8_t i = 0; i < sizeof(T); ++i) x.tmp[i] = ptr[sizeof(T) - i - 1]; *(T*)var.memadr = x.t; } @@ -192,11 +192,11 @@ class DGUSScreenHandler { // Display will get a 4-byte integer scaled to the number of digits: // Tell the display the number of digits and it cheats by displaying a dot between... template - static void DGUSLCD_SendFloatAsLongValueToDisplay(DGUS_VP_Variable &var) { + static void sendFloatAsLongValueToDisplay(DGUS_VP_Variable &var) { if (var.memadr) { float f = *(float *)var.memadr; f *= cpow(10, decimals); - dgusdisplay.WriteVariable(var.VP, (long)f); + dgus.writeVariable(var.VP, (long)f); } } @@ -204,34 +204,34 @@ class DGUSScreenHandler { // Display will get a 2-byte integer scaled to the number of digits: // Tell the display the number of digits and it cheats by displaying a dot between... template - static void DGUSLCD_SendFloatAsIntValueToDisplay(DGUS_VP_Variable &var) { + static void sendFloatAsIntValueToDisplay(DGUS_VP_Variable &var) { if (var.memadr) { float f = *(float *)var.memadr; DEBUG_ECHOLNPAIR_F(" >> ", f, 6); f *= cpow(10, decimals); - dgusdisplay.WriteVariable(var.VP, (int16_t)f); + dgus.writeVariable(var.VP, (int16_t)f); } } // Force an update of all VP on the current screen. - static void ForceCompleteUpdate() { update_ptr = 0; ScreenComplete = false; } + static void forceCompleteUpdate() { update_ptr = 0; screenComplete = false; } // Has all VPs sent to the screen - static bool IsScreenComplete() { return ScreenComplete; } + static bool isScreenComplete() { return screenComplete; } - static DGUSLCD_Screens getCurrentScreen() { return current_screen; } + static DGUS_ScreenID getCurrentScreen() { return current_screenID; } - static void SetupConfirmAction( void (*f)()) { confirm_action_cb = f; } + static void setupConfirmAction( void (*f)()) { confirm_action_cb = f; } protected: - static DGUSLCD_Screens current_screen; //< currently on screen + static DGUS_ScreenID current_screenID; //< currently on screen static constexpr uint8_t NUM_PAST_SCREENS = 4; - static DGUSLCD_Screens past_screens[NUM_PAST_SCREENS]; //< LIFO with past screens for the "back" button. + static DGUS_ScreenID past_screenIDs[NUM_PAST_SCREENS]; //< LIFO with past screens for the "back" button. static uint8_t update_ptr; //< Last sent entry in the VPList for the actual screen. static uint16_t skipVP; //< When updating the screen data, skip this one, because the user is interacting with it. - static bool ScreenComplete; //< All VPs sent to screen? + static bool screenComplete; //< All VPs sent to screen? - static uint16_t ConfirmVP; //< context for confirm screen (VP that will be emulated-sent on "OK"). + static uint16_t confirmVP; //< context for confirm screen (VP that will be emulated-sent on "OK"). #if HAS_MEDIA static int16_t top_file; //< file on top of file chooser diff --git a/Marlin/src/lcd/extui/dgus/dgus_extui.cpp b/Marlin/src/lcd/extui/dgus/dgus_extui.cpp index 1d86d8bd558f..30d1c710b213 100644 --- a/Marlin/src/lcd/extui/dgus/dgus_extui.cpp +++ b/Marlin/src/lcd/extui/dgus/dgus_extui.cpp @@ -36,21 +36,21 @@ namespace ExtUI { void onStartup() { - dgusdisplay.InitDisplay(); - ScreenHandler.UpdateScreenVPData(); + dgus.initDisplay(); + screen.updateScreenVPData(); } - void onIdle() { ScreenHandler.loop(); } + void onIdle() { screen.loop(); } void onPrinterKilled(FSTR_P const error, FSTR_P const) { - ScreenHandler.sendinfoscreen(GET_TEXT_F(MSG_HALTED), error, FPSTR(NUL_STR), GET_TEXT_F(MSG_PLEASE_RESET), true, true, true, true); - ScreenHandler.GotoScreen(DGUSLCD_SCREEN_KILL); - while (!ScreenHandler.loop()); // Wait while anything is left to be sent + screen.sendInfoScreen(GET_TEXT_F(MSG_HALTED), error, FPSTR(NUL_STR), GET_TEXT_F(MSG_PLEASE_RESET), true, true, true, true); + screen.gotoScreen(DGUS_SCREEN_KILL); + while (!screen.loop()); // Wait while anything is left to be sent } - void onMediaInserted() { TERN_(HAS_MEDIA, ScreenHandler.SDCardInserted()); } - void onMediaError() { TERN_(HAS_MEDIA, ScreenHandler.SDCardError()); } - void onMediaRemoved() { TERN_(HAS_MEDIA, ScreenHandler.SDCardRemoved()); } + void onMediaInserted() { TERN_(HAS_MEDIA, screen.sdCardInserted()); } + void onMediaError() { TERN_(HAS_MEDIA, screen.sdCardError()); } + void onMediaRemoved() { TERN_(HAS_MEDIA, screen.sdCardRemoved()); } void onPlayTone(const uint16_t frequency, const uint16_t duration) {} void onPrintTimerStarted() {} @@ -60,17 +60,17 @@ namespace ExtUI { void onUserConfirmRequired(const char * const msg) { if (msg) { - ScreenHandler.sendinfoscreen(F("Please confirm."), nullptr, msg, nullptr, true, true, false, true); - ScreenHandler.SetupConfirmAction(setUserConfirmed); - ScreenHandler.GotoScreen(DGUSLCD_SCREEN_POPUP); + screen.sendInfoScreen(F("Please confirm."), nullptr, msg, nullptr, true, true, false, true); + screen.setupConfirmAction(setUserConfirmed); + screen.gotoScreen(DGUS_SCREEN_POPUP); } - else if (ScreenHandler.getCurrentScreen() == DGUSLCD_SCREEN_POPUP) { - ScreenHandler.SetupConfirmAction(nullptr); - ScreenHandler.PopToOldScreen(); + else if (screen.getCurrentScreen() == DGUS_SCREEN_POPUP) { + screen.setupConfirmAction(nullptr); + screen.popToOldScreen(); } } - void onStatusChanged(const char * const msg) { ScreenHandler.setstatusmessage(msg); } + void onStatusChanged(const char * const msg) { screen.setStatusMessage(msg); } void onHomingStart() {} void onHomingDone() {} @@ -112,10 +112,12 @@ namespace ExtUI { // whether successful or not. } - #if HAS_MESH + #if HAS_LEVELING void onLevelingStart() {} void onLevelingDone() {} + #endif + #if HAS_MESH void onMeshUpdate(const int8_t xpos, const int8_t ypos, const_float_t zval) { // Called when any mesh points are updated } @@ -134,7 +136,7 @@ namespace ExtUI { } void onPowerLossResume() { // Called on resume from power-loss - IF_DISABLED(DGUS_LCD_UI_MKS, ScreenHandler.GotoScreen(DGUSLCD_SCREEN_POWER_LOSS)); + IF_DISABLED(DGUS_LCD_UI_MKS, screen.gotoScreen(DGUS_SCREEN_POWER_LOSS)); } #endif @@ -143,22 +145,22 @@ namespace ExtUI { // Called for temperature PID tuning result switch (rst) { case PID_STARTED: - ScreenHandler.setstatusmessage(GET_TEXT_F(MSG_PID_AUTOTUNE)); + screen.setStatusMessage(GET_TEXT_F(MSG_PID_AUTOTUNE)); break; case PID_BAD_HEATER_ID: - ScreenHandler.setstatusmessage(GET_TEXT_F(MSG_PID_BAD_HEATER_ID)); + screen.setStatusMessage(GET_TEXT_F(MSG_PID_BAD_HEATER_ID)); break; case PID_TEMP_TOO_HIGH: - ScreenHandler.setstatusmessage(GET_TEXT_F(MSG_PID_TEMP_TOO_HIGH)); + screen.setStatusMessage(GET_TEXT_F(MSG_PID_TEMP_TOO_HIGH)); break; case PID_TUNING_TIMEOUT: - ScreenHandler.setstatusmessage(GET_TEXT_F(MSG_PID_TIMEOUT)); + screen.setStatusMessage(GET_TEXT_F(MSG_PID_TIMEOUT)); break; case PID_DONE: - ScreenHandler.setstatusmessage(GET_TEXT_F(MSG_PID_AUTOTUNE_DONE)); + screen.setStatusMessage(GET_TEXT_F(MSG_PID_AUTOTUNE_DONE)); break; } - ScreenHandler.GotoScreen(DGUSLCD_SCREEN_MAIN); + screen.gotoScreen(DGUS_SCREEN_MAIN); } #endif diff --git a/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.cpp index 6b670368b656..08d5387ceff3 100644 --- a/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.cpp +++ b/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.cpp @@ -289,28 +289,28 @@ const uint16_t VPList_Z_Offset[] PROGMEM = { }; const struct VPMapping VPMap[] PROGMEM = { - { DGUSLCD_SCREEN_BOOT, VPList_Boot }, - { DGUSLCD_SCREEN_MAIN, VPList_Main }, - { DGUSLCD_SCREEN_TEMPERATURE, VPList_Temp }, - { DGUSLCD_SCREEN_STATUS, VPList_Status }, - { DGUSLCD_SCREEN_STATUS2, VPList_Status2 }, - { DGUSLCD_SCREEN_PREHEAT, VPList_Preheat }, - { DGUSLCD_SCREEN_MANUALMOVE, VPList_ManualMove }, - { DGUSLCD_SCREEN_MANUALEXTRUDE, VPList_ManualExtrude }, - { DGUSLCD_SCREEN_FILAMENT_HEATING, VPList_Filament_heating }, - { DGUSLCD_SCREEN_FILAMENT_LOADING, VPList_Filament_load_unload }, - { DGUSLCD_SCREEN_FILAMENT_UNLOADING, VPList_Filament_load_unload }, - { DGUSLCD_SCREEN_SDPRINTMANIPULATION, VPList_SD_PrintManipulation }, - { DGUSLCD_SCREEN_SDFILELIST, VPList_SDFileList }, - { DGUSLCD_SCREEN_SDPRINTTUNE, VPList_SDPrintTune }, - { DGUSLCD_SCREEN_WAITING, VPList_PIDTuningWaiting }, - { DGUSLCD_SCREEN_FLC_PREHEAT, VPList_FLCPreheat }, - { DGUSLCD_SCREEN_FLC_PRINTING, VPList_FLCPrinting }, - { DGUSLCD_SCREEN_Z_OFFSET, VPList_Z_Offset }, - { DGUSLCD_SCREEN_STEPPERMM, VPList_StepPerMM }, - { DGUSLCD_SCREEN_PID_E, VPList_PIDE0 }, - { DGUSLCD_SCREEN_PID_BED, VPList_PIDBED }, - { DGUSLCD_SCREEN_INFOS, VPList_Infos }, + { DGUS_SCREEN_BOOT, VPList_Boot }, + { DGUS_SCREEN_MAIN, VPList_Main }, + { DGUS_SCREEN_TEMPERATURE, VPList_Temp }, + { DGUS_SCREEN_STATUS, VPList_Status }, + { DGUS_SCREEN_STATUS2, VPList_Status2 }, + { DGUS_SCREEN_PREHEAT, VPList_Preheat }, + { DGUS_SCREEN_MANUALMOVE, VPList_ManualMove }, + { DGUS_SCREEN_MANUALEXTRUDE, VPList_ManualExtrude }, + { DGUS_SCREEN_FILAMENT_HEATING, VPList_Filament_heating }, + { DGUS_SCREEN_FILAMENT_LOADING, VPList_Filament_load_unload }, + { DGUS_SCREEN_FILAMENT_UNLOADING, VPList_Filament_load_unload }, + { DGUS_SCREEN_SDPRINTMANIPULATION, VPList_SD_PrintManipulation }, + { DGUS_SCREEN_SDFILELIST, VPList_SDFileList }, + { DGUS_SCREEN_SDPRINTTUNE, VPList_SDPrintTune }, + { DGUS_SCREEN_WAITING, VPList_PIDTuningWaiting }, + { DGUS_SCREEN_FLC_PREHEAT, VPList_FLCPreheat }, + { DGUS_SCREEN_FLC_PRINTING, VPList_FLCPrinting }, + { DGUS_SCREEN_Z_OFFSET, VPList_Z_Offset }, + { DGUS_SCREEN_STEPPERMM, VPList_StepPerMM }, + { DGUS_SCREEN_PID_E, VPList_PIDE0 }, + { DGUS_SCREEN_PID_BED, VPList_PIDBED }, + { DGUS_SCREEN_INFOS, VPList_Infos }, { 0 , nullptr } // List is terminated with an nullptr as table entry. }; @@ -318,159 +318,159 @@ const char MarlinVersion[] PROGMEM = SHORT_BUILD_VERSION; const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { // Helper to detect touch events - VPHELPER(VP_SCREENCHANGE, nullptr, ScreenHandler.ScreenChangeHook, nullptr), - VPHELPER(VP_SCREENCHANGE_ASK, nullptr, ScreenHandler.ScreenChangeHookIfIdle, nullptr), + VPHELPER(VP_SCREENCHANGE, nullptr, screen.screenChangeHook, nullptr), + VPHELPER(VP_SCREENCHANGE_ASK, nullptr, screen.screenChangeHookIfIdle, nullptr), #if HAS_MEDIA - VPHELPER(VP_SCREENCHANGE_WHENSD, nullptr, ScreenHandler.ScreenChangeHookIfSD, nullptr), + VPHELPER(VP_SCREENCHANGE_WHENSD, nullptr, screen.screenChangeHookIfSD, nullptr), #endif - VPHELPER(VP_CONFIRMED, nullptr, ScreenHandler.ScreenConfirmedOK, nullptr), + VPHELPER(VP_CONFIRMED, nullptr, screen.screenConfirmedOK, nullptr), - VPHELPER(VP_TEMP_ALL_OFF, nullptr, ScreenHandler.HandleAllHeatersOff, nullptr), + VPHELPER(VP_TEMP_ALL_OFF, nullptr, screen.handleAllHeatersOff, nullptr), #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) - VPHELPER(VP_MOVE_OPTION, &distanceToMove, ScreenHandler.HandleManualMoveOption, nullptr), + VPHELPER(VP_MOVE_OPTION, &distanceToMove, screen.handleManualMoveOption, nullptr), #endif #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) - VPHELPER(VP_MOVE_X, &distanceToMove, ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Y, &distanceToMove, ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Z, &distanceToMove, ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_HOME_ALL, &distanceToMove, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_X, &distanceToMove, screen.handleManualMove, nullptr), + VPHELPER(VP_MOVE_Y, &distanceToMove, screen.handleManualMove, nullptr), + VPHELPER(VP_MOVE_Z, &distanceToMove, screen.handleManualMove, nullptr), + VPHELPER(VP_HOME_ALL, &distanceToMove, screen.handleManualMove, nullptr), #else - VPHELPER(VP_MOVE_X, nullptr, ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Y, nullptr, ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Z, nullptr, ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_HOME_ALL, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_X, nullptr, screen.handleManualMove, nullptr), + VPHELPER(VP_MOVE_Y, nullptr, screen.handleManualMove, nullptr), + VPHELPER(VP_MOVE_Z, nullptr, screen.handleManualMove, nullptr), + VPHELPER(VP_HOME_ALL, nullptr, screen.handleManualMove, nullptr), #endif - VPHELPER(VP_MOTOR_LOCK_UNLOK, nullptr, ScreenHandler.HandleMotorLockUnlock, nullptr), + VPHELPER(VP_MOTOR_LOCK_UNLOK, nullptr, screen.handleMotorLockUnlock, nullptr), #if ENABLED(POWER_LOSS_RECOVERY) - VPHELPER(VP_POWER_LOSS_RECOVERY, nullptr, ScreenHandler.HandlePowerLossRecovery, nullptr), + VPHELPER(VP_POWER_LOSS_RECOVERY, nullptr, screen.handlePowerLossRecovery, nullptr), #endif - VPHELPER(VP_SETTINGS, nullptr, ScreenHandler.HandleSettings, nullptr), + VPHELPER(VP_SETTINGS, nullptr, screen.handleSettings, nullptr), #if ENABLED(SINGLE_Z_CALIBRATION) - VPHELPER(VP_Z_CALIBRATE, nullptr, ScreenHandler.HandleZCalibration, nullptr), + VPHELPER(VP_Z_CALIBRATE, nullptr, screen.handleZCalibration, nullptr), #endif #if ENABLED(FIRST_LAYER_CAL) - VPHELPER(VP_Z_FIRST_LAYER_CAL, nullptr, ScreenHandler.HandleFirstLayerCal, nullptr), + VPHELPER(VP_Z_FIRST_LAYER_CAL, nullptr, screen.handleFirstLayerCal, nullptr), #endif - { .VP = VP_MARLIN_VERSION, .memadr = (void*)MarlinVersion, .size = VP_MARLIN_VERSION_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + { .VP = VP_MARLIN_VERSION, .memadr = (void*)MarlinVersion, .size = VP_MARLIN_VERSION_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = screen.sendStringToDisplayPGM }, // M117 LCD String (We don't need the string in memory but "just" push it to the display on demand, hence the nullptr - { .VP = VP_M117, .memadr = nullptr, .size = VP_M117_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplay }, + { .VP = VP_M117, .memadr = nullptr, .size = VP_M117_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = screen.sendStringToDisplay }, // Temperature Data #if HAS_HOTEND - VPHELPER(VP_T_E0_Is, &thermalManager.temp_hotend[0].celsius, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<0>), - VPHELPER(VP_T_E0_Set, &thermalManager.temp_hotend[0].target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_Flowrate_E0, &planner.flow_percentage[ExtUI::extruder_t::E0], ScreenHandler.HandleFlowRateChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_EPos, &destination.e, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), - VPHELPER(VP_MOVE_E0, nullptr, ScreenHandler.HandleManualExtrude, nullptr), - VPHELPER(VP_E0_CONTROL, &thermalManager.temp_hotend[0].target, ScreenHandler.HandleHeaterControl, nullptr), - VPHELPER(VP_E0_STATUS, &thermalManager.temp_hotend[0].target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), + VPHELPER(VP_T_E0_Is, &thermalManager.temp_hotend[0].celsius, nullptr, screen.sendFloatAsLongValueToDisplay<0>), + VPHELPER(VP_T_E0_Set, &thermalManager.temp_hotend[0].target, screen.handleTemperatureChanged, screen.sendWordValueToDisplay), + VPHELPER(VP_Flowrate_E0, &planner.flow_percentage[ExtUI::extruder_t::E0], screen.handleFlowRateChanged, screen.sendWordValueToDisplay), + VPHELPER(VP_EPos, &destination.e, nullptr, screen.sendFloatAsLongValueToDisplay<2>), + VPHELPER(VP_MOVE_E0, nullptr, screen.handleManualExtrude, nullptr), + VPHELPER(VP_E0_CONTROL, &thermalManager.temp_hotend[0].target, screen.handleHeaterControl, nullptr), + VPHELPER(VP_E0_STATUS, &thermalManager.temp_hotend[0].target, nullptr, screen.sendHeaterStatusToDisplay), #if ENABLED(DGUS_PREHEAT_UI) - VPHELPER(VP_E0_BED_PREHEAT, nullptr, ScreenHandler.HandlePreheat, nullptr), + VPHELPER(VP_E0_BED_PREHEAT, nullptr, screen.handlePreheat, nullptr), #endif #if ENABLED(PIDTEMP) - VPHELPER(VP_E0_PID_P, &thermalManager.temp_hotend[0].pid.Kp, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_E0_PID_I, &thermalManager.temp_hotend[0].pid.Ki, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_E0_PID_D, &thermalManager.temp_hotend[0].pid.Kd, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_PID_AUTOTUNE_E0, nullptr, ScreenHandler.HandlePIDAutotune, nullptr), + VPHELPER(VP_E0_PID_P, &thermalManager.temp_hotend[0].pid.Kp, screen.handleTemperaturePIDChanged, screen.sendTemperaturePID), + VPHELPER(VP_E0_PID_I, &thermalManager.temp_hotend[0].pid.Ki, screen.handleTemperaturePIDChanged, screen.sendTemperaturePID), + VPHELPER(VP_E0_PID_D, &thermalManager.temp_hotend[0].pid.Kd, screen.handleTemperaturePIDChanged, screen.sendTemperaturePID), + VPHELPER(VP_PID_AUTOTUNE_E0, nullptr, screen.handlePIDAutotune, nullptr), #endif #if ENABLED(DGUS_FILAMENT_LOADUNLOAD) - VPHELPER(VP_E0_FILAMENT_LOAD_UNLOAD, nullptr, ScreenHandler.HandleFilamentOption, ScreenHandler.HandleFilamentLoadUnload), + VPHELPER(VP_E0_FILAMENT_LOAD_UNLOAD, nullptr, screen.handleFilamentOption, screen.handleFilamentLoadUnload), #endif #endif #if HAS_MULTI_HOTEND - VPHELPER(VP_T_E1_Is, &thermalManager.temp_hotend[1].celsius, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<0>), - VPHELPER(VP_T_E1_Set, &thermalManager.temp_hotend[1].target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_Flowrate_E1, &planner.flow_percentage[ExtUI::extruder_t::E1], ScreenHandler.HandleFlowRateChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), // ERROR: Flow is per-extruder, not per-hotend - VPHELPER(VP_MOVE_E1, nullptr, ScreenHandler.HandleManualExtrude, nullptr), - VPHELPER(VP_E1_CONTROL, &thermalManager.temp_hotend[1].target, ScreenHandler.HandleHeaterControl, nullptr), - VPHELPER(VP_E1_STATUS, &thermalManager.temp_hotend[1].target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), + VPHELPER(VP_T_E1_Is, &thermalManager.temp_hotend[1].celsius, nullptr, screen.sendFloatAsLongValueToDisplay<0>), + VPHELPER(VP_T_E1_Set, &thermalManager.temp_hotend[1].target, screen.handleTemperatureChanged, screen.sendWordValueToDisplay), + VPHELPER(VP_Flowrate_E1, &planner.flow_percentage[ExtUI::extruder_t::E1], screen.handleFlowRateChanged, screen.sendWordValueToDisplay), // ERROR: Flow is per-extruder, not per-hotend + VPHELPER(VP_MOVE_E1, nullptr, screen.handleManualExtrude, nullptr), + VPHELPER(VP_E1_CONTROL, &thermalManager.temp_hotend[1].target, screen.handleHeaterControl, nullptr), + VPHELPER(VP_E1_STATUS, &thermalManager.temp_hotend[1].target, nullptr, screen.sendHeaterStatusToDisplay), #if ENABLED(PIDTEMP) - VPHELPER(VP_PID_AUTOTUNE_E1, nullptr, ScreenHandler.HandlePIDAutotune, nullptr), + VPHELPER(VP_PID_AUTOTUNE_E1, nullptr, screen.handlePIDAutotune, nullptr), #endif - VPHELPER(VP_E1_FILAMENT_LOAD_UNLOAD, nullptr, ScreenHandler.HandleFilamentOption, ScreenHandler.HandleFilamentLoadUnload), + VPHELPER(VP_E1_FILAMENT_LOAD_UNLOAD, nullptr, screen.handleFilamentOption, screen.handleFilamentLoadUnload), #endif #if HAS_HEATED_BED - VPHELPER(VP_T_Bed_Is, &thermalManager.temp_bed.celsius, nullptr, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_T_Bed_Set, &thermalManager.temp_bed.target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_BED_CONTROL, &thermalManager.temp_bed.target, ScreenHandler.HandleHeaterControl, nullptr), - VPHELPER(VP_BED_STATUS, &thermalManager.temp_bed.target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), + VPHELPER(VP_T_Bed_Is, &thermalManager.temp_bed.celsius, nullptr, screen.sendWordValueToDisplay), + VPHELPER(VP_T_Bed_Set, &thermalManager.temp_bed.target, screen.handleTemperatureChanged, screen.sendWordValueToDisplay), + VPHELPER(VP_BED_CONTROL, &thermalManager.temp_bed.target, screen.handleHeaterControl, nullptr), + VPHELPER(VP_BED_STATUS, &thermalManager.temp_bed.target, nullptr, screen.sendHeaterStatusToDisplay), #if ENABLED(PIDTEMPBED) - VPHELPER(VP_BED_PID_P, &thermalManager.temp_bed.pid.Kp, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_BED_PID_I, &thermalManager.temp_bed.pid.Ki, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_BED_PID_D, &thermalManager.temp_bed.pid.Kd, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_PID_AUTOTUNE_BED, nullptr, ScreenHandler.HandlePIDAutotune, nullptr), + VPHELPER(VP_BED_PID_P, &thermalManager.temp_bed.pid.Kp, screen.handleTemperaturePIDChanged, screen.sendTemperaturePID), + VPHELPER(VP_BED_PID_I, &thermalManager.temp_bed.pid.Ki, screen.handleTemperaturePIDChanged, screen.sendTemperaturePID), + VPHELPER(VP_BED_PID_D, &thermalManager.temp_bed.pid.Kd, screen.handleTemperaturePIDChanged, screen.sendTemperaturePID), + VPHELPER(VP_PID_AUTOTUNE_BED, nullptr, screen.handlePIDAutotune, nullptr), #endif #endif // Fan Data #if HAS_FAN #define FAN_VPHELPER(N) \ - VPHELPER(VP_Fan##N##_Percentage, &thermalManager.fan_speed[N], ScreenHandler.DGUSLCD_PercentageToUint8, ScreenHandler.DGUSLCD_SendPercentageToDisplay), \ - VPHELPER(VP_FAN##N##_CONTROL, &thermalManager.fan_speed[N], ScreenHandler.HandleFanControl, nullptr), \ - VPHELPER(VP_FAN##N##_STATUS, &thermalManager.fan_speed[N], nullptr, ScreenHandler.DGUSLCD_SendFanStatusToDisplay), + VPHELPER(VP_Fan##N##_Percentage, &thermalManager.fan_speed[N], screen.percentageToUint8, screen.sendPercentageToDisplay), \ + VPHELPER(VP_FAN##N##_CONTROL, &thermalManager.fan_speed[N], screen.handleFanControl, nullptr), \ + VPHELPER(VP_FAN##N##_STATUS, &thermalManager.fan_speed[N], nullptr, screen.sendFanStatusToDisplay), REPEAT(FAN_COUNT, FAN_VPHELPER) #endif // Feedrate - VPHELPER(VP_Feedrate_Percentage, &feedrate_percentage, ScreenHandler.DGUSLCD_SetValueDirectly, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Feedrate_Percentage, &feedrate_percentage, screen.setValueDirectly, screen.sendWordValueToDisplay), // Position Data - VPHELPER(VP_XPos, ¤t_position.x, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), - VPHELPER(VP_YPos, ¤t_position.y, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), - VPHELPER(VP_ZPos, ¤t_position.z, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), + VPHELPER(VP_XPos, ¤t_position.x, nullptr, screen.sendFloatAsLongValueToDisplay<2>), + VPHELPER(VP_YPos, ¤t_position.y, nullptr, screen.sendFloatAsLongValueToDisplay<2>), + VPHELPER(VP_ZPos, ¤t_position.z, nullptr, screen.sendFloatAsLongValueToDisplay<2>), // Print Progress - VPHELPER(VP_PrintProgress_Percentage, nullptr, nullptr, ScreenHandler.DGUSLCD_SendPrintProgressToDisplay), + VPHELPER(VP_PrintProgress_Percentage, nullptr, nullptr, screen.sendPrintProgressToDisplay), // Print Time - VPHELPER_STR(VP_PrintTime, nullptr, VP_PrintTime_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintTimeToDisplay), + VPHELPER_STR(VP_PrintTime, nullptr, VP_PrintTime_LEN, nullptr, screen.sendPrintTimeToDisplay), #if ENABLED(PRINTCOUNTER) - VPHELPER_STR(VP_PrintAccTime, nullptr, VP_PrintAccTime_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintAccTimeToDisplay), - VPHELPER_STR(VP_PrintsTotal, nullptr, VP_PrintsTotal_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintsTotalToDisplay), + VPHELPER_STR(VP_PrintAccTime, nullptr, VP_PrintAccTime_LEN, nullptr, screen.sendPrintAccTimeToDisplay), + VPHELPER_STR(VP_PrintsTotal, nullptr, VP_PrintsTotal_LEN, nullptr, screen.sendPrintsTotalToDisplay), #endif - VPHELPER(VP_X_STEP_PER_MM, &planner.settings.axis_steps_per_mm[X_AXIS], ScreenHandler.HandleStepPerMMChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), - VPHELPER(VP_Y_STEP_PER_MM, &planner.settings.axis_steps_per_mm[Y_AXIS], ScreenHandler.HandleStepPerMMChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), - VPHELPER(VP_Z_STEP_PER_MM, &planner.settings.axis_steps_per_mm[Z_AXIS], ScreenHandler.HandleStepPerMMChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), + VPHELPER(VP_X_STEP_PER_MM, &planner.settings.axis_steps_per_mm[X_AXIS], screen.handleStepPerMMChanged, screen.sendFloatAsIntValueToDisplay<1>), + VPHELPER(VP_Y_STEP_PER_MM, &planner.settings.axis_steps_per_mm[Y_AXIS], screen.handleStepPerMMChanged, screen.sendFloatAsIntValueToDisplay<1>), + VPHELPER(VP_Z_STEP_PER_MM, &planner.settings.axis_steps_per_mm[Z_AXIS], screen.handleStepPerMMChanged, screen.sendFloatAsIntValueToDisplay<1>), #if HAS_EXTRUDERS - VPHELPER(VP_E0_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(0)], ScreenHandler.HandleStepPerMMExtruderChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), + VPHELPER(VP_E0_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(0)], screen.handleStepPerMMExtruderChanged, screen.sendFloatAsIntValueToDisplay<1>), #if HAS_MULTI_EXTRUDER - VPHELPER(VP_E1_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(1)], ScreenHandler.HandleStepPerMMExtruderChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), + VPHELPER(VP_E1_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(1)], screen.handleStepPerMMExtruderChanged, screen.sendFloatAsIntValueToDisplay<1>), #endif #endif // SDCard File listing. #if HAS_MEDIA - VPHELPER(VP_SD_ScrollEvent, nullptr, ScreenHandler.DGUSLCD_SD_ScrollFilelist, nullptr), - VPHELPER(VP_SD_FileSelected, nullptr, ScreenHandler.DGUSLCD_SD_FileSelected, nullptr), - VPHELPER(VP_SD_FileSelectConfirm, nullptr, ScreenHandler.DGUSLCD_SD_StartPrint, nullptr), - VPHELPER_STR(VP_SD_FileName0, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), - VPHELPER_STR(VP_SD_FileName1, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), - VPHELPER_STR(VP_SD_FileName2, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), - VPHELPER_STR(VP_SD_FileName3, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), - VPHELPER_STR(VP_SD_FileName4, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), - VPHELPER(VP_SD_ResumePauseAbort, nullptr, ScreenHandler.DGUSLCD_SD_ResumePauseAbort, nullptr), - VPHELPER(VP_SD_AbortPrintConfirmed, nullptr, ScreenHandler.DGUSLCD_SD_ReallyAbort, nullptr), - VPHELPER(VP_SD_Print_Setting, nullptr, ScreenHandler.DGUSLCD_SD_PrintTune, nullptr), + VPHELPER(VP_SD_ScrollEvent, nullptr, screen.sdScrollFilelist, nullptr), + VPHELPER(VP_SD_FileSelected, nullptr, screen.sdFileSelected, nullptr), + VPHELPER(VP_SD_FileSelectConfirm, nullptr, screen.sdStartPrint, nullptr), + VPHELPER_STR(VP_SD_FileName0, nullptr, VP_SD_FileName_LEN, nullptr, screen.sdSendFilename), + VPHELPER_STR(VP_SD_FileName1, nullptr, VP_SD_FileName_LEN, nullptr, screen.sdSendFilename), + VPHELPER_STR(VP_SD_FileName2, nullptr, VP_SD_FileName_LEN, nullptr, screen.sdSendFilename), + VPHELPER_STR(VP_SD_FileName3, nullptr, VP_SD_FileName_LEN, nullptr, screen.sdSendFilename), + VPHELPER_STR(VP_SD_FileName4, nullptr, VP_SD_FileName_LEN, nullptr, screen.sdSendFilename), + VPHELPER(VP_SD_ResumePauseAbort, nullptr, screen.sdResumePauseAbort, nullptr), + VPHELPER(VP_SD_AbortPrintConfirmed, nullptr, screen.sdReallyAbort, nullptr), + VPHELPER(VP_SD_Print_Setting, nullptr, screen.sdPrintTune, nullptr), #if HAS_BED_PROBE - VPHELPER(VP_SD_Print_ProbeOffsetZ, &probe.offset.z, ScreenHandler.HandleProbeOffsetZChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<2>), + VPHELPER(VP_SD_Print_ProbeOffsetZ, &probe.offset.z, screen.handleProbeOffsetZChanged, screen.sendFloatAsIntValueToDisplay<2>), #if ENABLED(BABYSTEPPING) - VPHELPER(VP_SD_Print_LiveAdjustZ, nullptr, ScreenHandler.HandleLiveAdjustZ, nullptr), + VPHELPER(VP_SD_Print_LiveAdjustZ, nullptr, screen.handleLiveAdjustZ, nullptr), #endif #endif #endif #if ENABLED(DGUS_UI_WAITING) - VPHELPER(VP_WAITING_STATUS, nullptr, nullptr, ScreenHandler.DGUSLCD_SendWaitingStatusToDisplay), + VPHELPER(VP_WAITING_STATUS, nullptr, nullptr, screen.sendWaitingStatusToDisplay), #endif // Messages for the User, shared by the popup and the kill screen. They can't be autouploaded as we do not buffer content. - { .VP = VP_MSGSTR1, .memadr = nullptr, .size = VP_MSGSTR1_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, - { .VP = VP_MSGSTR2, .memadr = nullptr, .size = VP_MSGSTR2_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, - { .VP = VP_MSGSTR3, .memadr = nullptr, .size = VP_MSGSTR3_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, - { .VP = VP_MSGSTR4, .memadr = nullptr, .size = VP_MSGSTR4_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + { .VP = VP_MSGSTR1, .memadr = nullptr, .size = VP_MSGSTR1_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = screen.sendStringToDisplayPGM }, + { .VP = VP_MSGSTR2, .memadr = nullptr, .size = VP_MSGSTR2_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = screen.sendStringToDisplayPGM }, + { .VP = VP_MSGSTR3, .memadr = nullptr, .size = VP_MSGSTR3_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = screen.sendStringToDisplayPGM }, + { .VP = VP_MSGSTR4, .memadr = nullptr, .size = VP_MSGSTR4_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = screen.sendStringToDisplayPGM }, VPHELPER(0, 0, 0, 0) // must be last entry. }; diff --git a/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.h b/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.h index 5deedc045079..70559f903196 100644 --- a/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.h +++ b/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.h @@ -23,35 +23,35 @@ #include "../DGUSDisplayDef.h" -enum DGUSLCD_Screens : uint8_t { - DGUSLCD_SCREEN_BOOT = 0, - DGUSLCD_SCREEN_MAIN = 1, - DGUSLCD_SCREEN_STATUS = 1, - DGUSLCD_SCREEN_STATUS2 = 1, - DGUSLCD_SCREEN_TEMPERATURE = 10, - DGUSLCD_SCREEN_PREHEAT = 18, - DGUSLCD_SCREEN_POWER_LOSS = 100, - DGUSLCD_SCREEN_MANUALMOVE = 192, - DGUSLCD_SCREEN_UTILITY = 120, - DGUSLCD_SCREEN_FILAMENT_HEATING = 146, - DGUSLCD_SCREEN_FILAMENT_LOADING = 148, - DGUSLCD_SCREEN_FILAMENT_UNLOADING = 158, - DGUSLCD_SCREEN_MANUALEXTRUDE = 160, - DGUSLCD_SCREEN_SDFILELIST = 71, - DGUSLCD_SCREEN_SDPRINTMANIPULATION = 73, - DGUSLCD_SCREEN_SDPRINTTUNE = 75, - DGUSLCD_SCREEN_FLC_PREHEAT = 94, - DGUSLCD_SCREEN_FLC_PRINTING = 96, - DGUSLCD_SCREEN_STEPPERMM = 212, - DGUSLCD_SCREEN_PID_E = 214, - DGUSLCD_SCREEN_PID_BED = 218, - DGUSLCD_SCREEN_Z_OFFSET = 222, - DGUSLCD_SCREEN_INFOS = 36, - DGUSLCD_SCREEN_CONFIRM = 240, - DGUSLCD_SCREEN_KILL = 250, ///< Kill Screen. Must always be 250 (to be able to display "Error wrong LCD Version") - DGUSLCD_SCREEN_WAITING = 251, - DGUSLCD_SCREEN_POPUP = 252, ///< special target, popup screen will also return this code to say "return to previous screen" - DGUSLCD_SCREEN_UNUSED = 255 +enum DGUS_ScreenID : uint8_t { + DGUS_SCREEN_BOOT = 0, + DGUS_SCREEN_MAIN = 1, + DGUS_SCREEN_STATUS = 1, + DGUS_SCREEN_STATUS2 = 1, + DGUS_SCREEN_TEMPERATURE = 10, + DGUS_SCREEN_PREHEAT = 18, + DGUS_SCREEN_POWER_LOSS = 100, + DGUS_SCREEN_MANUALMOVE = 192, + DGUS_SCREEN_UTILITY = 120, + DGUS_SCREEN_FILAMENT_HEATING = 146, + DGUS_SCREEN_FILAMENT_LOADING = 148, + DGUS_SCREEN_FILAMENT_UNLOADING = 158, + DGUS_SCREEN_MANUALEXTRUDE = 160, + DGUS_SCREEN_SDFILELIST = 71, + DGUS_SCREEN_SDPRINTMANIPULATION = 73, + DGUS_SCREEN_SDPRINTTUNE = 75, + DGUS_SCREEN_FLC_PREHEAT = 94, + DGUS_SCREEN_FLC_PRINTING = 96, + DGUS_SCREEN_STEPPERMM = 212, + DGUS_SCREEN_PID_E = 214, + DGUS_SCREEN_PID_BED = 218, + DGUS_SCREEN_Z_OFFSET = 222, + DGUS_SCREEN_INFOS = 36, + DGUS_SCREEN_CONFIRM = 240, + DGUS_SCREEN_KILL = 250, ///< Kill Screen. Must always be 250 (to be able to display "Error wrong LCD Version") + DGUS_SCREEN_WAITING = 251, + DGUS_SCREEN_POPUP = 252, ///< special target, popup screen will also return this code to say "return to previous screen" + DGUS_SCREEN_UNUSED = 255 }; // Display Memory layout used (T5UID) diff --git a/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp index aa83ee2a4ee2..768092633eda 100644 --- a/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp @@ -44,7 +44,7 @@ extern ExtUI::FileList filelist; - void DGUSScreenHandler::DGUSLCD_SD_FileSelected(DGUS_VP_Variable &var, void *val_ptr) { + void DGUSScreenHandler::sdFileSelected(DGUS_VP_Variable &var, void *val_ptr) { uint16_t touched_nr = (int16_t)swap16(*(uint16_t*)val_ptr) + top_file; if (touched_nr > filelist.count()) return; if (!filelist.seek(touched_nr)) return; @@ -52,28 +52,28 @@ if (filelist.isDir()) { filelist.changeDir(filelist.filename()); top_file = 0; - ForceCompleteUpdate(); + forceCompleteUpdate(); return; } #if ENABLED(DGUS_PRINT_FILENAME) // Send print filename - dgusdisplay.WriteVariable(VP_SD_Print_Filename, filelist.filename(), VP_SD_FileName_LEN, true); + dgus.writeVariable(VP_SD_Print_Filename, filelist.filename(), VP_SD_FileName_LEN, true); #endif // Setup Confirmation screen file_to_print = touched_nr; - HandleUserConfirmationPopUp(VP_SD_FileSelectConfirm, nullptr, PSTR("Print file"), filelist.filename(), PSTR("from SD Card?"), true, true, false, true); + handleUserConfirmationPopUp(VP_SD_FileSelectConfirm, nullptr, PSTR("Print file"), filelist.filename(), PSTR("from SD Card?"), true, true, false, true); } - void DGUSScreenHandler::DGUSLCD_SD_StartPrint(DGUS_VP_Variable &var, void *val_ptr) { + void DGUSScreenHandler::sdStartPrint(DGUS_VP_Variable &var, void *val_ptr) { if (!filelist.seek(file_to_print)) return; ExtUI::printFile(filelist.shortFilename()); - GotoScreen(DGUSLCD_SCREEN_SDPRINTMANIPULATION); + gotoScreen(DGUS_SCREEN_SDPRINTMANIPULATION); } - void DGUSScreenHandler::DGUSLCD_SD_ResumePauseAbort(DGUS_VP_Variable &var, void *val_ptr) { + void DGUSScreenHandler::sdResumePauseAbort(DGUS_VP_Variable &var, void *val_ptr) { if (!ExtUI::isPrintingFromMedia()) return; // avoid race condition when user stays in this menu and printer finishes. switch (swap16(*(uint16_t*)val_ptr)) { @@ -85,19 +85,19 @@ case 1: // Pause - GotoScreen(DGUSLCD_SCREEN_SDPRINTMANIPULATION); + gotoScreen(DGUS_SCREEN_SDPRINTMANIPULATION); if (!ExtUI::isPrintingFromMediaPaused()) { ExtUI::pausePrint(); //ExtUI::mks_pausePrint(); } break; case 2: // Abort - HandleUserConfirmationPopUp(VP_SD_AbortPrintConfirmed, nullptr, PSTR("Abort printing"), filelist.filename(), PSTR("?"), true, true, false, true); + handleUserConfirmationPopUp(VP_SD_AbortPrintConfirmed, nullptr, PSTR("Abort printing"), filelist.filename(), PSTR("?"), true, true, false, true); break; } } - void DGUSScreenHandler::DGUSLCD_SD_SendFilename(DGUS_VP_Variable& var) { + void DGUSScreenHandler::sdSendFilename(DGUS_VP_Variable& var) { uint16_t target_line = (var.VP - VP_SD_FileName0) / VP_SD_FileName_LEN; if (target_line > DGUS_SD_FILESPERSCREEN) return; char tmpfilename[VP_SD_FileName_LEN + 1] = ""; @@ -106,49 +106,49 @@ if (filelist.seek(top_file + target_line)) { snprintf_P(tmpfilename, VP_SD_FileName_LEN, PSTR("%s%c"), filelist.filename(), filelist.isDir() ? '/' : 0); // snprintf_P(tmpfilename, VP_SD_FileName_LEN, PSTR("%s"), filelist.filename()); } - DGUSLCD_SendStringToDisplay(var); + sendStringToDisplay(var); } - void DGUSScreenHandler::SDCardInserted() { + void DGUSScreenHandler::sdCardInserted() { top_file = 0; filelist.refresh(); auto cs = getCurrentScreen(); - if (cs == DGUSLCD_SCREEN_MAIN || cs == DGUSLCD_SCREEN_STATUS) - GotoScreen(DGUSLCD_SCREEN_SDFILELIST); + if (cs == DGUS_SCREEN_MAIN || cs == DGUS_SCREEN_STATUS) + gotoScreen(DGUS_SCREEN_SDFILELIST); } - void DGUSScreenHandler::SDCardRemoved() { - if (current_screen == DGUSLCD_SCREEN_SDFILELIST - || (current_screen == DGUSLCD_SCREEN_CONFIRM && (ConfirmVP == VP_SD_AbortPrintConfirmed || ConfirmVP == VP_SD_FileSelectConfirm)) - || current_screen == DGUSLCD_SCREEN_SDPRINTMANIPULATION - ) GotoScreen(DGUSLCD_SCREEN_MAIN); + void DGUSScreenHandler::sdCardRemoved() { + if (current_screenID == DGUS_SCREEN_SDFILELIST + || (current_screenID == DGUS_SCREEN_CONFIRM && (confirmVP == VP_SD_AbortPrintConfirmed || confirmVP == VP_SD_FileSelectConfirm)) + || current_screenID == DGUS_SCREEN_SDPRINTMANIPULATION + ) gotoScreen(DGUS_SCREEN_MAIN); } #endif // HAS_MEDIA -void DGUSScreenHandler::ScreenChangeHook(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandler::screenChangeHook(DGUS_VP_Variable &var, void *val_ptr) { uint8_t *tmp = (uint8_t*)val_ptr; // The keycode in target is coded as , so 0x0100A means - // from screen 1 (main) to 10 (temperature). DGUSLCD_SCREEN_POPUP is special, + // from screen 1 (main) to 10 (temperature). DGUS_SCREEN_POPUP is special, // meaning "return to previous screen" - DGUSLCD_Screens target = (DGUSLCD_Screens)tmp[1]; + DGUS_ScreenID target = (DGUS_ScreenID)tmp[1]; - if (target == DGUSLCD_SCREEN_POPUP) { + if (target == DGUS_SCREEN_POPUP) { // Special handling for popup is to return to previous menu - if (current_screen == DGUSLCD_SCREEN_POPUP && confirm_action_cb) confirm_action_cb(); - PopToOldScreen(); + if (current_screenID == DGUS_SCREEN_POPUP && confirm_action_cb) confirm_action_cb(); + popToOldScreen(); return; } - UpdateNewScreen(target); + updateNewScreen(target); #ifdef DEBUG_DGUSLCD - if (!DGUSLCD_FindScreenVPMapList(target)) DEBUG_ECHOLNPGM("WARNING: No screen Mapping found for ", target); + if (!findScreenVPMapList(target)) DEBUG_ECHOLNPGM("WARNING: No screen Mapping found for ", target); #endif } -void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandler::handleManualMove(DGUS_VP_Variable &var, void *val_ptr) { int16_t movevalue = swap16(*(uint16_t*)val_ptr); #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) if (movevalue) { @@ -196,7 +196,7 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { char buf[6] = "G28 X"; buf[4] = axiscode; queue.enqueue_one_now(buf); - ForceCompleteUpdate(); + forceCompleteUpdate(); return; } else { @@ -219,14 +219,14 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { if (!old_relative_mode) queue.enqueue_now(F("G90")); } - ForceCompleteUpdate(); + forceCompleteUpdate(); cannotmove: return; } #if HAS_PID_HEATING - void DGUSScreenHandler::HandleTemperaturePIDChanged(DGUS_VP_Variable &var, void *val_ptr) { + void DGUSScreenHandler::handleTemperaturePIDChanged(DGUS_VP_Variable &var, void *val_ptr) { uint16_t rawvalue = swap16(*(uint16_t*)val_ptr); float value = (float)rawvalue / 10; float newvalue = 0; @@ -257,17 +257,17 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { #endif // HAS_PID_HEATING #if ENABLED(BABYSTEPPING) - void DGUSScreenHandler::HandleLiveAdjustZ(DGUS_VP_Variable &var, void *val_ptr) { + void DGUSScreenHandler::handleLiveAdjustZ(DGUS_VP_Variable &var, void *val_ptr) { int16_t flag = swap16(*(uint16_t*)val_ptr), steps = flag ? -20 : 20; ExtUI::smartAdjustAxis_steps(steps, ExtUI::axis_t::Z, true); - ForceCompleteUpdate(); + forceCompleteUpdate(); } #endif #if ENABLED(DGUS_FILAMENT_LOADUNLOAD) - void DGUSScreenHandler::HandleFilamentOption(DGUS_VP_Variable &var, void *val_ptr) { + void DGUSScreenHandler::handleFilamentOption(DGUS_VP_Variable &var, void *val_ptr) { uint8_t e_temp = 0; filament_data.heated = false; uint16_t preheat_option = swap16(*(uint16_t*)val_ptr); @@ -315,7 +315,7 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { thermalManager.setTargetHotend(e_temp, ExtUI::extruder_t::E1); #endif #endif - GotoScreen(DGUSLCD_SCREEN_UTILITY); + gotoScreen(DGUS_SCREEN_UTILITY); } else { // Go to the preheat screen to show the heating progress switch (var.VP) { @@ -333,11 +333,11 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { break; #endif } - GotoScreen(DGUSLCD_SCREEN_FILAMENT_HEATING); + gotoScreen(DGUS_SCREEN_FILAMENT_HEATING); } } - void DGUSScreenHandler::HandleFilamentLoadUnload(DGUS_VP_Variable &var) { + void DGUSScreenHandler::handleFilamentLoadUnload(DGUS_VP_Variable &var) { if (filament_data.action <= 0) return; // If we close to the target temperature, we can start load or unload the filament @@ -347,14 +347,14 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { if (filament_data.action == 1) { // load filament if (!filament_data.heated) { - //GotoScreen(DGUSLCD_SCREEN_FILAMENT_LOADING); + //gotoScreen(DGUS_SCREEN_FILAMENT_LOADING); filament_data.heated = true; } movevalue = ExtUI::getAxisPosition_mm(filament_data.extruder) + movevalue; } else { // unload filament if (!filament_data.heated) { - GotoScreen(DGUSLCD_SCREEN_FILAMENT_UNLOADING); + gotoScreen(DGUS_SCREEN_FILAMENT_UNLOADING); filament_data.heated = true; } // Before unloading extrude to prevent jamming @@ -372,14 +372,14 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { #endif // DGUS_FILAMENT_LOADUNLOAD bool DGUSScreenHandler::loop() { - dgusdisplay.loop(); + dgus.loop(); const millis_t ms = millis(); static millis_t next_event_ms = 0; - if (!IsScreenComplete() || ELAPSED(ms, next_event_ms)) { + if (!isScreenComplete() || ELAPSED(ms, next_event_ms)) { next_event_ms = ms + DGUS_UPDATE_INTERVAL_MS; - UpdateScreenVPData(); + updateScreenVPData(); } #if ENABLED(SHOW_BOOTSCREEN) @@ -390,11 +390,11 @@ bool DGUSScreenHandler::loop() { if (!booted && ELAPSED(ms, BOOTSCREEN_TIMEOUT)) { booted = true; - GotoScreen(TERN0(POWER_LOSS_RECOVERY, recovery.valid()) ? DGUSLCD_SCREEN_POWER_LOSS : DGUSLCD_SCREEN_MAIN); + gotoScreen(TERN0(POWER_LOSS_RECOVERY, recovery.valid()) ? DGUS_SCREEN_POWER_LOSS : DGUS_SCREEN_MAIN); } #endif - return IsScreenComplete(); + return isScreenComplete(); } #endif // DGUS_LCD_UI_FYSETC diff --git a/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.h index 73e3527d7e7c..16c5dec408d6 100644 --- a/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.h +++ b/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.h @@ -26,6 +26,6 @@ typedef DGUSScreenHandler DGUSScreenHandlerClass; #if ENABLED(POWER_LOSS_RECOVERY) - #define PLR_SCREEN_RECOVER DGUSLCD_SCREEN_SDPRINTMANIPULATION - #define PLR_SCREEN_CANCEL DGUSLCD_SCREEN_STATUS + #define PLR_SCREEN_RECOVER DGUS_SCREEN_SDPRINTMANIPULATION + #define PLR_SCREEN_CANCEL DGUS_SCREEN_STATUS #endif diff --git a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.cpp index c278179e3f27..d99a4fe4f688 100644 --- a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.cpp +++ b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.cpp @@ -286,28 +286,28 @@ const uint16_t VPList_Z_Offset[] PROGMEM = { }; const struct VPMapping VPMap[] PROGMEM = { - { DGUSLCD_SCREEN_BOOT, VPList_Boot }, - { DGUSLCD_SCREEN_MAIN, VPList_Main }, - { DGUSLCD_SCREEN_TEMPERATURE, VPList_Temp }, - { DGUSLCD_SCREEN_STATUS, VPList_Status }, - { DGUSLCD_SCREEN_STATUS2, VPList_Status2 }, - { DGUSLCD_SCREEN_PREHEAT, VPList_Preheat }, - { DGUSLCD_SCREEN_MANUALMOVE, VPList_ManualMove }, - { DGUSLCD_SCREEN_Z_OFFSET, VPList_Z_Offset }, - { DGUSLCD_SCREEN_MANUALEXTRUDE, VPList_ManualExtrude }, - { DGUSLCD_SCREEN_FILAMENT_HEATING, VPList_Filament_heating }, - { DGUSLCD_SCREEN_FILAMENT_LOADING, VPList_Filament_load_unload }, - { DGUSLCD_SCREEN_FILAMENT_UNLOADING, VPList_Filament_load_unload }, - { DGUSLCD_SCREEN_SDPRINTMANIPULATION, VPList_SD_PrintManipulation }, - { DGUSLCD_SCREEN_SDFILELIST, VPList_SDFileList }, - { DGUSLCD_SCREEN_SDPRINTTUNE, VPList_SDPrintTune }, - { DGUSLCD_SCREEN_WAITING, VPList_PIDTuningWaiting }, - { DGUSLCD_SCREEN_FLC_PREHEAT, VPList_FLCPreheat }, - { DGUSLCD_SCREEN_FLC_PRINTING, VPList_FLCPrinting }, - { DGUSLCD_SCREEN_STEPPERMM, VPList_StepPerMM }, - { DGUSLCD_SCREEN_PID_E, VPList_PIDE0 }, - { DGUSLCD_SCREEN_PID_BED, VPList_PIDBED }, - { DGUSLCD_SCREEN_INFOS, VPList_Infos }, + { DGUS_SCREEN_BOOT, VPList_Boot }, + { DGUS_SCREEN_MAIN, VPList_Main }, + { DGUS_SCREEN_TEMPERATURE, VPList_Temp }, + { DGUS_SCREEN_STATUS, VPList_Status }, + { DGUS_SCREEN_STATUS2, VPList_Status2 }, + { DGUS_SCREEN_PREHEAT, VPList_Preheat }, + { DGUS_SCREEN_MANUALMOVE, VPList_ManualMove }, + { DGUS_SCREEN_Z_OFFSET, VPList_Z_Offset }, + { DGUS_SCREEN_MANUALEXTRUDE, VPList_ManualExtrude }, + { DGUS_SCREEN_FILAMENT_HEATING, VPList_Filament_heating }, + { DGUS_SCREEN_FILAMENT_LOADING, VPList_Filament_load_unload }, + { DGUS_SCREEN_FILAMENT_UNLOADING, VPList_Filament_load_unload }, + { DGUS_SCREEN_SDPRINTMANIPULATION, VPList_SD_PrintManipulation }, + { DGUS_SCREEN_SDFILELIST, VPList_SDFileList }, + { DGUS_SCREEN_SDPRINTTUNE, VPList_SDPrintTune }, + { DGUS_SCREEN_WAITING, VPList_PIDTuningWaiting }, + { DGUS_SCREEN_FLC_PREHEAT, VPList_FLCPreheat }, + { DGUS_SCREEN_FLC_PRINTING, VPList_FLCPrinting }, + { DGUS_SCREEN_STEPPERMM, VPList_StepPerMM }, + { DGUS_SCREEN_PID_E, VPList_PIDE0 }, + { DGUS_SCREEN_PID_BED, VPList_PIDBED }, + { DGUS_SCREEN_INFOS, VPList_Infos }, { 0 , nullptr } // List is terminated with an nullptr as table entry. }; @@ -315,155 +315,155 @@ const char MarlinVersion[] PROGMEM = SHORT_BUILD_VERSION; const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { // Helper to detect touch events - VPHELPER(VP_SCREENCHANGE, nullptr, ScreenHandler.ScreenChangeHook, nullptr), - VPHELPER(VP_SCREENCHANGE_ASK, nullptr, ScreenHandler.ScreenChangeHookIfIdle, nullptr), + VPHELPER(VP_SCREENCHANGE, nullptr, screen.screenChangeHook, nullptr), + VPHELPER(VP_SCREENCHANGE_ASK, nullptr, screen.screenChangeHookIfIdle, nullptr), #if HAS_MEDIA - VPHELPER(VP_SCREENCHANGE_WHENSD, nullptr, ScreenHandler.ScreenChangeHookIfSD, nullptr), + VPHELPER(VP_SCREENCHANGE_WHENSD, nullptr, screen.screenChangeHookIfSD, nullptr), #endif - VPHELPER(VP_CONFIRMED, nullptr, ScreenHandler.ScreenConfirmedOK, nullptr), + VPHELPER(VP_CONFIRMED, nullptr, screen.screenConfirmedOK, nullptr), - VPHELPER(VP_TEMP_ALL_OFF, nullptr, ScreenHandler.HandleAllHeatersOff, nullptr), + VPHELPER(VP_TEMP_ALL_OFF, nullptr, screen.handleAllHeatersOff, nullptr), #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) - VPHELPER(VP_MOVE_OPTION, &distanceToMove, ScreenHandler.HandleManualMoveOption, nullptr), + VPHELPER(VP_MOVE_OPTION, &distanceToMove, screen.handleManualMoveOption, nullptr), #endif #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) - VPHELPER(VP_MOVE_X, &distanceToMove, ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Y, &distanceToMove, ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Z, &distanceToMove, ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_HOME_ALL, &distanceToMove, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_X, &distanceToMove, screen.handleManualMove, nullptr), + VPHELPER(VP_MOVE_Y, &distanceToMove, screen.handleManualMove, nullptr), + VPHELPER(VP_MOVE_Z, &distanceToMove, screen.handleManualMove, nullptr), + VPHELPER(VP_HOME_ALL, &distanceToMove, screen.handleManualMove, nullptr), #else - VPHELPER(VP_MOVE_X, nullptr, ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Y, nullptr, ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Z, nullptr, ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_HOME_ALL, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_X, nullptr, screen.handleManualMove, nullptr), + VPHELPER(VP_MOVE_Y, nullptr, screen.handleManualMove, nullptr), + VPHELPER(VP_MOVE_Z, nullptr, screen.handleManualMove, nullptr), + VPHELPER(VP_HOME_ALL, nullptr, screen.handleManualMove, nullptr), #endif - VPHELPER(VP_MOTOR_LOCK_UNLOK, nullptr, ScreenHandler.HandleMotorLockUnlock, nullptr), + VPHELPER(VP_MOTOR_LOCK_UNLOK, nullptr, screen.handleMotorLockUnlock, nullptr), #if ENABLED(POWER_LOSS_RECOVERY) - VPHELPER(VP_POWER_LOSS_RECOVERY, nullptr, ScreenHandler.HandlePowerLossRecovery, nullptr), + VPHELPER(VP_POWER_LOSS_RECOVERY, nullptr, screen.handlePowerLossRecovery, nullptr), #endif - VPHELPER(VP_SETTINGS, nullptr, ScreenHandler.HandleSettings, nullptr), + VPHELPER(VP_SETTINGS, nullptr, screen.handleSettings, nullptr), #if ENABLED(SINGLE_Z_CALIBRATION) - VPHELPER(VP_Z_CALIBRATE, nullptr, ScreenHandler.HandleZCalibration, nullptr), + VPHELPER(VP_Z_CALIBRATE, nullptr, screen.handleZCalibration, nullptr), #endif #if ENABLED(FIRST_LAYER_CAL) - VPHELPER(VP_Z_FIRST_LAYER_CAL, nullptr, ScreenHandler.HandleFirstLayerCal, nullptr), + VPHELPER(VP_Z_FIRST_LAYER_CAL, nullptr, screen.handleFirstLayerCal, nullptr), #endif - { .VP = VP_MARLIN_VERSION, .memadr = (void*)MarlinVersion, .size = VP_MARLIN_VERSION_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + { .VP = VP_MARLIN_VERSION, .memadr = (void*)MarlinVersion, .size = VP_MARLIN_VERSION_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = screen.sendStringToDisplayPGM }, // M117 LCD String (We don't need the string in memory but "just" push it to the display on demand, hence the nullptr - { .VP = VP_M117, .memadr = nullptr, .size = VP_M117_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplay }, + { .VP = VP_M117, .memadr = nullptr, .size = VP_M117_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = screen.sendStringToDisplay }, // Temperature Data #if HAS_HOTEND - VPHELPER(VP_T_E0_Is, &thermalManager.temp_hotend[0].celsius, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<0>), - VPHELPER(VP_T_E0_Set, &thermalManager.temp_hotend[0].target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_Flowrate_E0, &planner.flow_percentage[ExtUI::extruder_t::E0], ScreenHandler.HandleFlowRateChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_EPos, &destination.e, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), - VPHELPER(VP_MOVE_E0, nullptr, ScreenHandler.HandleManualExtrude, nullptr), - VPHELPER(VP_E0_CONTROL, &thermalManager.temp_hotend[0].target, ScreenHandler.HandleHeaterControl, nullptr), - VPHELPER(VP_E0_STATUS, &thermalManager.temp_hotend[0].target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), + VPHELPER(VP_T_E0_Is, &thermalManager.temp_hotend[0].celsius, nullptr, screen.sendFloatAsLongValueToDisplay<0>), + VPHELPER(VP_T_E0_Set, &thermalManager.temp_hotend[0].target, screen.handleTemperatureChanged, screen.sendWordValueToDisplay), + VPHELPER(VP_Flowrate_E0, &planner.flow_percentage[ExtUI::extruder_t::E0], screen.handleFlowRateChanged, screen.sendWordValueToDisplay), + VPHELPER(VP_EPos, &destination.e, nullptr, screen.sendFloatAsLongValueToDisplay<2>), + VPHELPER(VP_MOVE_E0, nullptr, screen.handleManualExtrude, nullptr), + VPHELPER(VP_E0_CONTROL, &thermalManager.temp_hotend[0].target, screen.handleHeaterControl, nullptr), + VPHELPER(VP_E0_STATUS, &thermalManager.temp_hotend[0].target, nullptr, screen.sendHeaterStatusToDisplay), #if ENABLED(DGUS_PREHEAT_UI) - VPHELPER(VP_E0_BED_PREHEAT, nullptr, ScreenHandler.HandlePreheat, nullptr), + VPHELPER(VP_E0_BED_PREHEAT, nullptr, screen.handlePreheat, nullptr), #endif #if ENABLED(DGUS_FILAMENT_LOADUNLOAD) - VPHELPER(VP_E0_FILAMENT_LOAD_UNLOAD, nullptr, ScreenHandler.HandleFilamentOption, ScreenHandler.HandleFilamentLoadUnload), + VPHELPER(VP_E0_FILAMENT_LOAD_UNLOAD, nullptr, screen.handleFilamentOption, screen.handleFilamentLoadUnload), #endif #if ENABLED(PIDTEMP) - VPHELPER(VP_E0_PID_P, &thermalManager.temp_hotend[0].pid.Kp, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_E0_PID_I, &thermalManager.temp_hotend[0].pid.Ki, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_E0_PID_D, &thermalManager.temp_hotend[0].pid.Kd, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_PID_AUTOTUNE_E0, nullptr, ScreenHandler.HandlePIDAutotune, nullptr), + VPHELPER(VP_E0_PID_P, &thermalManager.temp_hotend[0].pid.Kp, screen.handleTemperaturePIDChanged, screen.sendTemperaturePID), + VPHELPER(VP_E0_PID_I, &thermalManager.temp_hotend[0].pid.Ki, screen.handleTemperaturePIDChanged, screen.sendTemperaturePID), + VPHELPER(VP_E0_PID_D, &thermalManager.temp_hotend[0].pid.Kd, screen.handleTemperaturePIDChanged, screen.sendTemperaturePID), + VPHELPER(VP_PID_AUTOTUNE_E0, nullptr, screen.handlePIDAutotune, nullptr), #endif #endif #if HAS_MULTI_HOTEND - VPHELPER(VP_T_E1_Is, &thermalManager.temp_hotend[1].celsius, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<0>), - VPHELPER(VP_T_E1_Set, &thermalManager.temp_hotend[1].target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_Flowrate_E1, nullptr, ScreenHandler.HandleFlowRateChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_MOVE_E1, nullptr, ScreenHandler.HandleManualExtrude, nullptr), - VPHELPER(VP_E1_CONTROL, &thermalManager.temp_hotend[1].target, ScreenHandler.HandleHeaterControl, nullptr), - VPHELPER(VP_E1_STATUS, &thermalManager.temp_hotend[1].target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), + VPHELPER(VP_T_E1_Is, &thermalManager.temp_hotend[1].celsius, nullptr, screen.sendFloatAsLongValueToDisplay<0>), + VPHELPER(VP_T_E1_Set, &thermalManager.temp_hotend[1].target, screen.handleTemperatureChanged, screen.sendWordValueToDisplay), + VPHELPER(VP_Flowrate_E1, nullptr, screen.handleFlowRateChanged, screen.sendWordValueToDisplay), + VPHELPER(VP_MOVE_E1, nullptr, screen.handleManualExtrude, nullptr), + VPHELPER(VP_E1_CONTROL, &thermalManager.temp_hotend[1].target, screen.handleHeaterControl, nullptr), + VPHELPER(VP_E1_STATUS, &thermalManager.temp_hotend[1].target, nullptr, screen.sendHeaterStatusToDisplay), #endif #if HAS_HEATED_BED - VPHELPER(VP_T_Bed_Is, &thermalManager.temp_bed.celsius, nullptr, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_T_Bed_Set, &thermalManager.temp_bed.target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_BED_CONTROL, &thermalManager.temp_bed.target, ScreenHandler.HandleHeaterControl, nullptr), - VPHELPER(VP_BED_STATUS, &thermalManager.temp_bed.target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), + VPHELPER(VP_T_Bed_Is, &thermalManager.temp_bed.celsius, nullptr, screen.sendWordValueToDisplay), + VPHELPER(VP_T_Bed_Set, &thermalManager.temp_bed.target, screen.handleTemperatureChanged, screen.sendWordValueToDisplay), + VPHELPER(VP_BED_CONTROL, &thermalManager.temp_bed.target, screen.handleHeaterControl, nullptr), + VPHELPER(VP_BED_STATUS, &thermalManager.temp_bed.target, nullptr, screen.sendHeaterStatusToDisplay), #if ENABLED(PIDTEMPBED) - VPHELPER(VP_BED_PID_P, &thermalManager.temp_bed.pid.Kp, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_BED_PID_I, &thermalManager.temp_bed.pid.Ki, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_BED_PID_D, &thermalManager.temp_bed.pid.Kd, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_PID_AUTOTUNE_BED, nullptr, ScreenHandler.HandlePIDAutotune, nullptr), + VPHELPER(VP_BED_PID_P, &thermalManager.temp_bed.pid.Kp, screen.handleTemperaturePIDChanged, screen.sendTemperaturePID), + VPHELPER(VP_BED_PID_I, &thermalManager.temp_bed.pid.Ki, screen.handleTemperaturePIDChanged, screen.sendTemperaturePID), + VPHELPER(VP_BED_PID_D, &thermalManager.temp_bed.pid.Kd, screen.handleTemperaturePIDChanged, screen.sendTemperaturePID), + VPHELPER(VP_PID_AUTOTUNE_BED, nullptr, screen.handlePIDAutotune, nullptr), #endif #endif // Fan Data #if HAS_FAN #define FAN_VPHELPER(N) \ - VPHELPER(VP_Fan##N##_Percentage, &thermalManager.fan_speed[N], ScreenHandler.DGUSLCD_PercentageToUint8, ScreenHandler.DGUSLCD_SendPercentageToDisplay), \ - VPHELPER(VP_FAN##N##_CONTROL, &thermalManager.fan_speed[N], ScreenHandler.HandleFanControl, nullptr), \ - VPHELPER(VP_FAN##N##_STATUS, &thermalManager.fan_speed[N], nullptr, ScreenHandler.DGUSLCD_SendFanStatusToDisplay), + VPHELPER(VP_Fan##N##_Percentage, &thermalManager.fan_speed[N], screen.percentageToUint8, screen.sendPercentageToDisplay), \ + VPHELPER(VP_FAN##N##_CONTROL, &thermalManager.fan_speed[N], screen.handleFanControl, nullptr), \ + VPHELPER(VP_FAN##N##_STATUS, &thermalManager.fan_speed[N], nullptr, screen.sendFanStatusToDisplay), REPEAT(FAN_COUNT, FAN_VPHELPER) #endif // Feedrate - VPHELPER(VP_Feedrate_Percentage, &feedrate_percentage, ScreenHandler.DGUSLCD_SetValueDirectly, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Feedrate_Percentage, &feedrate_percentage, screen.setValueDirectly, screen.sendWordValueToDisplay), // Position Data - VPHELPER(VP_XPos, ¤t_position.x, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), - VPHELPER(VP_YPos, ¤t_position.y, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), - VPHELPER(VP_ZPos, ¤t_position.z, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), + VPHELPER(VP_XPos, ¤t_position.x, nullptr, screen.sendFloatAsLongValueToDisplay<2>), + VPHELPER(VP_YPos, ¤t_position.y, nullptr, screen.sendFloatAsLongValueToDisplay<2>), + VPHELPER(VP_ZPos, ¤t_position.z, nullptr, screen.sendFloatAsLongValueToDisplay<2>), // Print Progress - VPHELPER(VP_PrintProgress_Percentage, nullptr, nullptr, ScreenHandler.DGUSLCD_SendPrintProgressToDisplay), + VPHELPER(VP_PrintProgress_Percentage, nullptr, nullptr, screen.sendPrintProgressToDisplay), // Print Time - VPHELPER_STR(VP_PrintTime, nullptr, VP_PrintTime_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintTimeToDisplay), + VPHELPER_STR(VP_PrintTime, nullptr, VP_PrintTime_LEN, nullptr, screen.sendPrintTimeToDisplay), #if ENABLED(PRINTCOUNTER) - VPHELPER_STR(VP_PrintAccTime, nullptr, VP_PrintAccTime_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintAccTimeToDisplay), - VPHELPER_STR(VP_PrintsTotal, nullptr, VP_PrintsTotal_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintsTotalToDisplay), + VPHELPER_STR(VP_PrintAccTime, nullptr, VP_PrintAccTime_LEN, nullptr, screen.sendPrintAccTimeToDisplay), + VPHELPER_STR(VP_PrintsTotal, nullptr, VP_PrintsTotal_LEN, nullptr, screen.sendPrintsTotalToDisplay), #endif - VPHELPER(VP_X_STEP_PER_MM, &planner.settings.axis_steps_per_mm[X_AXIS], ScreenHandler.HandleStepPerMMChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), - VPHELPER(VP_Y_STEP_PER_MM, &planner.settings.axis_steps_per_mm[Y_AXIS], ScreenHandler.HandleStepPerMMChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), - VPHELPER(VP_Z_STEP_PER_MM, &planner.settings.axis_steps_per_mm[Z_AXIS], ScreenHandler.HandleStepPerMMChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), + VPHELPER(VP_X_STEP_PER_MM, &planner.settings.axis_steps_per_mm[X_AXIS], screen.handleStepPerMMChanged, screen.sendFloatAsIntValueToDisplay<1>), + VPHELPER(VP_Y_STEP_PER_MM, &planner.settings.axis_steps_per_mm[Y_AXIS], screen.handleStepPerMMChanged, screen.sendFloatAsIntValueToDisplay<1>), + VPHELPER(VP_Z_STEP_PER_MM, &planner.settings.axis_steps_per_mm[Z_AXIS], screen.handleStepPerMMChanged, screen.sendFloatAsIntValueToDisplay<1>), #if HAS_HOTEND - VPHELPER(VP_E0_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(0)], ScreenHandler.HandleStepPerMMExtruderChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), + VPHELPER(VP_E0_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(0)], screen.handleStepPerMMExtruderChanged, screen.sendFloatAsIntValueToDisplay<1>), #if HAS_MULTI_HOTEND - VPHELPER(VP_E1_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(1)], ScreenHandler.HandleStepPerMMExtruderChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), + VPHELPER(VP_E1_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(1)], screen.handleStepPerMMExtruderChanged, screen.sendFloatAsIntValueToDisplay<1>), #endif #endif // SDCard File listing. #if HAS_MEDIA - VPHELPER(VP_SD_ScrollEvent, nullptr, ScreenHandler.DGUSLCD_SD_ScrollFilelist, nullptr), - VPHELPER(VP_SD_FileSelected, nullptr, ScreenHandler.DGUSLCD_SD_FileSelected, nullptr), - VPHELPER(VP_SD_FileSelectConfirm, nullptr, ScreenHandler.DGUSLCD_SD_StartPrint, nullptr), - VPHELPER_STR(VP_SD_FileName0, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), - VPHELPER_STR(VP_SD_FileName1, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), - VPHELPER_STR(VP_SD_FileName2, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), - VPHELPER_STR(VP_SD_FileName3, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), - VPHELPER_STR(VP_SD_FileName4, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), - VPHELPER(VP_SD_ResumePauseAbort, nullptr, ScreenHandler.DGUSLCD_SD_ResumePauseAbort, nullptr), - VPHELPER(VP_SD_AbortPrintConfirmed, nullptr, ScreenHandler.DGUSLCD_SD_ReallyAbort, nullptr), - VPHELPER(VP_SD_Print_Setting, nullptr, ScreenHandler.DGUSLCD_SD_PrintTune, nullptr), + VPHELPER(VP_SD_ScrollEvent, nullptr, screen.sdScrollFilelist, nullptr), + VPHELPER(VP_SD_FileSelected, nullptr, screen.sdFileSelected, nullptr), + VPHELPER(VP_SD_FileSelectConfirm, nullptr, screen.sdStartPrint, nullptr), + VPHELPER_STR(VP_SD_FileName0, nullptr, VP_SD_FileName_LEN, nullptr, screen.sdSendFilename), + VPHELPER_STR(VP_SD_FileName1, nullptr, VP_SD_FileName_LEN, nullptr, screen.sdSendFilename), + VPHELPER_STR(VP_SD_FileName2, nullptr, VP_SD_FileName_LEN, nullptr, screen.sdSendFilename), + VPHELPER_STR(VP_SD_FileName3, nullptr, VP_SD_FileName_LEN, nullptr, screen.sdSendFilename), + VPHELPER_STR(VP_SD_FileName4, nullptr, VP_SD_FileName_LEN, nullptr, screen.sdSendFilename), + VPHELPER(VP_SD_ResumePauseAbort, nullptr, screen.sdResumePauseAbort, nullptr), + VPHELPER(VP_SD_AbortPrintConfirmed, nullptr, screen.sdReallyAbort, nullptr), + VPHELPER(VP_SD_Print_Setting, nullptr, screen.sdPrintTune, nullptr), #if HAS_BED_PROBE - VPHELPER(VP_SD_Print_ProbeOffsetZ, &probe.offset.z, ScreenHandler.HandleProbeOffsetZChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<2>), + VPHELPER(VP_SD_Print_ProbeOffsetZ, &probe.offset.z, screen.handleProbeOffsetZChanged, screen.sendFloatAsIntValueToDisplay<2>), #if ENABLED(BABYSTEPPING) - VPHELPER(VP_SD_Print_LiveAdjustZ, nullptr, ScreenHandler.HandleLiveAdjustZ, nullptr), + VPHELPER(VP_SD_Print_LiveAdjustZ, nullptr, screen.handleLiveAdjustZ, nullptr), #endif #endif #endif #if ENABLED(DGUS_UI_WAITING) - VPHELPER(VP_WAITING_STATUS, nullptr, nullptr, ScreenHandler.DGUSLCD_SendWaitingStatusToDisplay), + VPHELPER(VP_WAITING_STATUS, nullptr, nullptr, screen.sendWaitingStatusToDisplay), #endif // Messages for the User, shared by the popup and the kill screen. They can't be autouploaded as we do not buffer content. - { .VP = VP_MSGSTR1, .memadr = nullptr, .size = VP_MSGSTR1_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, - { .VP = VP_MSGSTR2, .memadr = nullptr, .size = VP_MSGSTR2_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, - { .VP = VP_MSGSTR3, .memadr = nullptr, .size = VP_MSGSTR3_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, - { .VP = VP_MSGSTR4, .memadr = nullptr, .size = VP_MSGSTR4_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + { .VP = VP_MSGSTR1, .memadr = nullptr, .size = VP_MSGSTR1_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = screen.sendStringToDisplayPGM }, + { .VP = VP_MSGSTR2, .memadr = nullptr, .size = VP_MSGSTR2_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = screen.sendStringToDisplayPGM }, + { .VP = VP_MSGSTR3, .memadr = nullptr, .size = VP_MSGSTR3_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = screen.sendStringToDisplayPGM }, + { .VP = VP_MSGSTR4, .memadr = nullptr, .size = VP_MSGSTR4_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = screen.sendStringToDisplayPGM }, VPHELPER(0, 0, 0, 0) // must be last entry. }; diff --git a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.h b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.h index 3b7199f07eb8..6270207990a7 100644 --- a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.h +++ b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.h @@ -23,35 +23,35 @@ #include "../DGUSDisplayDef.h" -enum DGUSLCD_Screens : uint8_t { - DGUSLCD_SCREEN_BOOT = 160, - DGUSLCD_SCREEN_MAIN = 1, - DGUSLCD_SCREEN_STATUS = 1, - DGUSLCD_SCREEN_STATUS2 = 1, - DGUSLCD_SCREEN_POWER_LOSS = 17, - DGUSLCD_SCREEN_TEMPERATURE = 40, - DGUSLCD_SCREEN_MANUALMOVE = 86, - DGUSLCD_SCREEN_PREHEAT = 48, - DGUSLCD_SCREEN_UTILITY = 70, - DGUSLCD_SCREEN_FILAMENT_HEATING = 80, - DGUSLCD_SCREEN_FILAMENT_LOADING = 76, - DGUSLCD_SCREEN_FILAMENT_UNLOADING = 82, - DGUSLCD_SCREEN_MANUALEXTRUDE = 84, - DGUSLCD_SCREEN_Z_OFFSET = 88, - DGUSLCD_SCREEN_SDFILELIST = 3, - DGUSLCD_SCREEN_SDPRINTMANIPULATION = 7, - DGUSLCD_SCREEN_SDPRINTTUNE = 9, - DGUSLCD_SCREEN_FLC_PREHEAT = 94, - DGUSLCD_SCREEN_FLC_PRINTING = 96, - DGUSLCD_SCREEN_STEPPERMM = 122, - DGUSLCD_SCREEN_PID_E = 126, - DGUSLCD_SCREEN_PID_BED = 128, - DGUSLCD_SCREEN_INFOS = 131, - DGUSLCD_SCREEN_CONFIRM = 240, - DGUSLCD_SCREEN_KILL = 250, ///< Kill Screen. Must always be 250 (to be able to display "Error wrong LCD Version") - DGUSLCD_SCREEN_WAITING = 251, - DGUSLCD_SCREEN_POPUP = 252, ///< special target, popup screen will also return this code to say "return to previous screen" - DGUSLCD_SCREEN_UNUSED = 255 +enum DGUS_ScreenID : uint8_t { + DGUS_SCREEN_BOOT = 160, + DGUS_SCREEN_MAIN = 1, + DGUS_SCREEN_STATUS = 1, + DGUS_SCREEN_STATUS2 = 1, + DGUS_SCREEN_POWER_LOSS = 17, + DGUS_SCREEN_TEMPERATURE = 40, + DGUS_SCREEN_MANUALMOVE = 86, + DGUS_SCREEN_PREHEAT = 48, + DGUS_SCREEN_UTILITY = 70, + DGUS_SCREEN_FILAMENT_HEATING = 80, + DGUS_SCREEN_FILAMENT_LOADING = 76, + DGUS_SCREEN_FILAMENT_UNLOADING = 82, + DGUS_SCREEN_MANUALEXTRUDE = 84, + DGUS_SCREEN_Z_OFFSET = 88, + DGUS_SCREEN_SDFILELIST = 3, + DGUS_SCREEN_SDPRINTMANIPULATION = 7, + DGUS_SCREEN_SDPRINTTUNE = 9, + DGUS_SCREEN_FLC_PREHEAT = 94, + DGUS_SCREEN_FLC_PRINTING = 96, + DGUS_SCREEN_STEPPERMM = 122, + DGUS_SCREEN_PID_E = 126, + DGUS_SCREEN_PID_BED = 128, + DGUS_SCREEN_INFOS = 131, + DGUS_SCREEN_CONFIRM = 240, + DGUS_SCREEN_KILL = 250, ///< Kill Screen. Must always be 250 (to be able to display "Error wrong LCD Version") + DGUS_SCREEN_WAITING = 251, + DGUS_SCREEN_POPUP = 252, ///< special target, popup screen will also return this code to say "return to previous screen" + DGUS_SCREEN_UNUSED = 255 }; // Display Memory layout used (T5UID) diff --git a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp index d0119d494f4b..f817453f1b0e 100644 --- a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp @@ -44,7 +44,7 @@ extern ExtUI::FileList filelist; - void DGUSScreenHandler::DGUSLCD_SD_FileSelected(DGUS_VP_Variable &var, void *val_ptr) { + void DGUSScreenHandler::sdFileSelected(DGUS_VP_Variable &var, void *val_ptr) { uint16_t touched_nr = (int16_t)swap16(*(uint16_t*)val_ptr) + top_file; if (touched_nr > filelist.count()) return; if (!filelist.seek(touched_nr)) return; @@ -52,28 +52,28 @@ if (filelist.isDir()) { filelist.changeDir(filelist.filename()); top_file = 0; - ForceCompleteUpdate(); + forceCompleteUpdate(); return; } #if ENABLED(DGUS_PRINT_FILENAME) // Send print filename - dgusdisplay.WriteVariable(VP_SD_Print_Filename, filelist.filename(), VP_SD_FileName_LEN, true); + dgus.writeVariable(VP_SD_Print_Filename, filelist.filename(), VP_SD_FileName_LEN, true); #endif // Setup Confirmation screen file_to_print = touched_nr; - HandleUserConfirmationPopUp(VP_SD_FileSelectConfirm, nullptr, PSTR("Print file"), filelist.filename(), PSTR("from SD Card?"), true, true, false, true); + handleUserConfirmationPopUp(VP_SD_FileSelectConfirm, nullptr, PSTR("Print file"), filelist.filename(), PSTR("from SD Card?"), true, true, false, true); } - void DGUSScreenHandler::DGUSLCD_SD_StartPrint(DGUS_VP_Variable &var, void *val_ptr) { + void DGUSScreenHandler::sdStartPrint(DGUS_VP_Variable &var, void *val_ptr) { if (!filelist.seek(file_to_print)) return; ExtUI::printFile(filelist.shortFilename()); - GotoScreen(DGUSLCD_SCREEN_SDPRINTMANIPULATION); + gotoScreen(DGUS_SCREEN_SDPRINTMANIPULATION); } - void DGUSScreenHandler::DGUSLCD_SD_ResumePauseAbort(DGUS_VP_Variable &var, void *val_ptr) { + void DGUSScreenHandler::sdResumePauseAbort(DGUS_VP_Variable &var, void *val_ptr) { if (!ExtUI::isPrintingFromMedia()) return; // avoid race condition when user stays in this menu and printer finishes. switch (swap16(*(uint16_t*)val_ptr)) { @@ -85,19 +85,19 @@ case 1: // Pause - GotoScreen(MKSLCD_SCREEN_PAUSE); + gotoScreen(MKSLCD_SCREEN_PAUSE); if (!ExtUI::isPrintingFromMediaPaused()) { ExtUI::pausePrint(); //ExtUI::mks_pausePrint(); } break; case 2: // Abort - HandleUserConfirmationPopUp(VP_SD_AbortPrintConfirmed, nullptr, PSTR("Abort printing"), filelist.filename(), PSTR("?"), true, true, false, true); + handleUserConfirmationPopUp(VP_SD_AbortPrintConfirmed, nullptr, PSTR("Abort printing"), filelist.filename(), PSTR("?"), true, true, false, true); break; } } - void DGUSScreenHandler::DGUSLCD_SD_SendFilename(DGUS_VP_Variable& var) { + void DGUSScreenHandler::sdSendFilename(DGUS_VP_Variable& var) { uint16_t target_line = (var.VP - VP_SD_FileName0) / VP_SD_FileName_LEN; if (target_line > DGUS_SD_FILESPERSCREEN) return; char tmpfilename[VP_SD_FileName_LEN + 1] = ""; @@ -106,49 +106,49 @@ if (filelist.seek(top_file + target_line)) { snprintf_P(tmpfilename, VP_SD_FileName_LEN, PSTR("%s%c"), filelist.filename(), filelist.isDir() ? '/' : 0); // snprintf_P(tmpfilename, VP_SD_FileName_LEN, PSTR("%s"), filelist.filename()); } - DGUSLCD_SendStringToDisplay(var); + sendStringToDisplay(var); } - void DGUSScreenHandler::SDCardInserted() { + void DGUSScreenHandler::sdCardInserted() { top_file = 0; filelist.refresh(); auto cs = getCurrentScreen(); - if (cs == DGUSLCD_SCREEN_MAIN || cs == DGUSLCD_SCREEN_STATUS) - GotoScreen(DGUSLCD_SCREEN_SDFILELIST); + if (cs == DGUS_SCREEN_MAIN || cs == DGUS_SCREEN_STATUS) + gotoScreen(DGUS_SCREEN_SDFILELIST); } - void DGUSScreenHandler::SDCardRemoved() { - if (current_screen == DGUSLCD_SCREEN_SDFILELIST - || (current_screen == DGUSLCD_SCREEN_CONFIRM && (ConfirmVP == VP_SD_AbortPrintConfirmed || ConfirmVP == VP_SD_FileSelectConfirm)) - || current_screen == DGUSLCD_SCREEN_SDPRINTMANIPULATION - ) GotoScreen(DGUSLCD_SCREEN_MAIN); + void DGUSScreenHandler::sdCardRemoved() { + if (current_screenID == DGUS_SCREEN_SDFILELIST + || (current_screenID == DGUS_SCREEN_CONFIRM && (confirmVP == VP_SD_AbortPrintConfirmed || confirmVP == VP_SD_FileSelectConfirm)) + || current_screenID == DGUS_SCREEN_SDPRINTMANIPULATION + ) gotoScreen(DGUS_SCREEN_MAIN); } #endif // HAS_MEDIA -void DGUSScreenHandler::ScreenChangeHook(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandler::screenChangeHook(DGUS_VP_Variable &var, void *val_ptr) { uint8_t *tmp = (uint8_t*)val_ptr; // The keycode in target is coded as , so 0x0100A means - // from screen 1 (main) to 10 (temperature). DGUSLCD_SCREEN_POPUP is special, + // from screen 1 (main) to 10 (temperature). DGUS_SCREEN_POPUP is special, // meaning "return to previous screen" - DGUSLCD_Screens target = (DGUSLCD_Screens)tmp[1]; + DGUS_ScreenID target = (DGUS_ScreenID)tmp[1]; - if (target == DGUSLCD_SCREEN_POPUP) { + if (target == DGUS_SCREEN_POPUP) { // Special handling for popup is to return to previous menu - if (current_screen == DGUSLCD_SCREEN_POPUP && confirm_action_cb) confirm_action_cb(); - PopToOldScreen(); + if (current_screenID == DGUS_SCREEN_POPUP && confirm_action_cb) confirm_action_cb(); + popToOldScreen(); return; } - UpdateNewScreen(target); + updateNewScreen(target); #ifdef DEBUG_DGUSLCD - if (!DGUSLCD_FindScreenVPMapList(target)) DEBUG_ECHOLNPGM("WARNING: No screen Mapping found for ", target); + if (!findScreenVPMapList(target)) DEBUG_ECHOLNPGM("WARNING: No screen Mapping found for ", target); #endif } -void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandler::handleManualMove(DGUS_VP_Variable &var, void *val_ptr) { int16_t movevalue = swap16(*(uint16_t*)val_ptr); #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) if (movevalue) { @@ -196,7 +196,7 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { char buf[6] = "G28 X"; buf[4] = axiscode; queue.enqueue_one_now(buf); - ForceCompleteUpdate(); + forceCompleteUpdate(); return; } else { @@ -219,14 +219,14 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { if (!old_relative_mode) queue.enqueue_now(F("G90")); } - ForceCompleteUpdate(); + forceCompleteUpdate(); cannotmove: return; } #if HAS_PID_HEATING - void DGUSScreenHandler::HandleTemperaturePIDChanged(DGUS_VP_Variable &var, void *val_ptr) { + void DGUSScreenHandler::handleTemperaturePIDChanged(DGUS_VP_Variable &var, void *val_ptr) { uint16_t rawvalue = swap16(*(uint16_t*)val_ptr); float value = (float)rawvalue / 10; float newvalue = 0; @@ -257,17 +257,17 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { #endif // HAS_PID_HEATING #if ENABLED(BABYSTEPPING) - void DGUSScreenHandler::HandleLiveAdjustZ(DGUS_VP_Variable &var, void *val_ptr) { + void DGUSScreenHandler::handleLiveAdjustZ(DGUS_VP_Variable &var, void *val_ptr) { int16_t flag = swap16(*(uint16_t*)val_ptr), steps = flag ? -20 : 20; ExtUI::smartAdjustAxis_steps(steps, ExtUI::axis_t::Z, true); - ForceCompleteUpdate(); + forceCompleteUpdate(); } #endif #if ENABLED(DGUS_FILAMENT_LOADUNLOAD) - void DGUSScreenHandler::HandleFilamentOption(DGUS_VP_Variable &var, void *val_ptr) { + void DGUSScreenHandler::handleFilamentOption(DGUS_VP_Variable &var, void *val_ptr) { uint8_t e_temp = 0; filament_data.heated = false; uint16_t preheat_option = swap16(*(uint16_t*)val_ptr); @@ -315,7 +315,7 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { thermalManager.setTargetHotend(e_temp, ExtUI::extruder_t::E1); #endif #endif - GotoScreen(DGUSLCD_SCREEN_UTILITY); + gotoScreen(DGUS_SCREEN_UTILITY); } else { // Go to the preheat screen to show the heating progress switch (var.VP) { @@ -333,11 +333,11 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { break; #endif } - GotoScreen(DGUSLCD_SCREEN_FILAMENT_HEATING); + gotoScreen(DGUS_SCREEN_FILAMENT_HEATING); } } - void DGUSScreenHandler::HandleFilamentLoadUnload(DGUS_VP_Variable &var) { + void DGUSScreenHandler::handleFilamentLoadUnload(DGUS_VP_Variable &var) { if (filament_data.action <= 0) return; // If we close to the target temperature, we can start load or unload the filament @@ -347,14 +347,14 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { if (filament_data.action == 1) { // load filament if (!filament_data.heated) { - //GotoScreen(DGUSLCD_SCREEN_FILAMENT_LOADING); + //gotoScreen(DGUS_SCREEN_FILAMENT_LOADING); filament_data.heated = true; } movevalue = ExtUI::getAxisPosition_mm(filament_data.extruder) + movevalue; } else { // unload filament if (!filament_data.heated) { - GotoScreen(DGUSLCD_SCREEN_FILAMENT_UNLOADING); + gotoScreen(DGUS_SCREEN_FILAMENT_UNLOADING); filament_data.heated = true; } // Before unloading extrude to prevent jamming @@ -372,14 +372,14 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { #endif // DGUS_FILAMENT_LOADUNLOAD bool DGUSScreenHandler::loop() { - dgusdisplay.loop(); + dgus.loop(); const millis_t ms = millis(); static millis_t next_event_ms = 0; - if (!IsScreenComplete() || ELAPSED(ms, next_event_ms)) { + if (!isScreenComplete() || ELAPSED(ms, next_event_ms)) { next_event_ms = ms + DGUS_UPDATE_INTERVAL_MS; - UpdateScreenVPData(); + updateScreenVPData(); } #if ENABLED(SHOW_BOOTSCREEN) @@ -390,11 +390,11 @@ bool DGUSScreenHandler::loop() { if (!booted && ELAPSED(ms, BOOTSCREEN_TIMEOUT)) { booted = true; - GotoScreen(TERN0(POWER_LOSS_RECOVERY, recovery.valid()) ? DGUSLCD_SCREEN_POWER_LOSS : DGUSLCD_SCREEN_MAIN); + gotoScreen(TERN0(POWER_LOSS_RECOVERY, recovery.valid()) ? DGUS_SCREEN_POWER_LOSS : DGUS_SCREEN_MAIN); } #endif - return IsScreenComplete(); + return isScreenComplete(); } #endif // DGUS_LCD_UI_HIPRECY diff --git a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.h index 73e3527d7e7c..16c5dec408d6 100644 --- a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.h +++ b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.h @@ -26,6 +26,6 @@ typedef DGUSScreenHandler DGUSScreenHandlerClass; #if ENABLED(POWER_LOSS_RECOVERY) - #define PLR_SCREEN_RECOVER DGUSLCD_SCREEN_SDPRINTMANIPULATION - #define PLR_SCREEN_CANCEL DGUSLCD_SCREEN_STATUS + #define PLR_SCREEN_RECOVER DGUS_SCREEN_SDPRINTMANIPULATION + #define PLR_SCREEN_CANCEL DGUS_SCREEN_STATUS #endif diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp index 8dee8e26d705..2b5b6d956e2a 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp @@ -500,301 +500,301 @@ const char Updata_Time[] PROGMEM = STRING_DISTRIBUTION_DATE; const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { // Helper to detect touch events - VPHELPER(VP_SCREENCHANGE, nullptr, ScreenHandler.ScreenChangeHook, nullptr), - VPHELPER(VP_SCREENCHANGE_ASK, nullptr, ScreenHandler.ScreenChangeHookIfIdle, nullptr), + VPHELPER(VP_SCREENCHANGE, nullptr, screen.screenChangeHook, nullptr), + VPHELPER(VP_SCREENCHANGE_ASK, nullptr, screen.screenChangeHookIfIdle, nullptr), #if HAS_MEDIA - VPHELPER(VP_SCREENCHANGE_WHENSD, nullptr, ScreenHandler.ScreenChangeHookIfSD, nullptr), + VPHELPER(VP_SCREENCHANGE_WHENSD, nullptr, screen.screenChangeHookIfSD, nullptr), #endif - VPHELPER(VP_CONFIRMED, nullptr, ScreenHandler.ScreenConfirmedOK, nullptr), + VPHELPER(VP_CONFIRMED, nullptr, screen.screenConfirmedOK, nullptr), // Back Button - VPHELPER(VP_BACK_PAGE, nullptr, ScreenHandler.ScreenBackChange, nullptr), - VPHELPER(VP_TEMP_ALL_OFF, nullptr, ScreenHandler.HandleAllHeatersOff, nullptr), + VPHELPER(VP_BACK_PAGE, nullptr, screen.screenBackChange, nullptr), + VPHELPER(VP_TEMP_ALL_OFF, nullptr, screen.handleAllHeatersOff, nullptr), - VPHELPER(VP_MOVE_X, nullptr, ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Y, nullptr, ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Z, nullptr, ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_HOME_ALL, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_X, nullptr, screen.handleManualMove, nullptr), + VPHELPER(VP_MOVE_Y, nullptr, screen.handleManualMove, nullptr), + VPHELPER(VP_MOVE_Z, nullptr, screen.handleManualMove, nullptr), + VPHELPER(VP_HOME_ALL, nullptr, screen.handleManualMove, nullptr), - VPHELPER(VP_X_HOME, nullptr, ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_Y_HOME, nullptr, ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_Z_HOME, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_X_HOME, nullptr, screen.handleManualMove, nullptr), + VPHELPER(VP_Y_HOME, nullptr, screen.handleManualMove, nullptr), + VPHELPER(VP_Z_HOME, nullptr, screen.handleManualMove, nullptr), - VPHELPER(VP_MOVE_DISTANCE, &manualMoveStep, ScreenHandler.GetManualMovestep, nullptr), + VPHELPER(VP_MOVE_DISTANCE, &manualMoveStep, screen.getManualMovestep, nullptr), - VPHELPER(VP_MOTOR_LOCK_UNLOK, nullptr, ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_LEVEL_POINT, nullptr, ScreenHandler.ManualAssistLeveling, nullptr), + VPHELPER(VP_MOTOR_LOCK_UNLOK, nullptr, screen.handleManualMove, nullptr), + VPHELPER(VP_LEVEL_POINT, nullptr, screen.manualAssistLeveling, nullptr), #if ENABLED(POWER_LOSS_RECOVERY) - VPHELPER(VP_POWER_LOSS_RECOVERY, nullptr, ScreenHandler.HandlePowerLossRecovery, nullptr), + VPHELPER(VP_POWER_LOSS_RECOVERY, nullptr, screen.handlePowerLossRecovery, nullptr), #endif - VPHELPER(VP_SETTINGS, nullptr, ScreenHandler.HandleSettings, nullptr), + VPHELPER(VP_SETTINGS, nullptr, screen.handleSettings, nullptr), #if ENABLED(SINGLE_Z_CALIBRATION) - VPHELPER(VP_Z_CALIBRATE, nullptr, ScreenHandler.HandleZCalibration, nullptr), + VPHELPER(VP_Z_CALIBRATE, nullptr, screen.handleZCalibration, nullptr), #endif #if ENABLED(FIRST_LAYER_CAL) - VPHELPER(VP_Z_FIRST_LAYER_CAL, nullptr, ScreenHandler.HandleFirstLayerCal, nullptr), + VPHELPER(VP_Z_FIRST_LAYER_CAL, nullptr, screen.handleFirstLayerCal, nullptr), #endif - {.VP = VP_MARLIN_VERSION, .memadr = (void *)MarlinVersion, .size = VP_MARLIN_VERSION_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM}, + {.VP = VP_MARLIN_VERSION, .memadr = (void *)MarlinVersion, .size = VP_MARLIN_VERSION_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = screen.sendStringToDisplayPGM}, // M117 LCD String (We don't need the string in memory but "just" push it to the display on demand, hence the nullptr - {.VP = VP_M117, .memadr = nullptr, .size = VP_M117_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplay}, - {.VP = VP_MKS_H43_VERSION, .memadr = (void *)H43Version, .size = VP_MKS_H43_VERSION_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM}, - {.VP = VP_MKS_H43_UpdataVERSION, .memadr = (void *)Updata_Time, .size = VP_MKS_H43_VERSION_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM}, + {.VP = VP_M117, .memadr = nullptr, .size = VP_M117_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = screen.sendStringToDisplay}, + {.VP = VP_MKS_H43_VERSION, .memadr = (void *)H43Version, .size = VP_MKS_H43_VERSION_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = screen.sendStringToDisplayPGM}, + {.VP = VP_MKS_H43_UpdataVERSION, .memadr = (void *)Updata_Time, .size = VP_MKS_H43_VERSION_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = screen.sendStringToDisplayPGM}, // Temperature Data #if HAS_HOTEND - VPHELPER(VP_T_E0_Is, &thermalManager.temp_hotend[0].celsius, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<0>), - VPHELPER(VP_T_E0_Set, &thermalManager.temp_hotend[0].target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_Flowrate_E0, &planner.flow_percentage[ExtUI::extruder_t::E0], ScreenHandler.HandleFlowRateChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_EPos, &destination.e, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), - VPHELPER(VP_MOVE_E0, nullptr, ScreenHandler.HandleManualExtrude, nullptr), - VPHELPER(VP_E0_CONTROL, &thermalManager.temp_hotend[0].target, ScreenHandler.HandleHeaterControl, nullptr), - VPHELPER(VP_E0_STATUS, &thermalManager.temp_hotend[0].target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), + VPHELPER(VP_T_E0_Is, &thermalManager.temp_hotend[0].celsius, nullptr, screen.sendFloatAsLongValueToDisplay<0>), + VPHELPER(VP_T_E0_Set, &thermalManager.temp_hotend[0].target, screen.handleTemperatureChanged, screen.sendWordValueToDisplay), + VPHELPER(VP_Flowrate_E0, &planner.flow_percentage[ExtUI::extruder_t::E0], screen.handleFlowRateChanged, screen.sendWordValueToDisplay), + VPHELPER(VP_EPos, &destination.e, nullptr, screen.sendFloatAsLongValueToDisplay<2>), + VPHELPER(VP_MOVE_E0, nullptr, screen.handleManualExtrude, nullptr), + VPHELPER(VP_E0_CONTROL, &thermalManager.temp_hotend[0].target, screen.handleHeaterControl, nullptr), + VPHELPER(VP_E0_STATUS, &thermalManager.temp_hotend[0].target, nullptr, screen.sendHeaterStatusToDisplay), #if ENABLED(DGUS_PREHEAT_UI) - VPHELPER(VP_E0_BED_PREHEAT, nullptr, ScreenHandler.HandlePreheat, nullptr), + VPHELPER(VP_E0_BED_PREHEAT, nullptr, screen.handlePreheat, nullptr), #endif #if ENABLED(PIDTEMP) - VPHELPER(VP_E0_PID_P, &thermalManager.temp_hotend[0].pid.Kp, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_E0_PID_I, &thermalManager.temp_hotend[0].pid.Ki, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_E0_PID_D, &thermalManager.temp_hotend[0].pid.Kd, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_PID_AUTOTUNE_E0, nullptr, ScreenHandler.HandlePIDAutotune, nullptr), + VPHELPER(VP_E0_PID_P, &thermalManager.temp_hotend[0].pid.Kp, screen.handleTemperaturePIDChanged, screen.sendTemperaturePID), + VPHELPER(VP_E0_PID_I, &thermalManager.temp_hotend[0].pid.Ki, screen.handleTemperaturePIDChanged, screen.sendTemperaturePID), + VPHELPER(VP_E0_PID_D, &thermalManager.temp_hotend[0].pid.Kd, screen.handleTemperaturePIDChanged, screen.sendTemperaturePID), + VPHELPER(VP_PID_AUTOTUNE_E0, nullptr, screen.handlePIDAutotune, nullptr), #endif #if ENABLED(DGUS_FILAMENT_LOADUNLOAD) - VPHELPER(VP_LOAD_Filament, nullptr, ScreenHandler.FilamentLoad, nullptr), - VPHELPER(VP_UNLOAD_Filament, nullptr, ScreenHandler.FilamentUnLoad, nullptr), - VPHELPER(VP_Filament_distance, &distanceFilament, ScreenHandler.GetManualFilament, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_Filament_speed, &filamentSpeed_mm_s, ScreenHandler.GetManualFilamentSpeed, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_LOAD_Filament, nullptr, screen.filamentLoad, nullptr), + VPHELPER(VP_UNLOAD_Filament, nullptr, screen.filamentUnload, nullptr), + VPHELPER(VP_Filament_distance, &distanceFilament, screen.getManualFilament, screen.sendWordValueToDisplay), + VPHELPER(VP_Filament_speed, &filamentSpeed_mm_s, screen.getManualFilamentSpeed, screen.sendWordValueToDisplay), #endif #endif #if HAS_MULTI_HOTEND - VPHELPER(VP_T_E1_Is, &thermalManager.temp_hotend[1].celsius, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<0>), - VPHELPER(VP_T_E1_Set, &thermalManager.temp_hotend[1].target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_Flowrate_E1, &planner.flow_percentage[ExtUI::extruder_t::E1], ScreenHandler.HandleFlowRateChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_MOVE_E1, nullptr, ScreenHandler.HandleManualExtrude, nullptr), - VPHELPER(VP_E1_CONTROL, &thermalManager.temp_hotend[1].target, ScreenHandler.HandleHeaterControl, nullptr), - VPHELPER(VP_E1_STATUS, &thermalManager.temp_hotend[1].target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), + VPHELPER(VP_T_E1_Is, &thermalManager.temp_hotend[1].celsius, nullptr, screen.sendFloatAsLongValueToDisplay<0>), + VPHELPER(VP_T_E1_Set, &thermalManager.temp_hotend[1].target, screen.handleTemperatureChanged, screen.sendWordValueToDisplay), + VPHELPER(VP_Flowrate_E1, &planner.flow_percentage[ExtUI::extruder_t::E1], screen.handleFlowRateChanged, screen.sendWordValueToDisplay), + VPHELPER(VP_MOVE_E1, nullptr, screen.handleManualExtrude, nullptr), + VPHELPER(VP_E1_CONTROL, &thermalManager.temp_hotend[1].target, screen.handleHeaterControl, nullptr), + VPHELPER(VP_E1_STATUS, &thermalManager.temp_hotend[1].target, nullptr, screen.sendHeaterStatusToDisplay), #if ENABLED(DGUS_FILAMENT_LOADUNLOAD) - VPHELPER(VP_Filament_distance, &distanceFilament, ScreenHandler.GetManualFilament, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), - VPHELPER(VP_Filament_speed, &filamentSpeed_mm_s, ScreenHandler.GetManualFilamentSpeed, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Filament_distance, &distanceFilament, screen.getManualFilament, screen.sendFloatAsIntValueToDisplay<0>), + VPHELPER(VP_Filament_speed, &filamentSpeed_mm_s, screen.getManualFilamentSpeed, screen.sendWordValueToDisplay), #endif #if ENABLED(PIDTEMP) - VPHELPER(VP_PID_AUTOTUNE_E1, nullptr, ScreenHandler.HandlePIDAutotune, nullptr), + VPHELPER(VP_PID_AUTOTUNE_E1, nullptr, screen.handlePIDAutotune, nullptr), #endif - VPHELPER(VP_E1_FILAMENT_LOAD_UNLOAD, nullptr, ScreenHandler.HandleFilamentOption, ScreenHandler.HandleFilamentLoadUnload), + VPHELPER(VP_E1_FILAMENT_LOAD_UNLOAD, nullptr, screen.handleFilamentOption, screen.handleFilamentLoadUnload), #endif #if HAS_HEATED_BED - VPHELPER(VP_T_Bed_Is, &thermalManager.temp_bed.celsius, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<0>), - VPHELPER(VP_T_Bed_Set, &thermalManager.temp_bed.target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_BED_CONTROL, &thermalManager.temp_bed.target, ScreenHandler.HandleHeaterControl, nullptr), - VPHELPER(VP_BED_STATUS, &thermalManager.temp_bed.target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), + VPHELPER(VP_T_Bed_Is, &thermalManager.temp_bed.celsius, nullptr, screen.sendFloatAsLongValueToDisplay<0>), + VPHELPER(VP_T_Bed_Set, &thermalManager.temp_bed.target, screen.handleTemperatureChanged, screen.sendWordValueToDisplay), + VPHELPER(VP_BED_CONTROL, &thermalManager.temp_bed.target, screen.handleHeaterControl, nullptr), + VPHELPER(VP_BED_STATUS, &thermalManager.temp_bed.target, nullptr, screen.sendHeaterStatusToDisplay), #if ENABLED(PIDTEMPBED) - VPHELPER(VP_BED_PID_P, &thermalManager.temp_bed.pid.Kp, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_BED_PID_I, &thermalManager.temp_bed.pid.Ki, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_BED_PID_D, &thermalManager.temp_bed.pid.Kd, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_PID_AUTOTUNE_BED, nullptr, ScreenHandler.HandlePIDAutotune, nullptr), + VPHELPER(VP_BED_PID_P, &thermalManager.temp_bed.pid.Kp, screen.handleTemperaturePIDChanged, screen.sendTemperaturePID), + VPHELPER(VP_BED_PID_I, &thermalManager.temp_bed.pid.Ki, screen.handleTemperaturePIDChanged, screen.sendTemperaturePID), + VPHELPER(VP_BED_PID_D, &thermalManager.temp_bed.pid.Kd, screen.handleTemperaturePIDChanged, screen.sendTemperaturePID), + VPHELPER(VP_PID_AUTOTUNE_BED, nullptr, screen.handlePIDAutotune, nullptr), #endif #endif // Fan Data #if HAS_FAN #define FAN_VPHELPER(N) \ - VPHELPER(VP_Fan##N##_Percentage, &thermalManager.fan_speed[N], ScreenHandler.DGUSLCD_SetUint8, ScreenHandler.DGUSLCD_SendFanToDisplay), \ - VPHELPER(VP_FAN##N##_CONTROL, &thermalManager.fan_speed[N], ScreenHandler.HandleFanControl, nullptr), \ - VPHELPER(VP_FAN##N##_STATUS, &thermalManager.fan_speed[N], nullptr, ScreenHandler.DGUSLCD_SendFanStatusToDisplay), + VPHELPER(VP_Fan##N##_Percentage, &thermalManager.fan_speed[N], screen.setUint8, screen.sendFanToDisplay), \ + VPHELPER(VP_FAN##N##_CONTROL, &thermalManager.fan_speed[N], screen.handleFanControl, nullptr), \ + VPHELPER(VP_FAN##N##_STATUS, &thermalManager.fan_speed[N], nullptr, screen.sendFanStatusToDisplay), REPEAT(FAN_COUNT, FAN_VPHELPER) #endif // Feedrate - VPHELPER(VP_Feedrate_Percentage, &feedrate_percentage, ScreenHandler.DGUSLCD_SetValueDirectly, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Feedrate_Percentage, &feedrate_percentage, screen.setValueDirectly, screen.sendWordValueToDisplay), // Position Data - VPHELPER(VP_XPos, ¤t_position.x, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), - VPHELPER(VP_YPos, ¤t_position.y, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), - VPHELPER(VP_ZPos, ¤t_position.z, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), + VPHELPER(VP_XPos, ¤t_position.x, nullptr, screen.sendFloatAsLongValueToDisplay<2>), + VPHELPER(VP_YPos, ¤t_position.y, nullptr, screen.sendFloatAsLongValueToDisplay<2>), + VPHELPER(VP_ZPos, ¤t_position.z, nullptr, screen.sendFloatAsLongValueToDisplay<2>), // Level Point Set - VPHELPER(VP_Level_Point_One_X, &mks_corner_offsets[0].x, ScreenHandler.HandleChangeLevelPoint, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_Level_Point_One_Y, &mks_corner_offsets[0].y, ScreenHandler.HandleChangeLevelPoint, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_Level_Point_Two_X, &mks_corner_offsets[1].x, ScreenHandler.HandleChangeLevelPoint, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_Level_Point_Two_Y, &mks_corner_offsets[1].y, ScreenHandler.HandleChangeLevelPoint, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_Level_Point_Three_X, &mks_corner_offsets[2].x, ScreenHandler.HandleChangeLevelPoint, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_Level_Point_Three_Y, &mks_corner_offsets[2].y, ScreenHandler.HandleChangeLevelPoint, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_Level_Point_Four_X, &mks_corner_offsets[3].x, ScreenHandler.HandleChangeLevelPoint, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_Level_Point_Four_Y, &mks_corner_offsets[3].y, ScreenHandler.HandleChangeLevelPoint, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_Level_Point_Five_X, &mks_corner_offsets[4].x, ScreenHandler.HandleChangeLevelPoint, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_Level_Point_Five_Y, &mks_corner_offsets[4].y, ScreenHandler.HandleChangeLevelPoint, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Level_Point_One_X, &mks_corner_offsets[0].x, screen.handleChangeLevelPoint, screen.sendWordValueToDisplay), + VPHELPER(VP_Level_Point_One_Y, &mks_corner_offsets[0].y, screen.handleChangeLevelPoint, screen.sendWordValueToDisplay), + VPHELPER(VP_Level_Point_Two_X, &mks_corner_offsets[1].x, screen.handleChangeLevelPoint, screen.sendWordValueToDisplay), + VPHELPER(VP_Level_Point_Two_Y, &mks_corner_offsets[1].y, screen.handleChangeLevelPoint, screen.sendWordValueToDisplay), + VPHELPER(VP_Level_Point_Three_X, &mks_corner_offsets[2].x, screen.handleChangeLevelPoint, screen.sendWordValueToDisplay), + VPHELPER(VP_Level_Point_Three_Y, &mks_corner_offsets[2].y, screen.handleChangeLevelPoint, screen.sendWordValueToDisplay), + VPHELPER(VP_Level_Point_Four_X, &mks_corner_offsets[3].x, screen.handleChangeLevelPoint, screen.sendWordValueToDisplay), + VPHELPER(VP_Level_Point_Four_Y, &mks_corner_offsets[3].y, screen.handleChangeLevelPoint, screen.sendWordValueToDisplay), + VPHELPER(VP_Level_Point_Five_X, &mks_corner_offsets[4].x, screen.handleChangeLevelPoint, screen.sendWordValueToDisplay), + VPHELPER(VP_Level_Point_Five_Y, &mks_corner_offsets[4].y, screen.handleChangeLevelPoint, screen.sendWordValueToDisplay), // Print Progress - VPHELPER(VP_PrintProgress_Percentage, nullptr, nullptr, ScreenHandler.DGUSLCD_SendPrintProgressToDisplay), + VPHELPER(VP_PrintProgress_Percentage, nullptr, nullptr, screen.sendPrintProgressToDisplay), // LCD Control - VPHELPER(VP_LCD_BLK, &lcd_default_light, ScreenHandler.LCD_BLK_Adjust, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_LCD_BLK, &lcd_default_light, screen.lcdBLKAdjust, screen.sendWordValueToDisplay), // SD File - Back - VPHELPER(VP_SD_FileSelect_Back, nullptr, ScreenHandler.SD_FileBack, nullptr), + VPHELPER(VP_SD_FileSelect_Back, nullptr, screen.sdFileBack, nullptr), // Print Time - VPHELPER_STR(VP_PrintTime, nullptr, VP_PrintTime_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintTimeToDisplay), + VPHELPER_STR(VP_PrintTime, nullptr, VP_PrintTime_LEN, nullptr, screen.sendPrintTimeToDisplay), #if ENABLED(PRINTCOUNTER) - VPHELPER_STR(VP_PrintAccTime, nullptr, VP_PrintAccTime_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintAccTimeToDisplay), - VPHELPER_STR(VP_PrintsTotal, nullptr, VP_PrintsTotal_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintsTotalToDisplay), + VPHELPER_STR(VP_PrintAccTime, nullptr, VP_PrintAccTime_LEN, nullptr, screen.sendPrintAccTimeToDisplay), + VPHELPER_STR(VP_PrintsTotal, nullptr, VP_PrintsTotal_LEN, nullptr, screen.sendPrintsTotalToDisplay), #endif - VPHELPER(VP_X_STEP_PER_MM, &planner.settings.axis_steps_per_mm[X_AXIS], ScreenHandler.HandleStepPerMMChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), - VPHELPER(VP_Y_STEP_PER_MM, &planner.settings.axis_steps_per_mm[Y_AXIS], ScreenHandler.HandleStepPerMMChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), - VPHELPER(VP_Z_STEP_PER_MM, &planner.settings.axis_steps_per_mm[Z_AXIS], ScreenHandler.HandleStepPerMMChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), + VPHELPER(VP_X_STEP_PER_MM, &planner.settings.axis_steps_per_mm[X_AXIS], screen.handleStepPerMMChanged, screen.sendFloatAsIntValueToDisplay<0>), + VPHELPER(VP_Y_STEP_PER_MM, &planner.settings.axis_steps_per_mm[Y_AXIS], screen.handleStepPerMMChanged, screen.sendFloatAsIntValueToDisplay<0>), + VPHELPER(VP_Z_STEP_PER_MM, &planner.settings.axis_steps_per_mm[Z_AXIS], screen.handleStepPerMMChanged, screen.sendFloatAsIntValueToDisplay<0>), - VPHELPER(VP_X_MAX_SPEED, &planner.settings.max_feedrate_mm_s[X_AXIS], ScreenHandler.HandleMaxSpeedChange, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), - VPHELPER(VP_Y_MAX_SPEED, &planner.settings.max_feedrate_mm_s[Y_AXIS], ScreenHandler.HandleMaxSpeedChange, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), - VPHELPER(VP_Z_MAX_SPEED, &planner.settings.max_feedrate_mm_s[Z_AXIS], ScreenHandler.HandleMaxSpeedChange, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), + VPHELPER(VP_X_MAX_SPEED, &planner.settings.max_feedrate_mm_s[X_AXIS], screen.handleMaxSpeedChange, screen.sendFloatAsIntValueToDisplay<0>), + VPHELPER(VP_Y_MAX_SPEED, &planner.settings.max_feedrate_mm_s[Y_AXIS], screen.handleMaxSpeedChange, screen.sendFloatAsIntValueToDisplay<0>), + VPHELPER(VP_Z_MAX_SPEED, &planner.settings.max_feedrate_mm_s[Z_AXIS], screen.handleMaxSpeedChange, screen.sendFloatAsIntValueToDisplay<0>), #if HAS_HOTEND - VPHELPER(VP_E0_MAX_SPEED, &planner.settings.max_feedrate_mm_s[E_AXIS_N(0)], ScreenHandler.HandleExtruderMaxSpeedChange, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), + VPHELPER(VP_E0_MAX_SPEED, &planner.settings.max_feedrate_mm_s[E_AXIS_N(0)], screen.handleExtruderMaxSpeedChange, screen.sendFloatAsIntValueToDisplay<0>), #if HAS_MULTI_HOTEND - VPHELPER(VP_E1_MAX_SPEED, &planner.settings.max_feedrate_mm_s[E_AXIS_N(1)], ScreenHandler.HandleExtruderMaxSpeedChange, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), + VPHELPER(VP_E1_MAX_SPEED, &planner.settings.max_feedrate_mm_s[E_AXIS_N(1)], screen.handleExtruderMaxSpeedChange, screen.sendFloatAsIntValueToDisplay<0>), #endif #endif - VPHELPER(VP_X_ACC_MAX_SPEED, (uint16_t *)&planner.settings.max_acceleration_mm_per_s2[X_AXIS], ScreenHandler.HandleMaxAccChange, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_Y_ACC_MAX_SPEED, (uint16_t *)&planner.settings.max_acceleration_mm_per_s2[Y_AXIS], ScreenHandler.HandleMaxAccChange, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_Z_ACC_MAX_SPEED, (uint16_t *)&planner.settings.max_acceleration_mm_per_s2[Z_AXIS], ScreenHandler.HandleMaxAccChange, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_X_ACC_MAX_SPEED, (uint16_t *)&planner.settings.max_acceleration_mm_per_s2[X_AXIS], screen.handleMaxAccChange, screen.sendWordValueToDisplay), + VPHELPER(VP_Y_ACC_MAX_SPEED, (uint16_t *)&planner.settings.max_acceleration_mm_per_s2[Y_AXIS], screen.handleMaxAccChange, screen.sendWordValueToDisplay), + VPHELPER(VP_Z_ACC_MAX_SPEED, (uint16_t *)&planner.settings.max_acceleration_mm_per_s2[Z_AXIS], screen.handleMaxAccChange, screen.sendWordValueToDisplay), #if HAS_HOTEND - VPHELPER(VP_E0_ACC_MAX_SPEED, (uint16_t *)&planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(0)], ScreenHandler.HandleExtruderAccChange, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_E0_ACC_MAX_SPEED, (uint16_t *)&planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(0)], screen.handleExtruderAccChange, screen.sendWordValueToDisplay), #if HAS_MULTI_HOTEND - VPHELPER(VP_E1_ACC_MAX_SPEED, (uint16_t *)&planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(1)], ScreenHandler.HandleExtruderAccChange, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_E1_ACC_MAX_SPEED, (uint16_t *)&planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(1)], screen.handleExtruderAccChange, screen.sendWordValueToDisplay), #endif #endif - VPHELPER(VP_TRAVEL_SPEED, (uint16_t *)&planner.settings.travel_acceleration, ScreenHandler.HandleTravelAccChange, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), - VPHELPER(VP_FEEDRATE_MIN_SPEED, (uint16_t *)&planner.settings.min_feedrate_mm_s, ScreenHandler.HandleFeedRateMinChange, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), - VPHELPER(VP_T_F_SPEED, (uint16_t *)&planner.settings.min_travel_feedrate_mm_s, ScreenHandler.HandleMin_T_F, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), - VPHELPER(VP_ACC_SPEED, (uint16_t *)&planner.settings.acceleration, ScreenHandler.HandleAccChange, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_TRAVEL_SPEED, (uint16_t *)&planner.settings.travel_acceleration, screen.handleTravelAccChange, screen.sendFloatAsIntValueToDisplay<0>), + VPHELPER(VP_FEEDRATE_MIN_SPEED, (uint16_t *)&planner.settings.min_feedrate_mm_s, screen.handleFeedRateMinChange, screen.sendFloatAsIntValueToDisplay<0>), + VPHELPER(VP_T_F_SPEED, (uint16_t *)&planner.settings.min_travel_feedrate_mm_s, screen.handleMin_T_F, screen.sendFloatAsIntValueToDisplay<0>), + VPHELPER(VP_ACC_SPEED, (uint16_t *)&planner.settings.acceleration, screen.handleAccChange, screen.sendWordValueToDisplay), - VPHELPER(VP_X_PARK_POS, &mks_park_pos.x, ScreenHandler.GetParkPos, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_Y_PARK_POS, &mks_park_pos.y, ScreenHandler.GetParkPos, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_Z_PARK_POS, &mks_park_pos.z, ScreenHandler.GetParkPos, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_X_PARK_POS, &mks_park_pos.x, screen.getParkPos, screen.sendWordValueToDisplay), + VPHELPER(VP_Y_PARK_POS, &mks_park_pos.y, screen.getParkPos, screen.sendWordValueToDisplay), + VPHELPER(VP_Z_PARK_POS, &mks_park_pos.z, screen.getParkPos, screen.sendWordValueToDisplay), #if ENABLED(PREVENT_COLD_EXTRUSION) - VPHELPER(VP_MIN_EX_T, &thermalManager.extrude_min_temp, ScreenHandler.HandleGetExMinTemp, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_MIN_EX_T, &thermalManager.extrude_min_temp, screen.handleGetExMinTemp, screen.sendWordValueToDisplay), #endif #if ENABLED(SENSORLESS_HOMING) // TMC SENSORLESS Setting #if X_HAS_STEALTHCHOP - VPHELPER(VP_TMC_X_STEP, &tmc_step.x, ScreenHandler.TMC_ChangeConfig, ScreenHandler.DGUSLCD_SendTMCStepValue), + VPHELPER(VP_TMC_X_STEP, &tmc_step.x, screen.tmcChangeConfig, screen.sendTMCStepValue), #endif #if Y_HAS_STEALTHCHOP - VPHELPER(VP_TMC_Y_STEP, &tmc_step.y, ScreenHandler.TMC_ChangeConfig, ScreenHandler.DGUSLCD_SendTMCStepValue), + VPHELPER(VP_TMC_Y_STEP, &tmc_step.y, screen.tmcChangeConfig, screen.sendTMCStepValue), #endif #if Z_HAS_STEALTHCHOP - VPHELPER(VP_TMC_Z_STEP, &tmc_step.z, ScreenHandler.TMC_ChangeConfig, ScreenHandler.DGUSLCD_SendTMCStepValue), + VPHELPER(VP_TMC_Z_STEP, &tmc_step.z, screen.tmcChangeConfig, screen.sendTMCStepValue), #endif #endif #if HAS_TRINAMIC_CONFIG // TMC Current Setting #if AXIS_IS_TMC(X) - VPHELPER(VP_TMC_X_Current, &stepperX.val_mA, ScreenHandler.TMC_ChangeConfig, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_TMC_X_Current, &stepperX.val_mA, screen.tmcChangeConfig, screen.sendWordValueToDisplay), #endif #if AXIS_IS_TMC(Y) - VPHELPER(VP_TMC_Y_Current, &stepperY.val_mA, ScreenHandler.TMC_ChangeConfig, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_TMC_Y_Current, &stepperY.val_mA, screen.tmcChangeConfig, screen.sendWordValueToDisplay), #endif #if AXIS_IS_TMC(Z) - VPHELPER(VP_TMC_Z_Current, &stepperZ.val_mA, ScreenHandler.TMC_ChangeConfig, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_TMC_Z_Current, &stepperZ.val_mA, screen.tmcChangeConfig, screen.sendWordValueToDisplay), #endif #if AXIS_IS_TMC(E0) - VPHELPER(VP_TMC_E0_Current, &stepperE0.val_mA, ScreenHandler.TMC_ChangeConfig, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_TMC_E0_Current, &stepperE0.val_mA, screen.tmcChangeConfig, screen.sendWordValueToDisplay), #endif #if AXIS_IS_TMC(E1) - VPHELPER(VP_TMC_E1_Current, &stepperE1.val_mA, ScreenHandler.TMC_ChangeConfig, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_TMC_E1_Current, &stepperE1.val_mA, screen.tmcChangeConfig, screen.sendWordValueToDisplay), #endif #if AXIS_IS_TMC(X2) - VPHELPER(VP_TMC_X1_Current, &stepperX2.val_mA, ScreenHandler.TMC_ChangeConfig, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_TMC_X1_Current, &stepperX2.val_mA, screen.tmcChangeConfig, screen.sendWordValueToDisplay), #endif #if AXIS_IS_TMC(Y2) - VPHELPER(VP_TMC_Y1_Current, &stepperY2.val_mA, ScreenHandler.TMC_ChangeConfig, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_TMC_Y1_Current, &stepperY2.val_mA, screen.tmcChangeConfig, screen.sendWordValueToDisplay), #endif #if AXIS_IS_TMC(Z2) - VPHELPER(VP_TMC_Z1_Current, &stepperZ2.val_mA, ScreenHandler.TMC_ChangeConfig, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_TMC_Z1_Current, &stepperZ2.val_mA, screen.tmcChangeConfig, screen.sendWordValueToDisplay), #endif #endif - VPHELPER(VP_EEPROM_CTRL, nullptr, ScreenHandler.EEPROM_CTRL, nullptr), - VPHELPER(VP_LEVEL_BUTTON, nullptr, ScreenHandler.Level_Ctrl, nullptr), - VPHELPER(VP_LANGUAGE_CHANGE, nullptr, ScreenHandler.LanguageChange, nullptr), + VPHELPER(VP_EEPROM_CTRL, nullptr, screen.eepromControl, nullptr), + VPHELPER(VP_LEVEL_BUTTON, nullptr, screen.levelControl, nullptr), + VPHELPER(VP_LANGUAGE_CHANGE, nullptr, screen.languageChange, nullptr), - //VPHELPER(VP_SD_Print_LiveAdjustZ, nullptr, ScreenHandler.HandleLiveAdjustZ, nullptr), + //VPHELPER(VP_SD_Print_LiveAdjustZ, nullptr, screen.handleLiveAdjustZ, nullptr), - VPHELPER(VP_SD_Print_LiveAdjustZ_Confirm, nullptr, ScreenHandler.ZoffsetConfirm, nullptr), + VPHELPER(VP_SD_Print_LiveAdjustZ_Confirm, nullptr, screen.zOffsetConfirm, nullptr), - VPHELPER(VP_ZOffset_Distance,nullptr ,ScreenHandler.GetZoffsetDistance, nullptr), - VPHELPER(VP_MESH_LEVEL_ADJUST, nullptr, ScreenHandler.MeshLevelDistanceConfig, nullptr), - VPHELPER(VP_MESH_LEVEL_POINT,nullptr, ScreenHandler.MeshLevel,nullptr), + VPHELPER(VP_ZOffset_Distance,nullptr ,screen.getZoffsetDistance, nullptr), + VPHELPER(VP_MESH_LEVEL_ADJUST, nullptr, screen.meshLevelDistanceConfig, nullptr), + VPHELPER(VP_MESH_LEVEL_POINT,nullptr, screen.meshLevel, nullptr), #if ENABLED(PREVENT_COLD_EXTRUSION) - VPHELPER(VP_Min_EX_T_E, &thermalManager.extrude_min_temp, ScreenHandler.GetMinExtrudeTemp, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Min_EX_T_E, &thermalManager.extrude_min_temp, screen.getMinExtrudeTemp, screen.sendWordValueToDisplay), #endif - VPHELPER(VP_AutoTurnOffSw, nullptr, ScreenHandler.GetTurnOffCtrl, nullptr), + VPHELPER(VP_AutoTurnOffSw, nullptr, screen.getTurnOffCtrl, nullptr), #if HAS_HOTEND - VPHELPER(VP_E0_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(0)], ScreenHandler.HandleStepPerMMExtruderChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), + VPHELPER(VP_E0_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(0)], screen.handleStepPerMMExtruderChanged, screen.sendFloatAsIntValueToDisplay<0>), #if HAS_MULTI_HOTEND - VPHELPER(VP_E1_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(1)], ScreenHandler.HandleStepPerMMExtruderChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), + VPHELPER(VP_E1_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(1)], screen.handleStepPerMMExtruderChanged, screen.sendFloatAsIntValueToDisplay<0>), #endif #endif // SDCard File listing #if HAS_MEDIA - VPHELPER(VP_SD_FileSelected, nullptr, ScreenHandler.DGUSLCD_SD_FileSelected, nullptr), - VPHELPER(VP_SD_ScrollEvent, nullptr, ScreenHandler.DGUSLCD_SD_ScrollFilelist, nullptr), - VPHELPER(VP_SD_FileSelectConfirm, nullptr, ScreenHandler.DGUSLCD_SD_StartPrint, nullptr), - VPHELPER_STR(VP_SD_FileName0, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), - VPHELPER_STR(VP_SD_FileName1, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), - VPHELPER_STR(VP_SD_FileName2, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), - VPHELPER_STR(VP_SD_FileName3, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), - VPHELPER_STR(VP_SD_FileName4, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), - VPHELPER_STR(VP_SD_FileName5, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), - VPHELPER_STR(VP_SD_FileName6, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), - VPHELPER_STR(VP_SD_FileName7, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), - VPHELPER_STR(VP_SD_FileName8, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), - VPHELPER_STR(VP_SD_FileName9, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), - VPHELPER(VP_SD_ResumePauseAbort, nullptr, ScreenHandler.DGUSLCD_SD_ResumePauseAbort, nullptr), - VPHELPER(VP_SD_AbortPrintConfirmed, nullptr, ScreenHandler.DGUSLCD_SD_ReallyAbort, nullptr), - VPHELPER(VP_SD_Print_Setting, nullptr, ScreenHandler.DGUSLCD_SD_PrintTune, nullptr), + VPHELPER(VP_SD_FileSelected, nullptr, screen.sdFileSelected, nullptr), + VPHELPER(VP_SD_ScrollEvent, nullptr, screen.sdScrollFilelist, nullptr), + VPHELPER(VP_SD_FileSelectConfirm, nullptr, screen.sdStartPrint, nullptr), + VPHELPER_STR(VP_SD_FileName0, nullptr, VP_SD_FileName_LEN, nullptr, screen.sdSendFilename), + VPHELPER_STR(VP_SD_FileName1, nullptr, VP_SD_FileName_LEN, nullptr, screen.sdSendFilename), + VPHELPER_STR(VP_SD_FileName2, nullptr, VP_SD_FileName_LEN, nullptr, screen.sdSendFilename), + VPHELPER_STR(VP_SD_FileName3, nullptr, VP_SD_FileName_LEN, nullptr, screen.sdSendFilename), + VPHELPER_STR(VP_SD_FileName4, nullptr, VP_SD_FileName_LEN, nullptr, screen.sdSendFilename), + VPHELPER_STR(VP_SD_FileName5, nullptr, VP_SD_FileName_LEN, nullptr, screen.sdSendFilename), + VPHELPER_STR(VP_SD_FileName6, nullptr, VP_SD_FileName_LEN, nullptr, screen.sdSendFilename), + VPHELPER_STR(VP_SD_FileName7, nullptr, VP_SD_FileName_LEN, nullptr, screen.sdSendFilename), + VPHELPER_STR(VP_SD_FileName8, nullptr, VP_SD_FileName_LEN, nullptr, screen.sdSendFilename), + VPHELPER_STR(VP_SD_FileName9, nullptr, VP_SD_FileName_LEN, nullptr, screen.sdSendFilename), + VPHELPER(VP_SD_ResumePauseAbort, nullptr, screen.sdResumePauseAbort, nullptr), + VPHELPER(VP_SD_AbortPrintConfirmed, nullptr, screen.sdReallyAbort, nullptr), + VPHELPER(VP_SD_Print_Setting, nullptr, screen.sdPrintTune, nullptr), #if ENABLED(BABYSTEPPING) - VPHELPER(VP_SD_Print_LiveAdjustZ, nullptr, ScreenHandler.HandleLiveAdjustZ, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<2>), - VPHELPER(VP_ZOffset_DE_DIS, &z_offset_add, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), + VPHELPER(VP_SD_Print_LiveAdjustZ, nullptr, screen.handleLiveAdjustZ, screen.sendFloatAsIntValueToDisplay<2>), + VPHELPER(VP_ZOffset_DE_DIS, &z_offset_add, nullptr, screen.sendFloatAsLongValueToDisplay<2>), #endif #if HAS_BED_PROBE - VPHELPER(VP_OFFSET_X, &probe.offset.x, ScreenHandler.GetOffsetValue,ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), - VPHELPER(VP_OFFSET_Y, &probe.offset.y, ScreenHandler.GetOffsetValue,ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), - VPHELPER(VP_OFFSET_Z, &probe.offset.z, ScreenHandler.GetOffsetValue,ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), + VPHELPER(VP_OFFSET_X, &probe.offset.x, screen.getOffsetValue,screen.sendFloatAsLongValueToDisplay<2>), + VPHELPER(VP_OFFSET_Y, &probe.offset.y, screen.getOffsetValue,screen.sendFloatAsLongValueToDisplay<2>), + VPHELPER(VP_OFFSET_Z, &probe.offset.z, screen.getOffsetValue,screen.sendFloatAsLongValueToDisplay<2>), #endif #else - VPHELPER(VP_SD_FileSelected, nullptr, ScreenHandler.PrintReturn, nullptr), + VPHELPER(VP_SD_FileSelected, nullptr, screen.printReturn, nullptr), #endif #if ENABLED(DGUS_UI_WAITING) - VPHELPER(VP_WAITING_STATUS, nullptr, nullptr, ScreenHandler.DGUSLCD_SendWaitingStatusToDisplay), + VPHELPER(VP_WAITING_STATUS, nullptr, nullptr, screen.sendWaitingStatusToDisplay), #endif // Messages for the User, shared by the popup and the kill screen. They can't be autouploaded as we do not buffer content. - //{.VP = VP_MSGSTR1, .memadr = nullptr, .size = VP_MSGSTR1_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM}, - //{.VP = VP_MSGSTR2, .memadr = nullptr, .size = VP_MSGSTR2_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM}, - //{.VP = VP_MSGSTR3, .memadr = nullptr, .size = VP_MSGSTR3_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM}, - //{.VP = VP_MSGSTR4, .memadr = nullptr, .size = VP_MSGSTR4_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM}, - - {.VP = VP_MSGSTR1, .memadr = nullptr, .size = VP_MSGSTR1_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplay_Language}, - {.VP = VP_MSGSTR2, .memadr = nullptr, .size = VP_MSGSTR2_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplay_Language}, - {.VP = VP_MSGSTR3, .memadr = nullptr, .size = VP_MSGSTR3_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplay_Language}, - {.VP = VP_MSGSTR4, .memadr = nullptr, .size = VP_MSGSTR4_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplay_Language}, + //{.VP = VP_MSGSTR1, .memadr = nullptr, .size = VP_MSGSTR1_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = screen.sendStringToDisplayPGM}, + //{.VP = VP_MSGSTR2, .memadr = nullptr, .size = VP_MSGSTR2_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = screen.sendStringToDisplayPGM}, + //{.VP = VP_MSGSTR3, .memadr = nullptr, .size = VP_MSGSTR3_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = screen.sendStringToDisplayPGM}, + //{.VP = VP_MSGSTR4, .memadr = nullptr, .size = VP_MSGSTR4_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = screen.sendStringToDisplayPGM}, + + {.VP = VP_MSGSTR1, .memadr = nullptr, .size = VP_MSGSTR1_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = screen.sendStringToDisplay_Language}, + {.VP = VP_MSGSTR2, .memadr = nullptr, .size = VP_MSGSTR2_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = screen.sendStringToDisplay_Language}, + {.VP = VP_MSGSTR3, .memadr = nullptr, .size = VP_MSGSTR3_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = screen.sendStringToDisplay_Language}, + {.VP = VP_MSGSTR4, .memadr = nullptr, .size = VP_MSGSTR4_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = screen.sendStringToDisplay_Language}, VPHELPER(0, 0, 0, 0) // must be last entry. }; diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h index 63586e7fe517..53e57e1c65bb 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h @@ -124,21 +124,21 @@ typedef struct { extern NOZZLE_PARK_DEF nozzle_park_mks; -enum DGUSLCD_Screens : uint8_t { +enum DGUS_ScreenID : uint8_t { #if ENABLED(USE_MKS_GREEN_UI) - DGUSLCD_SCREEN_BOOT = 33, - DGUSLCD_SCREEN_MAIN = 60, - DGUSLCD_SCREEN_STATUS = 60, - DGUSLCD_SCREEN_STATUS2 = 60, - DGUSLCD_SCREEN_PREHEAT = 18, - DGUSLCD_SCREEN_POWER_LOSS = 100, - DGUSLCD_SCREEN_MANUALMOVE = 192, - DGUSLCD_SCREEN_UTILITY = 120, - DGUSLCD_SCREEN_FILAMENT_UNLOADING = 158, - DGUSLCD_SCREEN_SDFILELIST = 15, - DGUSLCD_SCREEN_SDPRINTMANIPULATION = 15, - DGUSLCD_SCREEN_SDPRINTTUNE = 17, + DGUS_SCREEN_BOOT = 33, + DGUS_SCREEN_MAIN = 60, + DGUS_SCREEN_STATUS = 60, + DGUS_SCREEN_STATUS2 = 60, + DGUS_SCREEN_PREHEAT = 18, + DGUS_SCREEN_POWER_LOSS = 100, + DGUS_SCREEN_MANUALMOVE = 192, + DGUS_SCREEN_UTILITY = 120, + DGUS_SCREEN_FILAMENT_UNLOADING = 158, + DGUS_SCREEN_SDFILELIST = 15, + DGUS_SCREEN_SDPRINTMANIPULATION = 15, + DGUS_SCREEN_SDPRINTTUNE = 17, MKSLCD_SCREEN_BOOT = 33, MKSLCD_SCREEN_HOME = 60, // MKS main page @@ -178,19 +178,19 @@ enum DGUSLCD_Screens : uint8_t { #else - DGUSLCD_SCREEN_BOOT = 120, - DGUSLCD_SCREEN_MAIN = 1, + DGUS_SCREEN_BOOT = 120, + DGUS_SCREEN_MAIN = 1, - DGUSLCD_SCREEN_STATUS = 1, - DGUSLCD_SCREEN_STATUS2 = 1, - DGUSLCD_SCREEN_PREHEAT = 18, - DGUSLCD_SCREEN_POWER_LOSS = 100, - DGUSLCD_SCREEN_MANUALMOVE = 192, - DGUSLCD_SCREEN_UTILITY = 120, - DGUSLCD_SCREEN_FILAMENT_UNLOADING = 158, - DGUSLCD_SCREEN_SDFILELIST = 15, - DGUSLCD_SCREEN_SDPRINTMANIPULATION = 15, - DGUSLCD_SCREEN_SDPRINTTUNE = 17, + DGUS_SCREEN_STATUS = 1, + DGUS_SCREEN_STATUS2 = 1, + DGUS_SCREEN_PREHEAT = 18, + DGUS_SCREEN_POWER_LOSS = 100, + DGUS_SCREEN_MANUALMOVE = 192, + DGUS_SCREEN_UTILITY = 120, + DGUS_SCREEN_FILAMENT_UNLOADING = 158, + DGUS_SCREEN_SDFILELIST = 15, + DGUS_SCREEN_SDPRINTMANIPULATION = 15, + DGUS_SCREEN_SDPRINTTUNE = 17, MKSLCD_SCREEN_BOOT = 0, MKSLCD_SCREEN_HOME = 1, // MKS main page @@ -234,11 +234,11 @@ enum DGUSLCD_Screens : uint8_t { #endif - DGUSLCD_SCREEN_CONFIRM = 240, - DGUSLCD_SCREEN_KILL = 250, ///< Kill Screen. Must always be 250 (to be able to display "Error wrong LCD Version") - DGUSLCD_SCREEN_WAITING = 251, - DGUSLCD_SCREEN_POPUP = 252, ///< special target, popup screen will also return this code to say "return to previous screen" - DGUSLCD_SCREEN_UNUSED = 255 + DGUS_SCREEN_CONFIRM = 240, + DGUS_SCREEN_KILL = 250, ///< Kill Screen. Must always be 250 (to be able to display "Error wrong LCD Version") + DGUS_SCREEN_WAITING = 251, + DGUS_SCREEN_POPUP = 252, ///< special target, popup screen will also return this code to say "return to previous screen" + DGUS_SCREEN_UNUSED = 255 }; diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp index ad89a715c362..4c1995cebc24 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp @@ -56,20 +56,20 @@ MKS_Language mks_language_index; // Initialized by settings.load() #if 0 void DGUSScreenHandlerMKS::sendinfoscreen_ch(const uint16_t *line1, const uint16_t *line2, const uint16_t *line3, const uint16_t *line4) { - dgusdisplay.WriteVariable(VP_MSGSTR1, line1, 32, true); - dgusdisplay.WriteVariable(VP_MSGSTR2, line2, 32, true); - dgusdisplay.WriteVariable(VP_MSGSTR3, line3, 32, true); - dgusdisplay.WriteVariable(VP_MSGSTR4, line4, 32, true); + dgus.writeVariable(VP_MSGSTR1, line1, 32, true); + dgus.writeVariable(VP_MSGSTR2, line2, 32, true); + dgus.writeVariable(VP_MSGSTR3, line3, 32, true); + dgus.writeVariable(VP_MSGSTR4, line4, 32, true); } void DGUSScreenHandlerMKS::sendinfoscreen_en(PGM_P const line1, PGM_P const line2, PGM_P const line3, PGM_P const line4) { - dgusdisplay.WriteVariable(VP_MSGSTR1, line1, 32, true); - dgusdisplay.WriteVariable(VP_MSGSTR2, line2, 32, true); - dgusdisplay.WriteVariable(VP_MSGSTR3, line3, 32, true); - dgusdisplay.WriteVariable(VP_MSGSTR4, line4, 32, true); + dgus.writeVariable(VP_MSGSTR1, line1, 32, true); + dgus.writeVariable(VP_MSGSTR2, line2, 32, true); + dgus.writeVariable(VP_MSGSTR3, line3, 32, true); + dgus.writeVariable(VP_MSGSTR4, line4, 32, true); } -void DGUSScreenHandlerMKS::sendinfoscreen(const void *line1, const void *line2, const void *line3, const void *line4, uint16_t language) { +void DGUSScreenHandlerMKS::sendInfoScreen(const void *line1, const void *line2, const void *line3, const void *line4, uint16_t language) { if (language == MKS_English) DGUSScreenHandlerMKS::sendinfoscreen_en((char *)line1, (char *)line2, (char *)line3, (char *)line4); else if (language == MKS_SimpleChinese) @@ -78,78 +78,78 @@ void DGUSScreenHandlerMKS::sendinfoscreen(const void *line1, const void *line2, #endif -void DGUSScreenHandlerMKS::DGUSLCD_SendFanToDisplay(DGUS_VP_Variable &var) { +void DGUSScreenHandlerMKS::sendFanToDisplay(DGUS_VP_Variable &var) { if (var.memadr) { uint16_t tmp = *(uint8_t *) var.memadr; // +1 -> avoid rounding issues for the display. // tmp = map(tmp, 0, 255, 0, 100); - dgusdisplay.WriteVariable(var.VP, tmp); + dgus.writeVariable(var.VP, tmp); } } -void DGUSScreenHandlerMKS::DGUSLCD_SendBabyStepToDisplay(DGUS_VP_Variable &var) { +void DGUSScreenHandlerMKS::sendBabyStepToDisplay(DGUS_VP_Variable &var) { float value = current_position.z; value *= cpow(10, 2); - dgusdisplay.WriteVariable(VP_SD_Print_Baby, (uint16_t)value); + dgus.writeVariable(VP_SD_Print_Baby, (uint16_t)value); } -void DGUSScreenHandlerMKS::DGUSLCD_SendPrintTimeToDisplay(DGUS_VP_Variable &var) { +void DGUSScreenHandlerMKS::sendPrintTimeToDisplay(DGUS_VP_Variable &var) { duration_t elapsed = print_job_timer.duration(); uint32_t time = elapsed.value; - dgusdisplay.WriteVariable(VP_PrintTime_H, uint16_t(time / 3600)); - dgusdisplay.WriteVariable(VP_PrintTime_M, uint16_t(time % 3600 / 60)); - dgusdisplay.WriteVariable(VP_PrintTime_S, uint16_t((time % 3600) % 60)); + dgus.writeVariable(VP_PrintTime_H, uint16_t(time / 3600)); + dgus.writeVariable(VP_PrintTime_M, uint16_t(time % 3600 / 60)); + dgus.writeVariable(VP_PrintTime_S, uint16_t((time % 3600) % 60)); } -void DGUSScreenHandlerMKS::DGUSLCD_SetUint8(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandlerMKS::setUint8(DGUS_VP_Variable &var, void *val_ptr) { if (var.memadr) { const uint16_t value = BE16_P(val_ptr); *(uint8_t*)var.memadr = map(constrain(value, 0, 255), 0, 255, 0, 255); } } -void DGUSScreenHandlerMKS::DGUSLCD_SendGbkToDisplay(DGUS_VP_Variable &var) { +void DGUSScreenHandlerMKS::sendGbkToDisplay(DGUS_VP_Variable &var) { uint16_t *tmp = (uint16_t*) var.memadr; - dgusdisplay.WriteVariable(var.VP, tmp, var.size, true); + dgus.writeVariable(var.VP, tmp, var.size, true); } -void DGUSScreenHandlerMKS::DGUSLCD_SendStringToDisplay_Language(DGUS_VP_Variable &var) { +void DGUSScreenHandlerMKS::sendStringToDisplay_Language(DGUS_VP_Variable &var) { if (mks_language_index == MKS_English) { char *tmp = (char*) var.memadr; - dgusdisplay.WriteVariable(var.VP, tmp, var.size, true); + dgus.writeVariable(var.VP, tmp, var.size, true); } else if (mks_language_index == MKS_SimpleChinese) { uint16_t *tmp = (uint16_t *)var.memadr; - dgusdisplay.WriteVariable(var.VP, tmp, var.size, true); + dgus.writeVariable(var.VP, tmp, var.size, true); } } -void DGUSScreenHandlerMKS::DGUSLCD_SendTMCStepValue(DGUS_VP_Variable &var) { +void DGUSScreenHandlerMKS::sendTMCStepValue(DGUS_VP_Variable &var) { #if ENABLED(SENSORLESS_HOMING) #if X_HAS_STEALTHCHOP tmc_step.x = stepperX.homing_threshold(); - dgusdisplay.WriteVariable(var.VP, *(int16_t*)var.memadr); + dgus.writeVariable(var.VP, *(int16_t*)var.memadr); #endif #if Y_HAS_STEALTHCHOP tmc_step.y = stepperY.homing_threshold(); - dgusdisplay.WriteVariable(var.VP, *(int16_t*)var.memadr); + dgus.writeVariable(var.VP, *(int16_t*)var.memadr); #endif #if Z_HAS_STEALTHCHOP tmc_step.z = stepperZ.homing_threshold(); - dgusdisplay.WriteVariable(var.VP, *(int16_t*)var.memadr); + dgus.writeVariable(var.VP, *(int16_t*)var.memadr); #endif #endif } #if HAS_MEDIA - void DGUSScreenHandler::DGUSLCD_SD_FileSelected(DGUS_VP_Variable &var, void *val_ptr) { + void DGUSScreenHandler::sdFileSelected(DGUS_VP_Variable &var, void *val_ptr) { uint16_t touched_nr = (int16_t)BE16_P(val_ptr) + top_file; if (touched_nr != 0x0F && touched_nr > filelist.count()) return; if (!filelist.seek(touched_nr) && touched_nr != 0x0F) return; if (touched_nr == 0x0F) { if (filelist.isAtRootDir()) - GotoScreen(DGUSLCD_SCREEN_MAIN); + gotoScreen(DGUS_SCREEN_MAIN); else filelist.upDir(); return; @@ -158,28 +158,28 @@ void DGUSScreenHandlerMKS::DGUSLCD_SendTMCStepValue(DGUS_VP_Variable &var) { if (filelist.isDir()) { filelist.changeDir(filelist.filename()); top_file = 0; - ForceCompleteUpdate(); + forceCompleteUpdate(); return; } #if ENABLED(DGUS_PRINT_FILENAME) // Send print filename - dgusdisplay.WriteVariable(VP_SD_Print_Filename, filelist.filename(), VP_SD_FileName_LEN, true); + dgus.writeVariable(VP_SD_Print_Filename, filelist.filename(), VP_SD_FileName_LEN, true); #endif // Setup Confirmation screen file_to_print = touched_nr; - GotoScreen(MKSLCD_SCREEN_PRINT_CONFIRM); + gotoScreen(MKSLCD_SCREEN_PRINT_CONFIRM); } - void DGUSScreenHandler::DGUSLCD_SD_StartPrint(DGUS_VP_Variable &var, void *val_ptr) { + void DGUSScreenHandler::sdStartPrint(DGUS_VP_Variable &var, void *val_ptr) { if (!filelist.seek(file_to_print)) return; ExtUI::printFile(filelist.shortFilename()); - GotoScreen(MKSLCD_SCREEN_PRINT); + gotoScreen(MKSLCD_SCREEN_PRINT); z_offset_add = 0; } - void DGUSScreenHandler::DGUSLCD_SD_ResumePauseAbort(DGUS_VP_Variable &var, void *val_ptr) { + void DGUSScreenHandler::sdResumePauseAbort(DGUS_VP_Variable &var, void *val_ptr) { if (!ExtUI::isPrintingFromMedia()) return; // avoid race condition when user stays in this menu and printer finishes. switch (BE16_P(val_ptr)) { @@ -187,13 +187,13 @@ void DGUSScreenHandlerMKS::DGUSLCD_SendTMCStepValue(DGUS_VP_Variable &var) { auto cs = getCurrentScreen(); if (runout_mks.runout_status != RUNOUT_WAITING_STATUS && runout_mks.runout_status != UNRUNOUT_STATUS) { if (cs == MKSLCD_SCREEN_PRINT || cs == MKSLCD_SCREEN_PAUSE) - GotoScreen(MKSLCD_SCREEN_PAUSE); + gotoScreen(MKSLCD_SCREEN_PAUSE); return; } else runout_mks.runout_status = UNRUNOUT_STATUS; - GotoScreen(MKSLCD_SCREEN_PRINT); + gotoScreen(MKSLCD_SCREEN_PRINT); if (ExtUI::isPrintingFromMediaPaused()) { nozzle_park_mks.print_pause_start_flag = 0; @@ -203,7 +203,7 @@ void DGUSScreenHandlerMKS::DGUSLCD_SendTMCStepValue(DGUS_VP_Variable &var) { } break; case 1: // Pause - GotoScreen(MKSLCD_SCREEN_PAUSE); + gotoScreen(MKSLCD_SCREEN_PAUSE); if (!ExtUI::isPrintingFromMediaPaused()) { nozzle_park_mks.print_pause_start_flag = 1; nozzle_park_mks.blstatus = true; @@ -213,12 +213,12 @@ void DGUSScreenHandlerMKS::DGUSLCD_SendTMCStepValue(DGUS_VP_Variable &var) { break; case 2: // Abort - HandleUserConfirmationPopUp(VP_SD_AbortPrintConfirmed, nullptr, PSTR("Abort printing"), filelist.filename(), PSTR("?"), true, true, false, true); + handleUserConfirmationPopUp(VP_SD_AbortPrintConfirmed, nullptr, PSTR("Abort printing"), filelist.filename(), PSTR("?"), true, true, false, true); break; } } - void DGUSScreenHandler::DGUSLCD_SD_SendFilename(DGUS_VP_Variable& var) { + void DGUSScreenHandler::sdSendFilename(DGUS_VP_Variable& var) { uint16_t target_line = (var.VP - VP_SD_FileName0) / VP_SD_FileName_LEN; if (target_line > DGUS_SD_FILESPERSCREEN) return; char tmpfilename[VP_SD_FileName_LEN + 1] = ""; @@ -229,50 +229,50 @@ void DGUSScreenHandlerMKS::DGUSLCD_SendTMCStepValue(DGUS_VP_Variable &var) { snprintf_P(tmpfilename, VP_SD_FileName_LEN, PSTR("%s%c"), filelist.filename(), filelist.isDir() ? '/' : 0); // snprintf_P(tmpfilename, VP_SD_FileName_LEN, PSTR("%s"), filelist.filename()); dir_icon_val = filelist.isDir() ? 0 : 1; } - DGUSLCD_SendStringToDisplay(var); + sendStringToDisplay(var); - dgusdisplay.WriteVariable(VP_File_Pictutr0 + target_line * 2, dir_icon_val); + dgus.writeVariable(VP_File_Pictutr0 + target_line * 2, dir_icon_val); } - void DGUSScreenHandler::SDCardInserted() { + void DGUSScreenHandler::sdCardInserted() { top_file = 0; filelist.refresh(); auto cs = getCurrentScreen(); - if (cs == DGUSLCD_SCREEN_MAIN || cs == DGUSLCD_SCREEN_STATUS) - GotoScreen(MKSLCD_SCREEN_CHOOSE_FILE); + if (cs == DGUS_SCREEN_MAIN || cs == DGUS_SCREEN_STATUS) + gotoScreen(MKSLCD_SCREEN_CHOOSE_FILE); } - void DGUSScreenHandler::SDCardRemoved() { - if (current_screen == DGUSLCD_SCREEN_SDFILELIST - || (current_screen == DGUSLCD_SCREEN_CONFIRM && (ConfirmVP == VP_SD_AbortPrintConfirmed || ConfirmVP == VP_SD_FileSelectConfirm)) - || current_screen == DGUSLCD_SCREEN_SDPRINTMANIPULATION + void DGUSScreenHandler::sdCardRemoved() { + if (current_screenID == DGUS_SCREEN_SDFILELIST + || (current_screenID == DGUS_SCREEN_CONFIRM && (confirmVP == VP_SD_AbortPrintConfirmed || confirmVP == VP_SD_FileSelectConfirm)) + || current_screenID == DGUS_SCREEN_SDPRINTMANIPULATION ) filelist.refresh(); } - void DGUSScreenHandlerMKS::SDPrintingFinished() { + void DGUSScreenHandlerMKS::sdPrintingFinished() { if (DGUSAutoTurnOff) { queue.exhaust(); gcode.process_subcommands_now(F("M81")); } - GotoScreen(MKSLCD_SCREEN_PrintDone); + gotoScreen(MKSLCD_SCREEN_PrintDone); } #else - void DGUSScreenHandlerMKS::PrintReturn(DGUS_VP_Variable& var, void *val_ptr) { + void DGUSScreenHandlerMKS::printReturn(DGUS_VP_Variable& var, void *val_ptr) { const uint16_t value = BE16_P(val_ptr); - if (value == 0x0F) GotoScreen(DGUSLCD_SCREEN_MAIN); + if (value == 0x0F) gotoScreen(DGUS_SCREEN_MAIN); } #endif // HAS_MEDIA -void DGUSScreenHandler::ScreenChangeHook(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandler::screenChangeHook(DGUS_VP_Variable &var, void *val_ptr) { uint8_t *tmp = (uint8_t*)val_ptr; // The keycode in target is coded as , so 0x0100A means - // from screen 1 (main) to 10 (temperature). DGUSLCD_SCREEN_POPUP is special, + // from screen 1 (main) to 10 (temperature). DGUS_SCREEN_POPUP is special, // meaning "return to previous screen" - DGUSLCD_Screens target = (DGUSLCD_Screens)tmp[1]; + DGUS_ScreenID target = (DGUS_ScreenID)tmp[1]; - // when the dgus had reboot, it will enter the DGUSLCD_SCREEN_MAIN page, + // when the dgus had reboot, it will enter the DGUS_SCREEN_MAIN page, // so user can change any page to use this function, an it will check // if robin nano is printing. when it is, dgus will enter the printing // page to continue print; @@ -283,41 +283,41 @@ void DGUSScreenHandler::ScreenChangeHook(DGUS_VP_Variable &var, void *val_ptr) { // ) { // } // else - // GotoScreen(MKSLCD_SCREEN_PRINT); + // gotoScreen(MKSLCD_SCREEN_PRINT); // return; //} - if (target == DGUSLCD_SCREEN_POPUP) { - SetupConfirmAction(ExtUI::setUserConfirmed); + if (target == DGUS_SCREEN_POPUP) { + setupConfirmAction(ExtUI::setUserConfirmed); // Special handling for popup is to return to previous menu - if (current_screen == DGUSLCD_SCREEN_POPUP && confirm_action_cb) confirm_action_cb(); - PopToOldScreen(); + if (current_screenID == DGUS_SCREEN_POPUP && confirm_action_cb) confirm_action_cb(); + popToOldScreen(); return; } - UpdateNewScreen(target); + updateNewScreen(target); #ifdef DEBUG_DGUSLCD - if (!DGUSLCD_FindScreenVPMapList(target)) DEBUG_ECHOLNPGM("WARNING: No screen Mapping found for ", target); + if (!findScreenVPMapList(target)) DEBUG_ECHOLNPGM("WARNING: No screen Mapping found for ", target); #endif } -void DGUSScreenHandlerMKS::ScreenBackChange(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandlerMKS::screenBackChange(DGUS_VP_Variable &var, void *val_ptr) { const uint16_t target = BE16_P(val_ptr); switch (target) { } } -void DGUSScreenHandlerMKS::ZoffsetConfirm(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandlerMKS::zOffsetConfirm(DGUS_VP_Variable &var, void *val_ptr) { settings.save(); if (printJobOngoing()) - GotoScreen(MKSLCD_SCREEN_PRINT); + gotoScreen(MKSLCD_SCREEN_PRINT); else if (print_job_timer.isPaused) - GotoScreen(MKSLCD_SCREEN_PAUSE); + gotoScreen(MKSLCD_SCREEN_PAUSE); } -void DGUSScreenHandlerMKS::GetTurnOffCtrl(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandlerMKS::getTurnOffCtrl(DGUS_VP_Variable &var, void *val_ptr) { const uint16_t value = BE16_P(val_ptr); switch (value) { case 0 ... 1: DGUSAutoTurnOff = (bool)value; break; @@ -325,14 +325,14 @@ void DGUSScreenHandlerMKS::GetTurnOffCtrl(DGUS_VP_Variable &var, void *val_ptr) } } -void DGUSScreenHandlerMKS::GetMinExtrudeTemp(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandlerMKS::getMinExtrudeTemp(DGUS_VP_Variable &var, void *val_ptr) { const uint16_t value = BE16_P(val_ptr); TERN_(PREVENT_COLD_EXTRUSION, thermalManager.extrude_min_temp = value); mks_min_extrusion_temp = value; settings.save(); } -void DGUSScreenHandlerMKS::GetZoffsetDistance(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandlerMKS::getZoffsetDistance(DGUS_VP_Variable &var, void *val_ptr) { const uint16_t value = BE16_P(val_ptr); float val_distance = 0; switch (value) { @@ -345,29 +345,29 @@ void DGUSScreenHandlerMKS::GetZoffsetDistance(DGUS_VP_Variable &var, void *val_p ZOffset_distance = val_distance; } -void DGUSScreenHandlerMKS::GetManualMovestep(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandlerMKS::getManualMovestep(DGUS_VP_Variable &var, void *val_ptr) { *(uint16_t *)var.memadr = BE16_P(val_ptr); } -void DGUSScreenHandlerMKS::EEPROM_CTRL(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandlerMKS::eepromControl(DGUS_VP_Variable &var, void *val_ptr) { const uint16_t eep_flag = BE16_P(val_ptr); switch (eep_flag) { case 0: settings.save(); settings.load(); // load eeprom data to check the data is right - GotoScreen(MKSLCD_SCREEN_EEP_Config); + gotoScreen(MKSLCD_SCREEN_EEP_Config); break; case 1: settings.reset(); - GotoScreen(MKSLCD_SCREEN_EEP_Config); + gotoScreen(MKSLCD_SCREEN_EEP_Config); break; default: break; } } -void DGUSScreenHandlerMKS::Z_offset_select(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandlerMKS::zOffsetSelect(DGUS_VP_Variable &var, void *val_ptr) { const uint16_t z = BE16_P(val_ptr); switch (z) { case 0: Z_distance = 0.01; break; @@ -377,7 +377,7 @@ void DGUSScreenHandlerMKS::Z_offset_select(DGUS_VP_Variable &var, void *val_ptr) } } -void DGUSScreenHandlerMKS::GetOffsetValue(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandlerMKS::getOffsetValue(DGUS_VP_Variable &var, void *val_ptr) { #if HAS_BED_PROBE const int32_t value = BE32_P(val_ptr); @@ -393,21 +393,21 @@ void DGUSScreenHandlerMKS::GetOffsetValue(DGUS_VP_Variable &var, void *val_ptr) #endif } -void DGUSScreenHandlerMKS::LanguageChange(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandlerMKS::languageChange(DGUS_VP_Variable &var, void *val_ptr) { const uint16_t lag_flag = BE16_P(val_ptr); switch (lag_flag) { case MKS_SimpleChinese: - DGUS_LanguageDisplay(MKS_SimpleChinese); + languageDisplay(MKS_SimpleChinese); mks_language_index = MKS_SimpleChinese; - dgusdisplay.WriteVariable(VP_LANGUAGE_CHANGE1, (uint8_t)MKS_Language_Choose); - dgusdisplay.WriteVariable(VP_LANGUAGE_CHANGE2, (uint8_t)MKS_Language_NoChoose); + dgus.writeVariable(VP_LANGUAGE_CHANGE1, (uint8_t)MKS_Language_Choose); + dgus.writeVariable(VP_LANGUAGE_CHANGE2, (uint8_t)MKS_Language_NoChoose); settings.save(); break; case MKS_English: - DGUS_LanguageDisplay(MKS_English); + languageDisplay(MKS_English); mks_language_index = MKS_English; - dgusdisplay.WriteVariable(VP_LANGUAGE_CHANGE1, (uint8_t)MKS_Language_NoChoose); - dgusdisplay.WriteVariable(VP_LANGUAGE_CHANGE2, (uint8_t)MKS_Language_Choose); + dgus.writeVariable(VP_LANGUAGE_CHANGE1, (uint8_t)MKS_Language_NoChoose); + dgus.writeVariable(VP_LANGUAGE_CHANGE2, (uint8_t)MKS_Language_Choose); settings.save(); break; default: break; @@ -418,7 +418,7 @@ void DGUSScreenHandlerMKS::LanguageChange(DGUS_VP_Variable &var, void *val_ptr) grid_count_t mesh_point_count = GRID_MAX_POINTS; #endif -void DGUSScreenHandlerMKS::Level_Ctrl(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandlerMKS::levelControl(DGUS_VP_Variable &var, void *val_ptr) { #if ENABLED(MESH_BED_LEVELING) auto cs = getCurrentScreen(); #endif @@ -440,32 +440,32 @@ void DGUSScreenHandlerMKS::Level_Ctrl(DGUS_VP_Variable &var, void *val_ptr) { if (mks_language_index == MKS_English) { const char level_buf_en[] = "Start Level"; - dgusdisplay.WriteVariable(VP_AutoLevel_1_Dis, level_buf_en, 32, true); + dgus.writeVariable(VP_AutoLevel_1_Dis, level_buf_en, 32, true); } else if (mks_language_index == MKS_SimpleChinese) { const uint16_t level_buf_ch[] = {0xAABF, 0xBCCA, 0xF7B5, 0xBDC6, 0x2000}; - dgusdisplay.WriteVariable(VP_AutoLevel_1_Dis, level_buf_ch, 32, true); + dgus.writeVariable(VP_AutoLevel_1_Dis, level_buf_ch, 32, true); } cs = getCurrentScreen(); - if (cs != MKSLCD_AUTO_LEVEL) GotoScreen(MKSLCD_AUTO_LEVEL); + if (cs != MKSLCD_AUTO_LEVEL) gotoScreen(MKSLCD_AUTO_LEVEL); #else - GotoScreen(MKSLCD_SCREEN_LEVEL); + gotoScreen(MKSLCD_SCREEN_LEVEL); #endif break; case 1: soft_endstop._enabled = true; - GotoScreen(MKSLCD_SCREEM_TOOL); + gotoScreen(MKSLCD_SCREEM_TOOL); break; default: break; } } -void DGUSScreenHandlerMKS::MeshLevelDistanceConfig(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandlerMKS::meshLevelDistanceConfig(DGUS_VP_Variable &var, void *val_ptr) { const uint16_t mesh_dist = BE16_P(val_ptr); switch (mesh_dist) { case 0: mesh_adj_distance = 0.01; break; @@ -475,7 +475,7 @@ void DGUSScreenHandlerMKS::MeshLevelDistanceConfig(DGUS_VP_Variable &var, void * } } -void DGUSScreenHandlerMKS::MeshLevel(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandlerMKS::meshLevel(DGUS_VP_Variable &var, void *val_ptr) { #if ENABLED(MESH_BED_LEVELING) const uint16_t mesh_val = BE16_P(val_ptr); // static uint8_t a_first_level = 1; @@ -524,11 +524,11 @@ void DGUSScreenHandlerMKS::MeshLevel(DGUS_VP_Variable &var, void *val_ptr) { if (mks_language_index == MKS_English) { const char level_buf_en1[] = "Next Point"; - dgusdisplay.WriteVariable(VP_AutoLevel_1_Dis, level_buf_en1, 32, true); + dgus.writeVariable(VP_AutoLevel_1_Dis, level_buf_en1, 32, true); } else if (mks_language_index == MKS_SimpleChinese) { const uint16_t level_buf_ch1[] = {0xC2CF, 0xBBD2, 0xE3B5, 0x2000}; - dgusdisplay.WriteVariable(VP_AutoLevel_1_Dis, level_buf_ch1, 32, true); + dgus.writeVariable(VP_AutoLevel_1_Dis, level_buf_ch1, 32, true); } } else if (mesh_point_count > 1) { // ε€’ζ•°η¬¬δΊŒδΈͺη‚Ή @@ -536,11 +536,11 @@ void DGUSScreenHandlerMKS::MeshLevel(DGUS_VP_Variable &var, void *val_ptr) { mesh_point_count--; if (mks_language_index == MKS_English) { const char level_buf_en2[] = "Next Point"; - dgusdisplay.WriteVariable(VP_AutoLevel_1_Dis, level_buf_en2, 32, true); + dgus.writeVariable(VP_AutoLevel_1_Dis, level_buf_en2, 32, true); } else if (mks_language_index == MKS_SimpleChinese) { const uint16_t level_buf_ch2[] = {0xC2CF, 0xBBD2, 0xE3B5, 0x2000}; - dgusdisplay.WriteVariable(VP_AutoLevel_1_Dis, level_buf_ch2, 32, true); + dgus.writeVariable(VP_AutoLevel_1_Dis, level_buf_ch2, 32, true); } } else if (mesh_point_count == 1) { @@ -548,11 +548,11 @@ void DGUSScreenHandlerMKS::MeshLevel(DGUS_VP_Variable &var, void *val_ptr) { mesh_point_count--; if (mks_language_index == MKS_English) { const char level_buf_en2[] = "Leveling Done"; - dgusdisplay.WriteVariable(VP_AutoLevel_1_Dis, level_buf_en2, 32, true); + dgus.writeVariable(VP_AutoLevel_1_Dis, level_buf_en2, 32, true); } else if (mks_language_index == MKS_SimpleChinese) { const uint16_t level_buf_ch2[] = {0xF7B5, 0xBDC6, 0xEACD, 0xC9B3, 0x2000}; - dgusdisplay.WriteVariable(VP_AutoLevel_1_Dis, level_buf_ch2, 32, true); + dgus.writeVariable(VP_AutoLevel_1_Dis, level_buf_ch2, 32, true); } settings.save(); } @@ -560,7 +560,7 @@ void DGUSScreenHandlerMKS::MeshLevel(DGUS_VP_Variable &var, void *val_ptr) { mesh_point_count = GRID_MAX_POINTS; soft_endstop._enabled = true; settings.save(); - GotoScreen(MKSLCD_SCREEM_TOOL); + gotoScreen(MKSLCD_SCREEM_TOOL); } break; @@ -570,19 +570,19 @@ void DGUSScreenHandlerMKS::MeshLevel(DGUS_VP_Variable &var, void *val_ptr) { #endif // MESH_BED_LEVELING } -void DGUSScreenHandlerMKS::SD_FileBack(DGUS_VP_Variable&, void*) { - GotoScreen(MKSLCD_SCREEN_HOME); +void DGUSScreenHandlerMKS::sdFileBack(DGUS_VP_Variable&, void*) { + gotoScreen(MKSLCD_SCREEN_HOME); } -void DGUSScreenHandlerMKS::LCD_BLK_Adjust(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandlerMKS::lcdBLKAdjust(DGUS_VP_Variable &var, void *val_ptr) { const uint16_t lcd_val = BE16_P(val_ptr); lcd_default_light = constrain(lcd_val, 10, 100); const uint16_t lcd_data[2] = { lcd_default_light, lcd_default_light }; - dgusdisplay.WriteVariable(0x0082, &lcd_data, 5, true); + dgus.writeVariable(0x0082, &lcd_data, 5, true); } -void DGUSScreenHandlerMKS::ManualAssistLeveling(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandlerMKS::manualAssistLeveling(DGUS_VP_Variable &var, void *val_ptr) { const int16_t point_val = BE16_P(val_ptr); // Insist on leveling first time at this screen @@ -635,8 +635,8 @@ void DGUSScreenHandlerMKS::ManualAssistLeveling(DGUS_VP_Variable &var, void *val #define mks_min(a, b) ((a) < (b)) ? (a) : (b) #define mks_max(a, b) ((a) > (b)) ? (a) : (b) -void DGUSScreenHandlerMKS::TMC_ChangeConfig(DGUS_VP_Variable &var, void *val_ptr) { - #if EITHER(HAS_TRINAMIC_CONFIG, HAS_STEALTHCHOP) +void DGUSScreenHandlerMKS::tmcChangeConfig(DGUS_VP_Variable &var, void *val_ptr) { + #if ANY(HAS_TRINAMIC_CONFIG, HAS_STEALTHCHOP) const uint16_t tmc_val = BE16_P(val_ptr); #endif @@ -727,7 +727,7 @@ void DGUSScreenHandlerMKS::TMC_ChangeConfig(DGUS_VP_Variable &var, void *val_ptr #endif } -void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandler::handleManualMove(DGUS_VP_Variable &var, void *val_ptr) { int16_t movevalue = BE16_P(val_ptr); // Choose Move distance @@ -812,14 +812,14 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { char buf[6]; sprintf(buf, "G28 %c", axiscode); queue.enqueue_one_now(buf); - ForceCompleteUpdate(); + forceCompleteUpdate(); return; } else if (movevalue == 5) { char buf[6]; snprintf_P(buf,6,PSTR("M84 %c"), axiscode); queue.enqueue_one_now(buf); - ForceCompleteUpdate(); + forceCompleteUpdate(); return; } else { @@ -845,13 +845,13 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { if (!old_relative_mode) queue.enqueue_now(F("G90")); } - ForceCompleteUpdate(); + forceCompleteUpdate(); cannotmove: return; } -void DGUSScreenHandlerMKS::GetParkPos(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandlerMKS::getParkPos(DGUS_VP_Variable &var, void *val_ptr) { const int16_t pos = BE16_P(val_ptr); switch (var.VP) { @@ -863,7 +863,7 @@ void DGUSScreenHandlerMKS::GetParkPos(DGUS_VP_Variable &var, void *val_ptr) { skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel } -void DGUSScreenHandlerMKS::HandleChangeLevelPoint(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandlerMKS::handleChangeLevelPoint(DGUS_VP_Variable &var, void *val_ptr) { const int16_t raw = BE16_P(val_ptr); *(int16_t*)var.memadr = raw; @@ -872,7 +872,7 @@ void DGUSScreenHandlerMKS::HandleChangeLevelPoint(DGUS_VP_Variable &var, void *v skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel } -void DGUSScreenHandlerMKS::HandleStepPerMMChanged(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandlerMKS::handleStepPerMMChanged(DGUS_VP_Variable &var, void *val_ptr) { const uint16_t raw = BE16_P(val_ptr); const float value = (float)raw; @@ -888,7 +888,7 @@ void DGUSScreenHandlerMKS::HandleStepPerMMChanged(DGUS_VP_Variable &var, void *v skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel } -void DGUSScreenHandlerMKS::HandleStepPerMMExtruderChanged(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandlerMKS::handleStepPerMMExtruderChanged(DGUS_VP_Variable &var, void *val_ptr) { const uint16_t raw = BE16_P(val_ptr); const float value = (float)raw; @@ -907,7 +907,7 @@ void DGUSScreenHandlerMKS::HandleStepPerMMExtruderChanged(DGUS_VP_Variable &var, skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel } -void DGUSScreenHandlerMKS::HandleMaxSpeedChange(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandlerMKS::handleMaxSpeedChange(DGUS_VP_Variable &var, void *val_ptr) { const uint16_t raw = BE16_P(val_ptr); const float value = (float)raw; @@ -923,7 +923,7 @@ void DGUSScreenHandlerMKS::HandleMaxSpeedChange(DGUS_VP_Variable &var, void *val skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel } -void DGUSScreenHandlerMKS::HandleExtruderMaxSpeedChange(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandlerMKS::handleExtruderMaxSpeedChange(DGUS_VP_Variable &var, void *val_ptr) { const uint16_t raw = BE16_P(val_ptr); const float value = (float)raw; @@ -942,7 +942,7 @@ void DGUSScreenHandlerMKS::HandleExtruderMaxSpeedChange(DGUS_VP_Variable &var, v skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel } -void DGUSScreenHandlerMKS::HandleMaxAccChange(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandlerMKS::handleMaxAccChange(DGUS_VP_Variable &var, void *val_ptr) { const uint16_t raw = BE16_P(val_ptr); const float value = (float)raw; @@ -958,7 +958,7 @@ void DGUSScreenHandlerMKS::HandleMaxAccChange(DGUS_VP_Variable &var, void *val_p skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel } -void DGUSScreenHandlerMKS::HandleExtruderAccChange(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandlerMKS::handleExtruderAccChange(DGUS_VP_Variable &var, void *val_ptr) { uint16_t raw = BE16_P(val_ptr); float value = (float)raw; ExtUI::extruder_t extruder; @@ -976,32 +976,32 @@ void DGUSScreenHandlerMKS::HandleExtruderAccChange(DGUS_VP_Variable &var, void * skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel } -void DGUSScreenHandlerMKS::HandleTravelAccChange(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandlerMKS::handleTravelAccChange(DGUS_VP_Variable &var, void *val_ptr) { uint16_t travel = BE16_P(val_ptr); planner.settings.travel_acceleration = (float)travel; skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel } -void DGUSScreenHandlerMKS::HandleFeedRateMinChange(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandlerMKS::handleFeedRateMinChange(DGUS_VP_Variable &var, void *val_ptr) { uint16_t t = BE16_P(val_ptr); planner.settings.min_feedrate_mm_s = (float)t; skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel } -void DGUSScreenHandlerMKS::HandleMin_T_F(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandlerMKS::handleMin_T_F(DGUS_VP_Variable &var, void *val_ptr) { uint16_t t_f = BE16_P(val_ptr); planner.settings.min_travel_feedrate_mm_s = (float)t_f; skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel } -void DGUSScreenHandlerMKS::HandleAccChange(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandlerMKS::handleAccChange(DGUS_VP_Variable &var, void *val_ptr) { uint16_t acc = BE16_P(val_ptr); planner.settings.acceleration = (float)acc; skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel } #if ENABLED(PREVENT_COLD_EXTRUSION) - void DGUSScreenHandlerMKS::HandleGetExMinTemp(DGUS_VP_Variable &var, void *val_ptr) { + void DGUSScreenHandlerMKS::handleGetExMinTemp(DGUS_VP_Variable &var, void *val_ptr) { const uint16_t ex_min_temp = BE16_P(val_ptr); thermalManager.extrude_min_temp = ex_min_temp; skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel @@ -1009,7 +1009,7 @@ void DGUSScreenHandlerMKS::HandleAccChange(DGUS_VP_Variable &var, void *val_ptr) #endif #if HAS_PID_HEATING - void DGUSScreenHandler::HandleTemperaturePIDChanged(DGUS_VP_Variable &var, void *val_ptr) { + void DGUSScreenHandler::handleTemperaturePIDChanged(DGUS_VP_Variable &var, void *val_ptr) { const uint16_t rawvalue = BE16_P(val_ptr); const float value = float(rawvalue); float newvalue = 0; @@ -1041,7 +1041,7 @@ void DGUSScreenHandlerMKS::HandleAccChange(DGUS_VP_Variable &var, void *val_ptr) #endif // HAS_PID_HEATING #if ENABLED(BABYSTEPPING) - void DGUSScreenHandler::HandleLiveAdjustZ(DGUS_VP_Variable &var, void *val_ptr) { + void DGUSScreenHandler::handleLiveAdjustZ(DGUS_VP_Variable &var, void *val_ptr) { const float step = ZOffset_distance; const uint16_t flag = BE16_P(val_ptr); @@ -1078,11 +1078,11 @@ void DGUSScreenHandlerMKS::HandleAccChange(DGUS_VP_Variable &var, void *val_ptr) default: break; } - ForceCompleteUpdate(); + forceCompleteUpdate(); } #endif // BABYSTEPPING -void DGUSScreenHandlerMKS::GetManualFilament(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandlerMKS::getManualFilament(DGUS_VP_Variable &var, void *val_ptr) { const uint16_t len = BE16_P(val_ptr); const float value = (float)len; @@ -1091,15 +1091,15 @@ void DGUSScreenHandlerMKS::GetManualFilament(DGUS_VP_Variable &var, void *val_pt skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel } -void DGUSScreenHandlerMKS::GetManualFilamentSpeed(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandlerMKS::getManualFilamentSpeed(DGUS_VP_Variable &var, void *val_ptr) { const uint16_t len = BE16_P(val_ptr); filamentSpeed_mm_s = len; skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel } -void DGUSScreenHandlerMKS::FilamentLoadUnload(DGUS_VP_Variable &var, void *val_ptr, const int filamentDir) { - #if EITHER(HAS_MULTI_HOTEND, SINGLENOZZLE) +void DGUSScreenHandlerMKS::filamentLoadUnload(DGUS_VP_Variable &var, void *val_ptr, const int filamentDir) { + #if ANY(HAS_MULTI_HOTEND, SINGLENOZZLE) uint8_t swap_tool = 0; #else constexpr uint8_t swap_tool = 1; // T0 (or none at all) @@ -1120,7 +1120,7 @@ void DGUSScreenHandlerMKS::FilamentLoadUnload(DGUS_VP_Variable &var, void *val_p if (thermalManager.tooColdToExtrude(0)) hotend_too_cold = 1; else { - #if EITHER(HAS_MULTI_HOTEND, SINGLENOZZLE) + #if ANY(HAS_MULTI_HOTEND, SINGLENOZZLE) swap_tool = 1; #endif } @@ -1135,19 +1135,19 @@ void DGUSScreenHandlerMKS::FilamentLoadUnload(DGUS_VP_Variable &var, void *val_p break; } - #if BOTH(HAS_HOTEND, PREVENT_COLD_EXTRUSION) + #if ALL(HAS_HOTEND, PREVENT_COLD_EXTRUSION) if (hotend_too_cold) { if (thermalManager.targetTooColdToExtrude(hotend_too_cold - 1)) thermalManager.setTargetHotend(thermalManager.extrude_min_temp, hotend_too_cold - 1); - sendinfoscreen(F("NOTICE"), nullptr, F("Please wait."), F("Nozzle heating!"), true, true, true, true); - SetupConfirmAction(nullptr); - GotoScreen(DGUSLCD_SCREEN_POPUP); + sendInfoScreen(F("NOTICE"), nullptr, F("Please wait."), F("Nozzle heating!"), true, true, true, true); + setupConfirmAction(nullptr); + gotoScreen(DGUS_SCREEN_POPUP); } #endif if (swap_tool) { char buf[30]; snprintf_P(buf, 30 - #if EITHER(HAS_MULTI_HOTEND, SINGLENOZZLE) + #if ANY(HAS_MULTI_HOTEND, SINGLENOZZLE) , PSTR("M1002T%cE%dF%d"), char('0' + swap_tool - 1) #else , PSTR("M1002E%dF%d") @@ -1159,11 +1159,11 @@ void DGUSScreenHandlerMKS::FilamentLoadUnload(DGUS_VP_Variable &var, void *val_p } /** - * M1002: Do a tool-change and relative move for FilamentLoadUnload + * M1002: Do a tool-change and relative move for filamentLoadUnload * within the G-code execution window for best concurrency. */ void GcodeSuite::M1002() { - #if EITHER(HAS_MULTI_HOTEND, SINGLENOZZLE) + #if ANY(HAS_MULTI_HOTEND, SINGLENOZZLE) { char buf[3]; sprintf_P(buf, PSTR("T%c"), char('0' + parser.intval('T'))); @@ -1181,17 +1181,17 @@ void GcodeSuite::M1002() { axis_relative = old_axis_relative; } -void DGUSScreenHandlerMKS::FilamentLoad(DGUS_VP_Variable &var, void *val_ptr) { - FilamentLoadUnload(var, val_ptr, 1); +void DGUSScreenHandlerMKS::filamentLoad(DGUS_VP_Variable &var, void *val_ptr) { + filamentLoadUnload(var, val_ptr, 1); } -void DGUSScreenHandlerMKS::FilamentUnLoad(DGUS_VP_Variable &var, void *val_ptr) { - FilamentLoadUnload(var, val_ptr, -1); +void DGUSScreenHandlerMKS::filamentUnload(DGUS_VP_Variable &var, void *val_ptr) { + filamentLoadUnload(var, val_ptr, -1); } #if ENABLED(DGUS_FILAMENT_LOADUNLOAD) - void DGUSScreenHandler::HandleFilamentOption(DGUS_VP_Variable &var, void *val_ptr) { + void DGUSScreenHandler::handleFilamentOption(DGUS_VP_Variable &var, void *val_ptr) { uint8_t e_temp = 0; filament_data.heated = false; uint16_t preheat_option = BE16_P(val_ptr); @@ -1237,7 +1237,7 @@ void DGUSScreenHandlerMKS::FilamentUnLoad(DGUS_VP_Variable &var, void *val_ptr) #if HAS_MULTI_HOTEND thermalManager.setTargetHotend(e_temp, ExtUI::extruder_t::E1); #endif - GotoScreen(DGUSLCD_SCREEN_UTILITY); + gotoScreen(DGUS_SCREEN_UTILITY); } else { // Go to the preheat screen to show the heating progress switch (var.VP) { @@ -1258,7 +1258,7 @@ void DGUSScreenHandlerMKS::FilamentUnLoad(DGUS_VP_Variable &var, void *val_ptr) } } - void DGUSScreenHandler::HandleFilamentLoadUnload(DGUS_VP_Variable &var) { + void DGUSScreenHandler::handleFilamentLoadUnload(DGUS_VP_Variable &var) { if (filament_data.action <= 0) return; // If we close to the target temperature, we can start load or unload the filament @@ -1274,7 +1274,7 @@ void DGUSScreenHandlerMKS::FilamentUnLoad(DGUS_VP_Variable &var, void *val_ptr) } else { // unload filament if (!filament_data.heated) { - GotoScreen(DGUSLCD_SCREEN_FILAMENT_UNLOADING); + gotoScreen(DGUS_SCREEN_FILAMENT_UNLOADING); filament_data.heated = true; } // Before unloading extrude to prevent jamming @@ -1293,21 +1293,21 @@ void DGUSScreenHandlerMKS::FilamentUnLoad(DGUS_VP_Variable &var, void *val_ptr) #endif // DGUS_FILAMENT_LOADUNLOAD bool DGUSScreenHandlerMKS::loop() { - dgusdisplay.loop(); + dgus.loop(); const millis_t ms = millis(); static millis_t next_event_ms = 0; static uint8_t language_times = 2; - if (!IsScreenComplete() || ELAPSED(ms, next_event_ms)) { + if (!isScreenComplete() || ELAPSED(ms, next_event_ms)) { next_event_ms = ms + DGUS_UPDATE_INTERVAL_MS; - UpdateScreenVPData(); + updateScreenVPData(); } if (language_times != 0) { - LanguagePInit(); - DGUS_LanguageDisplay(mks_language_index); + languagePInit(); + languageDisplay(mks_language_index); language_times--; } @@ -1326,40 +1326,40 @@ bool DGUSScreenHandlerMKS::loop() { thermalManager.extrude_min_temp = mks_min_extrusion_temp; #endif - DGUS_ExtrudeLoadInit(); + extrudeLoadInit(); - TERN_(DGUS_MKS_RUNOUT_SENSOR, DGUS_RunoutInit()); + TERN_(DGUS_MKS_RUNOUT_SENSOR, runoutInit()); if (TERN0(POWER_LOSS_RECOVERY, recovery.valid())) - GotoScreen(DGUSLCD_SCREEN_POWER_LOSS); + gotoScreen(DGUS_SCREEN_POWER_LOSS); else - GotoScreen(DGUSLCD_SCREEN_MAIN); + gotoScreen(DGUS_SCREEN_MAIN); } #if ENABLED(DGUS_MKS_RUNOUT_SENSOR) - if (booted && printingIsActive()) DGUS_Runout_Idle(); + if (booted && printingIsActive()) runoutIdle(); #endif #endif // SHOW_BOOTSCREEN - return IsScreenComplete(); + return isScreenComplete(); } -void DGUSScreenHandlerMKS::LanguagePInit() { +void DGUSScreenHandlerMKS::languagePInit() { switch (mks_language_index) { case MKS_SimpleChinese: - dgusdisplay.WriteVariable(VP_LANGUAGE_CHANGE1, (uint8_t)MKS_Language_Choose); - dgusdisplay.WriteVariable(VP_LANGUAGE_CHANGE2, (uint8_t)MKS_Language_NoChoose); + dgus.writeVariable(VP_LANGUAGE_CHANGE1, (uint8_t)MKS_Language_Choose); + dgus.writeVariable(VP_LANGUAGE_CHANGE2, (uint8_t)MKS_Language_NoChoose); break; case MKS_English: - dgusdisplay.WriteVariable(VP_LANGUAGE_CHANGE1, (uint8_t)MKS_Language_NoChoose); - dgusdisplay.WriteVariable(VP_LANGUAGE_CHANGE2, (uint8_t)MKS_Language_Choose); + dgus.writeVariable(VP_LANGUAGE_CHANGE1, (uint8_t)MKS_Language_NoChoose); + dgus.writeVariable(VP_LANGUAGE_CHANGE2, (uint8_t)MKS_Language_Choose); break; default: break; } } -void DGUSScreenHandlerMKS::DGUS_ExtrudeLoadInit() { +void DGUSScreenHandlerMKS::extrudeLoadInit() { ex_filament.ex_length = distanceFilament; ex_filament.ex_load_unload_flag = 0; ex_filament.ex_need_time = filamentSpeed_mm_s; @@ -1369,7 +1369,7 @@ void DGUSScreenHandlerMKS::DGUS_ExtrudeLoadInit() { ex_filament.ex_tick_start = 0; } -void DGUSScreenHandlerMKS::DGUS_RunoutInit() { +void DGUSScreenHandlerMKS::runoutInit() { #if PIN_EXISTS(MT_DET_1) SET_INPUT_PULLUP(MT_DET_1_PIN); #endif @@ -1379,7 +1379,7 @@ void DGUSScreenHandlerMKS::DGUS_RunoutInit() { runout_mks.runout_status = UNRUNOUT_STATUS; } -void DGUSScreenHandlerMKS::DGUS_Runout_Idle() { +void DGUSScreenHandlerMKS::runoutIdle() { #if ENABLED(DGUS_MKS_RUNOUT_SENSOR) // scanf runout pin switch (runout_mks.runout_status) { @@ -1387,11 +1387,11 @@ void DGUSScreenHandlerMKS::DGUS_Runout_Idle() { case RUNOUT_STATUS: runout_mks.runout_status = RUNOUT_BEGIN_STATUS; queue.inject(F("M25")); - GotoScreen(MKSLCD_SCREEN_PAUSE); + gotoScreen(MKSLCD_SCREEN_PAUSE); - sendinfoscreen(F("NOTICE"), nullptr, F("Please change filament!"), nullptr, true, true, true, true); - //SetupConfirmAction(nullptr); - GotoScreen(DGUSLCD_SCREEN_POPUP); + sendInfoScreen(F("NOTICE"), nullptr, F("Please change filament!"), nullptr, true, true, true, true); + //setupConfirmAction(nullptr); + gotoScreen(DGUS_SCREEN_POPUP); break; case UNRUNOUT_STATUS: @@ -1414,516 +1414,516 @@ void DGUSScreenHandlerMKS::DGUS_Runout_Idle() { #endif } -void DGUSScreenHandlerMKS::DGUS_LanguageDisplay(uint8_t var) { +void DGUSScreenHandlerMKS::languageDisplay(uint8_t var) { if (var == MKS_English) { const char home_buf_en[] = "Home"; - dgusdisplay.WriteVariable(VP_HOME_Dis, home_buf_en, 32, true); + dgus.writeVariable(VP_HOME_Dis, home_buf_en, 32, true); const char setting_buf_en[] = "Setting"; - dgusdisplay.WriteVariable(VP_Setting_Dis, setting_buf_en, 32, true); + dgus.writeVariable(VP_Setting_Dis, setting_buf_en, 32, true); const char Tool_buf_en[] = "Tool"; - dgusdisplay.WriteVariable(VP_Tool_Dis, Tool_buf_en, 32, true); + dgus.writeVariable(VP_Tool_Dis, Tool_buf_en, 32, true); const char Print_buf_en[] = "Print"; - dgusdisplay.WriteVariable(VP_Print_Dis, Print_buf_en, 32, true); + dgus.writeVariable(VP_Print_Dis, Print_buf_en, 32, true); const char Language_buf_en[] = "Language"; - dgusdisplay.WriteVariable(VP_Language_Dis, Language_buf_en, 32, true); + dgus.writeVariable(VP_Language_Dis, Language_buf_en, 32, true); const char About_buf_en[] = "About"; - dgusdisplay.WriteVariable(VP_About_Dis, About_buf_en, 32, true); + dgus.writeVariable(VP_About_Dis, About_buf_en, 32, true); const char Config_buf_en[] = "Config"; - dgusdisplay.WriteVariable(VP_Config_Dis, Config_buf_en, 32, true); + dgus.writeVariable(VP_Config_Dis, Config_buf_en, 32, true); const char MotorConfig_buf_en[] = "MotorConfig"; - dgusdisplay.WriteVariable(VP_MotorConfig_Dis, MotorConfig_buf_en, 32, true); + dgus.writeVariable(VP_MotorConfig_Dis, MotorConfig_buf_en, 32, true); const char LevelConfig_buf_en[] = "LevelConfig"; - dgusdisplay.WriteVariable(VP_LevelConfig_Dis, LevelConfig_buf_en, 32, true); + dgus.writeVariable(VP_LevelConfig_Dis, LevelConfig_buf_en, 32, true); const char TemperatureConfig_buf_en[] = "Temperature"; - dgusdisplay.WriteVariable(VP_TemperatureConfig_Dis, TemperatureConfig_buf_en, 32, true); + dgus.writeVariable(VP_TemperatureConfig_Dis, TemperatureConfig_buf_en, 32, true); const char Advance_buf_en[] = "Advance"; - dgusdisplay.WriteVariable(VP_Advance_Dis, Advance_buf_en, 32, true); + dgus.writeVariable(VP_Advance_Dis, Advance_buf_en, 32, true); const char Filament_buf_en[] = "Extrude"; - dgusdisplay.WriteVariable(VP_Filament_Dis, Filament_buf_en, 32, true); + dgus.writeVariable(VP_Filament_Dis, Filament_buf_en, 32, true); const char Move_buf_en[] = "Move"; - dgusdisplay.WriteVariable(VP_Move_Dis, Move_buf_en, 32, true); + dgus.writeVariable(VP_Move_Dis, Move_buf_en, 32, true); #if ENABLED(AUTO_BED_LEVELING_BILINEAR) const char Level_buf_en[] = "AutoLevel"; - dgusdisplay.WriteVariable(VP_Level_Dis, Level_buf_en, 32, true); + dgus.writeVariable(VP_Level_Dis, Level_buf_en, 32, true); #elif ENABLED(MESH_BED_LEVELING) const char Level_buf_en[] = "MeshLevel"; - dgusdisplay.WriteVariable(VP_Level_Dis, Level_buf_en, 32, true); + dgus.writeVariable(VP_Level_Dis, Level_buf_en, 32, true); #else const char Level_buf_en[] = "Level"; - dgusdisplay.WriteVariable(VP_Level_Dis, Level_buf_en, 32, true); + dgus.writeVariable(VP_Level_Dis, Level_buf_en, 32, true); #endif const char MotorPluse_buf_en[] = "MotorPluse"; - dgusdisplay.WriteVariable(VP_MotorPluse_Dis, MotorPluse_buf_en, 32, true); + dgus.writeVariable(VP_MotorPluse_Dis, MotorPluse_buf_en, 32, true); const char MotorMaxSpeed_buf_en[] = "MotorMaxSpeed"; - dgusdisplay.WriteVariable(VP_MotorMaxSpeed_Dis, MotorMaxSpeed_buf_en, 32, true); + dgus.writeVariable(VP_MotorMaxSpeed_Dis, MotorMaxSpeed_buf_en, 32, true); const char MotorMaxAcc_buf_en[] = "MotorAcc"; - dgusdisplay.WriteVariable(VP_MotorMaxAcc_Dis, MotorMaxAcc_buf_en, 32, true); + dgus.writeVariable(VP_MotorMaxAcc_Dis, MotorMaxAcc_buf_en, 32, true); const char TravelAcc_buf_en[] = "TravelAcc"; - dgusdisplay.WriteVariable(VP_TravelAcc_Dis, TravelAcc_buf_en, 32, true); + dgus.writeVariable(VP_TravelAcc_Dis, TravelAcc_buf_en, 32, true); const char FeedRateMin_buf_en[] = "FeedRateMin"; - dgusdisplay.WriteVariable(VP_FeedRateMin_Dis, FeedRateMin_buf_en, 32, true); + dgus.writeVariable(VP_FeedRateMin_Dis, FeedRateMin_buf_en, 32, true); const char TravelFeeRateMin_buf_en[] = "TravelFeedRateMin"; - dgusdisplay.WriteVariable(VP_TravelFeeRateMin_Dis, TravelFeeRateMin_buf_en, 32, true); + dgus.writeVariable(VP_TravelFeeRateMin_Dis, TravelFeeRateMin_buf_en, 32, true); const char Acc_buf_en[] = "Acc"; - dgusdisplay.WriteVariable(VP_ACC_Dis, Acc_buf_en, 32, true); + dgus.writeVariable(VP_ACC_Dis, Acc_buf_en, 32, true); const char Point_One_buf_en[] = "Point_First"; - dgusdisplay.WriteVariable(VP_Point_One_Dis, Point_One_buf_en, 32, true); + dgus.writeVariable(VP_Point_One_Dis, Point_One_buf_en, 32, true); const char Point_Two_buf_en[] = "Point_Second"; - dgusdisplay.WriteVariable(VP_Point_Two_Dis, Point_Two_buf_en, 32, true); + dgus.writeVariable(VP_Point_Two_Dis, Point_Two_buf_en, 32, true); const char Point_Three_buf_en[] = "Point_Third"; - dgusdisplay.WriteVariable(VP_Point_Three_Dis, Point_Three_buf_en, 32, true); + dgus.writeVariable(VP_Point_Three_Dis, Point_Three_buf_en, 32, true); const char Point_Four_buf_en[] = "Point_Fourth"; - dgusdisplay.WriteVariable(VP_Point_Four_Dis, Point_Four_buf_en, 32, true); + dgus.writeVariable(VP_Point_Four_Dis, Point_Four_buf_en, 32, true); const char Point_Five_buf_en[] = "Point_Fifth"; - dgusdisplay.WriteVariable(VP_Point_Five_Dis, Point_Five_buf_en, 32, true); + dgus.writeVariable(VP_Point_Five_Dis, Point_Five_buf_en, 32, true); const char Extrusion_buf_en[] = "Extrusion"; - dgusdisplay.WriteVariable(VP_Extrusion_Dis, Extrusion_buf_en, 32, true); + dgus.writeVariable(VP_Extrusion_Dis, Extrusion_buf_en, 32, true); const char HeatBed_buf_en[] = "HeatBed"; - dgusdisplay.WriteVariable(VP_HeatBed_Dis, HeatBed_buf_en, 32, true); + dgus.writeVariable(VP_HeatBed_Dis, HeatBed_buf_en, 32, true); const char FactoryDefaults_buf_en[] = "FactoryDefaults"; - dgusdisplay.WriteVariable(VP_FactoryDefaults_Dis, FactoryDefaults_buf_en, 32, true); + dgus.writeVariable(VP_FactoryDefaults_Dis, FactoryDefaults_buf_en, 32, true); const char StoreSetting_buf_en[] = "StoreSetting"; - dgusdisplay.WriteVariable(VP_StoreSetting_Dis, StoreSetting_buf_en, 32, true); + dgus.writeVariable(VP_StoreSetting_Dis, StoreSetting_buf_en, 32, true); const char PrintPauseConfig_buf_en[] = "PrintPauseConfig"; - dgusdisplay.WriteVariable(VP_PrintPauseConfig_Dis, PrintPauseConfig_buf_en, 32, true); + dgus.writeVariable(VP_PrintPauseConfig_Dis, PrintPauseConfig_buf_en, 32, true); const char X_Pluse_buf_en[] = "X_Pluse"; - dgusdisplay.WriteVariable(VP_X_Pluse_Dis, X_Pluse_buf_en, 32, true); + dgus.writeVariable(VP_X_Pluse_Dis, X_Pluse_buf_en, 32, true); const char Y_Pluse_buf_en[] = "Y_Pluse"; - dgusdisplay.WriteVariable(VP_Y_Pluse_Dis, Y_Pluse_buf_en, 32, true); + dgus.writeVariable(VP_Y_Pluse_Dis, Y_Pluse_buf_en, 32, true); const char Z_Pluse_buf_en[] = "Z_Pluse"; - dgusdisplay.WriteVariable(VP_Z_Pluse_Dis, Z_Pluse_buf_en, 32, true); + dgus.writeVariable(VP_Z_Pluse_Dis, Z_Pluse_buf_en, 32, true); const char E0_Pluse_buf_en[] = "E0_Pluse"; - dgusdisplay.WriteVariable(VP_E0_Pluse_Dis, E0_Pluse_buf_en, 32, true); + dgus.writeVariable(VP_E0_Pluse_Dis, E0_Pluse_buf_en, 32, true); const char E1_Pluse_buf_en[] = "E1_Pluse"; - dgusdisplay.WriteVariable(VP_E1_Pluse_Dis, E1_Pluse_buf_en, 32, true); + dgus.writeVariable(VP_E1_Pluse_Dis, E1_Pluse_buf_en, 32, true); const char X_Max_Speed_buf_en[] = "X_Max_Speed"; - dgusdisplay.WriteVariable(VP_X_Max_Speed_Dis, X_Max_Speed_buf_en, 32, true); + dgus.writeVariable(VP_X_Max_Speed_Dis, X_Max_Speed_buf_en, 32, true); const char Y_Max_Speed_buf_en[] = "Y_Max_Speed"; - dgusdisplay.WriteVariable(VP_Y_Max_Speed_Dis, Y_Max_Speed_buf_en, 32, true); + dgus.writeVariable(VP_Y_Max_Speed_Dis, Y_Max_Speed_buf_en, 32, true); const char Z_Max_Speed_buf_en[] = "Z_Max_Speed"; - dgusdisplay.WriteVariable(VP_Z_Max_Speed_Dis, Z_Max_Speed_buf_en, 32, true); + dgus.writeVariable(VP_Z_Max_Speed_Dis, Z_Max_Speed_buf_en, 32, true); const char E0_Max_Speed_buf_en[] = "E0_Max_Speed"; - dgusdisplay.WriteVariable(VP_E0_Max_Speed_Dis, E0_Max_Speed_buf_en, 32, true); + dgus.writeVariable(VP_E0_Max_Speed_Dis, E0_Max_Speed_buf_en, 32, true); const char E1_Max_Speed_buf_en[] = "E1_Max_Speed"; - dgusdisplay.WriteVariable(VP_E1_Max_Speed_Dis, E1_Max_Speed_buf_en, 32, true); + dgus.writeVariable(VP_E1_Max_Speed_Dis, E1_Max_Speed_buf_en, 32, true); const char X_Max_Acc_Speed_buf_en[] = "X_Max_Acc_Speed"; - dgusdisplay.WriteVariable(VP_X_Max_Acc_Speed_Dis, X_Max_Acc_Speed_buf_en, 32, true); + dgus.writeVariable(VP_X_Max_Acc_Speed_Dis, X_Max_Acc_Speed_buf_en, 32, true); const char Y_Max_Acc_Speed_buf_en[] = "Y_Max_Acc_Speed"; - dgusdisplay.WriteVariable(VP_Y_Max_Acc_Speed_Dis, Y_Max_Acc_Speed_buf_en, 32, true); + dgus.writeVariable(VP_Y_Max_Acc_Speed_Dis, Y_Max_Acc_Speed_buf_en, 32, true); const char Z_Max_Acc_Speed_buf_en[] = "Z_Max_Acc_Speed"; - dgusdisplay.WriteVariable(VP_Z_Max_Acc_Speed_Dis, Z_Max_Acc_Speed_buf_en, 32, true); + dgus.writeVariable(VP_Z_Max_Acc_Speed_Dis, Z_Max_Acc_Speed_buf_en, 32, true); const char E0_Max_Acc_Speed_buf_en[] = "E0_Max_Acc_Speed"; - dgusdisplay.WriteVariable(VP_E0_Max_Acc_Speed_Dis, E0_Max_Acc_Speed_buf_en, 32, true); + dgus.writeVariable(VP_E0_Max_Acc_Speed_Dis, E0_Max_Acc_Speed_buf_en, 32, true); const char E1_Max_Acc_Speed_buf_en[] = "E1_Max_Acc_Speed"; - dgusdisplay.WriteVariable(VP_E1_Max_Acc_Speed_Dis, E1_Max_Acc_Speed_buf_en, 32, true); + dgus.writeVariable(VP_E1_Max_Acc_Speed_Dis, E1_Max_Acc_Speed_buf_en, 32, true); const char X_PARK_POS_buf_en[] = "X_PARK_POS"; - dgusdisplay.WriteVariable(VP_X_PARK_POS_Dis, X_PARK_POS_buf_en, 32, true); + dgus.writeVariable(VP_X_PARK_POS_Dis, X_PARK_POS_buf_en, 32, true); const char Y_PARK_POS_buf_en[] = "Y_PARK_POS"; - dgusdisplay.WriteVariable(VP_Y_PARK_POS_Dis, Y_PARK_POS_buf_en, 32, true); + dgus.writeVariable(VP_Y_PARK_POS_Dis, Y_PARK_POS_buf_en, 32, true); const char Z_PARK_POS_buf_en[] = "Z_PARK_POS"; - dgusdisplay.WriteVariable(VP_Z_PARK_POS_Dis, Z_PARK_POS_buf_en, 32, true); + dgus.writeVariable(VP_Z_PARK_POS_Dis, Z_PARK_POS_buf_en, 32, true); const char Length_buf_en[] = "Length"; - dgusdisplay.WriteVariable(VP_Length_Dis, Length_buf_en, 32, true); + dgus.writeVariable(VP_Length_Dis, Length_buf_en, 32, true); const char Speed_buf_en[] = "Speed"; - dgusdisplay.WriteVariable(VP_Speed_Dis, Speed_buf_en, 32, true); + dgus.writeVariable(VP_Speed_Dis, Speed_buf_en, 32, true); const char InOut_buf_en[] = "InOut"; - dgusdisplay.WriteVariable(VP_InOut_Dis, InOut_buf_en, 32, true); + dgus.writeVariable(VP_InOut_Dis, InOut_buf_en, 32, true); const char PrintTimet_buf_en[] = "PrintTime"; - dgusdisplay.WriteVariable(VP_PrintTime_Dis, PrintTimet_buf_en, 32, true); + dgus.writeVariable(VP_PrintTime_Dis, PrintTimet_buf_en, 32, true); const char E0_Temp_buf_en[] = "E0_Temp"; - dgusdisplay.WriteVariable(VP_E0_Temp_Dis, E0_Temp_buf_en, 32, true); + dgus.writeVariable(VP_E0_Temp_Dis, E0_Temp_buf_en, 32, true); const char E1_Temp_buf_en[] = "E1_Temp"; - dgusdisplay.WriteVariable(VP_E1_Temp_Dis, E1_Temp_buf_en, 32, true); + dgus.writeVariable(VP_E1_Temp_Dis, E1_Temp_buf_en, 32, true); const char HB_Temp_buf_en[] = "HB_Temp"; - dgusdisplay.WriteVariable(VP_HB_Temp_Dis, HB_Temp_buf_en, 32, true); + dgus.writeVariable(VP_HB_Temp_Dis, HB_Temp_buf_en, 32, true); const char Feedrate_buf_en[] = "Feedrate"; - dgusdisplay.WriteVariable(VP_Feedrate_Dis, Feedrate_buf_en, 32, true); + dgus.writeVariable(VP_Feedrate_Dis, Feedrate_buf_en, 32, true); const char PrintAcc_buf_en[] = "PrintSpeed"; - dgusdisplay.WriteVariable(VP_PrintAcc_Dis, PrintAcc_buf_en, 32, true); + dgus.writeVariable(VP_PrintAcc_Dis, PrintAcc_buf_en, 32, true); const char FAN_Speed_buf_en[] = "FAN_Speed"; - dgusdisplay.WriteVariable(VP_Fan_Speed_Dis, FAN_Speed_buf_en, 32, true); + dgus.writeVariable(VP_Fan_Speed_Dis, FAN_Speed_buf_en, 32, true); const char Printing_buf_en[] = "Printing"; - dgusdisplay.WriteVariable(VP_Printing_Dis, Printing_buf_en, 32, true); + dgus.writeVariable(VP_Printing_Dis, Printing_buf_en, 32, true); const char Info_EEPROM_1_buf_en[] = "Store setting?"; - dgusdisplay.WriteVariable(VP_Info_EEPROM_1_Dis, Info_EEPROM_1_buf_en, 32, true); + dgus.writeVariable(VP_Info_EEPROM_1_Dis, Info_EEPROM_1_buf_en, 32, true); const char Info_EEPROM_2_buf_en[] = "Revert setting?"; - dgusdisplay.WriteVariable(VP_Info_EEPROM_2_Dis, Info_EEPROM_2_buf_en, 32, true); + dgus.writeVariable(VP_Info_EEPROM_2_Dis, Info_EEPROM_2_buf_en, 32, true); const char Info_PrintFinish_1_buf_en[] = "Print Done"; - dgusdisplay.WriteVariable(VP_Info_PrintFinish_1_Dis, Info_PrintFinish_1_buf_en, 32, true); + dgus.writeVariable(VP_Info_PrintFinish_1_Dis, Info_PrintFinish_1_buf_en, 32, true); const char TMC_X_Step_buf_en[] = "X_SenSitivity"; - dgusdisplay.WriteVariable(VP_TMC_X_Step_Dis, TMC_X_Step_buf_en, 32, true); + dgus.writeVariable(VP_TMC_X_Step_Dis, TMC_X_Step_buf_en, 32, true); const char TMC_Y_Step_buf_en[] = "Y_SenSitivity"; - dgusdisplay.WriteVariable(VP_TMC_Y_Step_Dis, TMC_Y_Step_buf_en, 32, true); + dgus.writeVariable(VP_TMC_Y_Step_Dis, TMC_Y_Step_buf_en, 32, true); const char TMC_Z_Step_buf_en[] = "Z_SenSitivity"; - dgusdisplay.WriteVariable(VP_TMC_Z_Step_Dis, TMC_Z_Step_buf_en, 32, true); + dgus.writeVariable(VP_TMC_Z_Step_Dis, TMC_Z_Step_buf_en, 32, true); const char TMC_X_Current_buf_en[] = "X_Current"; - dgusdisplay.WriteVariable(VP_TMC_X_Current_Dis, TMC_X_Current_buf_en, 32, true); + dgus.writeVariable(VP_TMC_X_Current_Dis, TMC_X_Current_buf_en, 32, true); const char TMC_Y_Current_buf_en[] = "Y_Current"; - dgusdisplay.WriteVariable(VP_TMC_Y_Current_Dis, TMC_Y_Current_buf_en, 32, true); + dgus.writeVariable(VP_TMC_Y_Current_Dis, TMC_Y_Current_buf_en, 32, true); const char TMC_Z_Current_buf_en[] = "Z_Current"; - dgusdisplay.WriteVariable(VP_TMC_Z_Current_Dis, TMC_Z_Current_buf_en, 32, true); + dgus.writeVariable(VP_TMC_Z_Current_Dis, TMC_Z_Current_buf_en, 32, true); const char TMC_E0_Current_buf_en[] = "E0_Current"; - dgusdisplay.WriteVariable(VP_TMC_E0_Current_Dis, TMC_E0_Current_buf_en, 32, true); + dgus.writeVariable(VP_TMC_E0_Current_Dis, TMC_E0_Current_buf_en, 32, true); const char TMC_X1_Current_buf_en[] = "X1_Current"; - dgusdisplay.WriteVariable(VP_TMC_X1_Current_Dis, TMC_X1_Current_buf_en, 32, true); + dgus.writeVariable(VP_TMC_X1_Current_Dis, TMC_X1_Current_buf_en, 32, true); const char TMC_Y1_Current_buf_en[] = "Y1_Current"; - dgusdisplay.WriteVariable(VP_TMC_Y1_Current_Dis, TMC_Y1_Current_buf_en, 32, true); + dgus.writeVariable(VP_TMC_Y1_Current_Dis, TMC_Y1_Current_buf_en, 32, true); const char TMC_Z1_Current_buf_en[] = "Z1_Current"; - dgusdisplay.WriteVariable(VP_TMC_Z1_Current_Dis, TMC_Z1_Current_buf_en, 32, true); + dgus.writeVariable(VP_TMC_Z1_Current_Dis, TMC_Z1_Current_buf_en, 32, true); const char TMC_E1_Current_buf_en[] = "E1_Current"; - dgusdisplay.WriteVariable(VP_TMC_E1_Current_Dis, TMC_E1_Current_buf_en, 32, true); + dgus.writeVariable(VP_TMC_E1_Current_Dis, TMC_E1_Current_buf_en, 32, true); const char Min_Ex_Temp_buf_en[] = "Min_Ex_Temp"; - dgusdisplay.WriteVariable(VP_Min_Ex_Temp_Dis, Min_Ex_Temp_buf_en, 32, true); + dgus.writeVariable(VP_Min_Ex_Temp_Dis, Min_Ex_Temp_buf_en, 32, true); const char AutoLEVEL_INFO1_buf_en[] = "Please Press Button!"; - dgusdisplay.WriteVariable(VP_AutoLEVEL_INFO1, AutoLEVEL_INFO1_buf_en, 32, true); + dgus.writeVariable(VP_AutoLEVEL_INFO1, AutoLEVEL_INFO1_buf_en, 32, true); const char EX_TEMP_INFO2_buf_en[] = "Please wait a monent"; - dgusdisplay.WriteVariable(VP_EX_TEMP_INFO2_Dis, EX_TEMP_INFO2_buf_en, 32, true); + dgus.writeVariable(VP_EX_TEMP_INFO2_Dis, EX_TEMP_INFO2_buf_en, 32, true); const char EX_TEMP_INFO3_buf_en[] = "Cancle"; - dgusdisplay.WriteVariable(VP_EX_TEMP_INFO3_Dis, EX_TEMP_INFO3_buf_en, 32, true); + dgus.writeVariable(VP_EX_TEMP_INFO3_Dis, EX_TEMP_INFO3_buf_en, 32, true); const char PrintConfrim_Info_buf_en[] = "Start Print?"; - dgusdisplay.WriteVariable(VP_PrintConfrim_Info_Dis, PrintConfrim_Info_buf_en, 32, true); + dgus.writeVariable(VP_PrintConfrim_Info_Dis, PrintConfrim_Info_buf_en, 32, true); const char StopPrintConfrim_Info_buf_en[] = "Stop Print?"; - dgusdisplay.WriteVariable(VP_StopPrintConfrim_Info_Dis, StopPrintConfrim_Info_buf_en, 32, true); + dgus.writeVariable(VP_StopPrintConfrim_Info_Dis, StopPrintConfrim_Info_buf_en, 32, true); const char Printting_buf_en[] = "Printing"; - dgusdisplay.WriteVariable(VP_Printting_Dis, Printting_buf_en, 32, true); + dgus.writeVariable(VP_Printting_Dis, Printting_buf_en, 32, true); const char LCD_BLK_buf_en[] = "Backlight"; - dgusdisplay.WriteVariable(VP_LCD_BLK_Dis, LCD_BLK_buf_en, 32, true); + dgus.writeVariable(VP_LCD_BLK_Dis, LCD_BLK_buf_en, 32, true); } else if (var == MKS_SimpleChinese) { uint16_t home_buf_ch[] = { 0xF7D6, 0xB3D2 }; - dgusdisplay.WriteVariable(VP_HOME_Dis, home_buf_ch, 4, true); + dgus.writeVariable(VP_HOME_Dis, home_buf_ch, 4, true); const uint16_t Setting_Dis[] = { 0xE8C9, 0xC3D6, 0x2000, 0x2000, 0x2000 }; - dgusdisplay.WriteVariable(VP_Setting_Dis, Setting_Dis, 7, true); + dgus.writeVariable(VP_Setting_Dis, Setting_Dis, 7, true); const uint16_t Tool_Dis[] = { 0xA4B9, 0xDFBE }; - dgusdisplay.WriteVariable(VP_Tool_Dis, Tool_Dis, 4, true); + dgus.writeVariable(VP_Tool_Dis, Tool_Dis, 4, true); const uint16_t Print_buf_ch[] = { 0xF2B4, 0xA1D3, 0x2000 }; - dgusdisplay.WriteVariable(VP_Print_Dis, Print_buf_ch, 6, true); + dgus.writeVariable(VP_Print_Dis, Print_buf_ch, 6, true); const uint16_t Language_buf_ch[] = { 0xEFD3, 0xD4D1, 0x2000, 0x2000 }; - dgusdisplay.WriteVariable(VP_Language_Dis, Language_buf_ch, 8, true); + dgus.writeVariable(VP_Language_Dis, Language_buf_ch, 8, true); const uint16_t About_buf_ch[] = { 0xD8B9, 0xDAD3, 0x2000 }; - dgusdisplay.WriteVariable(VP_About_Dis, About_buf_ch, 6, true); + dgus.writeVariable(VP_About_Dis, About_buf_ch, 6, true); const uint16_t Config_buf_ch[] = { 0xE4C5, 0xC3D6, 0x2000 }; - dgusdisplay.WriteVariable(VP_Config_Dis, Config_buf_ch, 6, true); + dgus.writeVariable(VP_Config_Dis, Config_buf_ch, 6, true); const uint16_t MotorConfig_buf_ch[] = { 0xE7B5, 0xFABB, 0xE4C5, 0xC3D6, 0x2000 }; - dgusdisplay.WriteVariable(VP_MotorConfig_Dis, MotorConfig_buf_ch, 12, true); + dgus.writeVariable(VP_MotorConfig_Dis, MotorConfig_buf_ch, 12, true); const uint16_t LevelConfig_buf_ch[] = { 0xD6CA, 0xAFB6, 0xF7B5, 0xBDC6, 0xE8C9, 0xC3D6, 0x2000 }; - dgusdisplay.WriteVariable(VP_LevelConfig_Dis, LevelConfig_buf_ch, 32, true); + dgus.writeVariable(VP_LevelConfig_Dis, LevelConfig_buf_ch, 32, true); const uint16_t TemperatureConfig_buf_ch[] = { 0xC2CE, 0xC8B6, 0x2000 }; - dgusdisplay.WriteVariable(VP_TemperatureConfig_Dis, TemperatureConfig_buf_ch, 11, true); + dgus.writeVariable(VP_TemperatureConfig_Dis, TemperatureConfig_buf_ch, 11, true); const uint16_t Advance_buf_ch[] = { 0xDFB8, 0xB6BC, 0xE8C9, 0xC3D6, 0x2000 }; - dgusdisplay.WriteVariable(VP_Advance_Dis, Advance_buf_ch, 16, true); + dgus.writeVariable(VP_Advance_Dis, Advance_buf_ch, 16, true); const uint16_t Filament_buf_ch[] = { 0xB7BC, 0xF6B3, 0x2000 }; - dgusdisplay.WriteVariable(VP_Filament_Dis, Filament_buf_ch, 8, true); + dgus.writeVariable(VP_Filament_Dis, Filament_buf_ch, 8, true); const uint16_t Move_buf_ch[] = { 0xC6D2, 0xAFB6, 0x2000 }; - dgusdisplay.WriteVariable(VP_Move_Dis, Move_buf_ch, 4, true); + dgus.writeVariable(VP_Move_Dis, Move_buf_ch, 4, true); #if ENABLED(AUTO_BED_LEVELING_BILINEAR) const uint16_t Level_buf_ch[] = { 0xD4D7, 0xAFB6, 0xF7B5, 0xBDC6, 0x2000 }; - dgusdisplay.WriteVariable(VP_Level_Dis, Level_buf_ch, 32, true); + dgus.writeVariable(VP_Level_Dis, Level_buf_ch, 32, true); #elif ENABLED(MESH_BED_LEVELING) const uint16_t Level_buf_ch[] = { 0xF8CD, 0xF1B8, 0xF7B5, 0xBDC6, 0x2000 }; - dgusdisplay.WriteVariable(VP_Level_Dis, Level_buf_ch, 32, true); + dgus.writeVariable(VP_Level_Dis, Level_buf_ch, 32, true); #else const uint16_t Level_buf_ch[] = { 0xD6CA, 0xAFB6, 0xF7B5, 0xBDC6, 0x2000 }; - dgusdisplay.WriteVariable(VP_Level_Dis, Level_buf_ch, 32, true); + dgus.writeVariable(VP_Level_Dis, Level_buf_ch, 32, true); #endif const uint16_t MotorPluse_buf_ch[] = { 0xF6C2, 0xE5B3, 0x2000 }; - dgusdisplay.WriteVariable(VP_MotorPluse_Dis, MotorPluse_buf_ch, 16, true); + dgus.writeVariable(VP_MotorPluse_Dis, MotorPluse_buf_ch, 16, true); const uint16_t MotorMaxSpeed_buf_ch[] = { 0xEED7, 0xF3B4, 0xD9CB, 0xC8B6, 0x2000 }; - dgusdisplay.WriteVariable(VP_MotorMaxSpeed_Dis, MotorMaxSpeed_buf_ch, 16, true); + dgus.writeVariable(VP_MotorMaxSpeed_Dis, MotorMaxSpeed_buf_ch, 16, true); const uint16_t MotorMaxAcc_buf_ch[] = { 0xEED7, 0xF3B4, 0xD3BC, 0xD9CB, 0xC8B6, 0x2000 }; - dgusdisplay.WriteVariable(VP_MotorMaxAcc_Dis, MotorMaxAcc_buf_ch, 16, true); + dgus.writeVariable(VP_MotorMaxAcc_Dis, MotorMaxAcc_buf_ch, 16, true); const uint16_t TravelAcc_buf_ch[] = { 0xD5BF, 0xD0D0, 0xD3BC, 0xD9CB, 0xC8B6, 0x2000 }; - dgusdisplay.WriteVariable(VP_TravelAcc_Dis, TravelAcc_buf_ch, 16, true); + dgus.writeVariable(VP_TravelAcc_Dis, TravelAcc_buf_ch, 16, true); const uint16_t FeedRateMin_buf_ch[] = { 0xEED7, 0xA1D0, 0xD9CB, 0xC8B6, 0x2000 }; - dgusdisplay.WriteVariable(VP_FeedRateMin_Dis, FeedRateMin_buf_ch, 12, true); + dgus.writeVariable(VP_FeedRateMin_Dis, FeedRateMin_buf_ch, 12, true); const uint16_t TravelFeeRateMin_buf_ch[] = { 0xD5BF, 0xD0D0, 0xEED7, 0xA1D0, 0xD9CB, 0xC8B6, 0x2000 }; - dgusdisplay.WriteVariable(VP_TravelFeeRateMin_Dis, TravelFeeRateMin_buf_ch, 24, true); + dgus.writeVariable(VP_TravelFeeRateMin_Dis, TravelFeeRateMin_buf_ch, 24, true); const uint16_t Acc_buf_ch[] = { 0xD3BC, 0xD9CB, 0xC8B6, 0x2000 }; - dgusdisplay.WriteVariable(VP_ACC_Dis, Acc_buf_ch, 16, true); + dgus.writeVariable(VP_ACC_Dis, Acc_buf_ch, 16, true); const uint16_t Point_One_buf_ch[] = { 0xDAB5, 0xBBD2, 0xE3B5, 0x2000 }; - dgusdisplay.WriteVariable(VP_Point_One_Dis, Point_One_buf_ch, 12, true); + dgus.writeVariable(VP_Point_One_Dis, Point_One_buf_ch, 12, true); const uint16_t Point_Two_buf_ch[] = { 0xDAB5, 0xFEB6, 0xE3B5, 0x2000 }; - dgusdisplay.WriteVariable(VP_Point_Two_Dis, Point_Two_buf_ch, 12, true); + dgus.writeVariable(VP_Point_Two_Dis, Point_Two_buf_ch, 12, true); const uint16_t Point_Three_buf_ch[] = { 0xDAB5, 0xFDC8, 0xE3B5, 0x2000 }; - dgusdisplay.WriteVariable(VP_Point_Three_Dis, Point_Three_buf_ch, 12, true); + dgus.writeVariable(VP_Point_Three_Dis, Point_Three_buf_ch, 12, true); const uint16_t Point_Four_buf_ch[] = { 0xDAB5, 0xC4CB, 0xE3B5, 0x2000 }; - dgusdisplay.WriteVariable(VP_Point_Four_Dis, Point_Four_buf_ch, 12, true); + dgus.writeVariable(VP_Point_Four_Dis, Point_Four_buf_ch, 12, true); const uint16_t Point_Five_buf_ch[] = { 0xDAB5, 0xE5CE, 0xE3B5, 0x2000 }; - dgusdisplay.WriteVariable(VP_Point_Five_Dis, Point_Five_buf_ch, 12, true); + dgus.writeVariable(VP_Point_Five_Dis, Point_Five_buf_ch, 12, true); const uint16_t Extrusion_buf_ch[] = { 0xB7BC, 0xF6B3, 0xB7CD, 0x2000 }; - dgusdisplay.WriteVariable(VP_Extrusion_Dis, Extrusion_buf_ch, 12, true); + dgus.writeVariable(VP_Extrusion_Dis, Extrusion_buf_ch, 12, true); const uint16_t HeatBed_buf_ch[] = { 0xC8C8, 0xB2B4, 0x2000 }; - dgusdisplay.WriteVariable(VP_HeatBed_Dis, HeatBed_buf_ch, 12, true); + dgus.writeVariable(VP_HeatBed_Dis, HeatBed_buf_ch, 12, true); const uint16_t FactoryDefaults_buf_ch[] = { 0xD6BB, 0xB4B8, 0xF6B3, 0xA7B3, 0xE8C9, 0xC3D6, 0x2000 }; - dgusdisplay.WriteVariable(VP_FactoryDefaults_Dis, FactoryDefaults_buf_ch, 16, true); + dgus.writeVariable(VP_FactoryDefaults_Dis, FactoryDefaults_buf_ch, 16, true); const uint16_t StoreSetting_buf_ch[] = { 0xA3B1, 0xE6B4, 0xE8C9, 0xC3D6, 0x2000 }; - dgusdisplay.WriteVariable(VP_StoreSetting_Dis, StoreSetting_buf_ch, 16, true); + dgus.writeVariable(VP_StoreSetting_Dis, StoreSetting_buf_ch, 16, true); const uint16_t PrintPauseConfig_buf_ch[] = { 0xDDD4, 0xA3CD, 0xBBCE, 0xC3D6, 0x2000 }; - dgusdisplay.WriteVariable(VP_PrintPauseConfig_Dis, PrintPauseConfig_buf_ch, 32, true); + dgus.writeVariable(VP_PrintPauseConfig_Dis, PrintPauseConfig_buf_ch, 32, true); const uint16_t X_Pluse_buf_ch[] = { 0x2058, 0xE1D6, 0xF6C2, 0xE5B3, 0x2000 }; - dgusdisplay.WriteVariable(VP_X_Pluse_Dis, X_Pluse_buf_ch, 16, true); + dgus.writeVariable(VP_X_Pluse_Dis, X_Pluse_buf_ch, 16, true); const uint16_t Y_Pluse_buf_ch[] = { 0x2059, 0xE1D6, 0xF6C2, 0xE5B3, 0x2000 }; - dgusdisplay.WriteVariable(VP_Y_Pluse_Dis, Y_Pluse_buf_ch, 16, true); + dgus.writeVariable(VP_Y_Pluse_Dis, Y_Pluse_buf_ch, 16, true); const uint16_t Z_Pluse_buf_ch[] = { 0x205A, 0xE1D6, 0xF6C2, 0xE5B3, 0x2000 }; - dgusdisplay.WriteVariable(VP_Z_Pluse_Dis, Z_Pluse_buf_ch, 16, true); + dgus.writeVariable(VP_Z_Pluse_Dis, Z_Pluse_buf_ch, 16, true); const uint16_t E0_Pluse_buf_ch[] = { 0x3045, 0xE1D6, 0xF6C2, 0xE5B3, 0x2000 }; - dgusdisplay.WriteVariable(VP_E0_Pluse_Dis, E0_Pluse_buf_ch, 16, true); + dgus.writeVariable(VP_E0_Pluse_Dis, E0_Pluse_buf_ch, 16, true); const uint16_t E1_Pluse_buf_ch[] = { 0x3145, 0xE1D6, 0xF6C2, 0xE5B3, 0x2000 }; - dgusdisplay.WriteVariable(VP_E1_Pluse_Dis, E1_Pluse_buf_ch, 16, true); + dgus.writeVariable(VP_E1_Pluse_Dis, E1_Pluse_buf_ch, 16, true); const uint16_t X_Max_Speed_buf_ch[] = { 0x2058, 0xEED7, 0xF3B4, 0xD9CB, 0xC8B6, 0x2000 }; - dgusdisplay.WriteVariable(VP_X_Max_Speed_Dis, X_Max_Speed_buf_ch, 16, true); + dgus.writeVariable(VP_X_Max_Speed_Dis, X_Max_Speed_buf_ch, 16, true); const uint16_t Y_Max_Speed_buf_ch[] = { 0x2059, 0xEED7, 0xF3B4, 0xD9CB, 0xC8B6, 0x2000 }; - dgusdisplay.WriteVariable(VP_Y_Max_Speed_Dis, Y_Max_Speed_buf_ch, 16, true); + dgus.writeVariable(VP_Y_Max_Speed_Dis, Y_Max_Speed_buf_ch, 16, true); const uint16_t Z_Max_Speed_buf_ch[] = { 0x205A, 0xEED7, 0xF3B4, 0xD9CB, 0xC8B6, 0x2000 }; - dgusdisplay.WriteVariable(VP_Z_Max_Speed_Dis, Z_Max_Speed_buf_ch, 16, true); + dgus.writeVariable(VP_Z_Max_Speed_Dis, Z_Max_Speed_buf_ch, 16, true); const uint16_t E0_Max_Speed_buf_ch[] = { 0x3045, 0xEED7, 0xF3B4, 0xD9CB, 0xC8B6, 0x2000 }; - dgusdisplay.WriteVariable(VP_E0_Max_Speed_Dis, E0_Max_Speed_buf_ch, 16, true); + dgus.writeVariable(VP_E0_Max_Speed_Dis, E0_Max_Speed_buf_ch, 16, true); const uint16_t E1_Max_Speed_buf_ch[] = { 0x3145, 0xEED7, 0xF3B4, 0xD9CB, 0xC8B6, 0x2000 }; - dgusdisplay.WriteVariable(VP_E1_Max_Speed_Dis, E1_Max_Speed_buf_ch, 16, true); + dgus.writeVariable(VP_E1_Max_Speed_Dis, E1_Max_Speed_buf_ch, 16, true); const uint16_t X_Max_Acc_Speed_buf_ch[] = { 0x2058, 0xEED7, 0xF3B4, 0xD3BC, 0xD9CB, 0xC8B6, 0x2000 }; - dgusdisplay.WriteVariable(VP_X_Max_Acc_Speed_Dis, X_Max_Acc_Speed_buf_ch, 16, true); + dgus.writeVariable(VP_X_Max_Acc_Speed_Dis, X_Max_Acc_Speed_buf_ch, 16, true); const uint16_t Y_Max_Acc_Speed_buf_ch[] = { 0x2059, 0xEED7, 0xF3B4, 0xD3BC, 0xD9CB, 0xC8B6, 0x2000 }; - dgusdisplay.WriteVariable(VP_Y_Max_Acc_Speed_Dis, Y_Max_Acc_Speed_buf_ch, 16, true); + dgus.writeVariable(VP_Y_Max_Acc_Speed_Dis, Y_Max_Acc_Speed_buf_ch, 16, true); const uint16_t Z_Max_Acc_Speed_buf_ch[] = { 0x205A, 0xEED7, 0xF3B4, 0xD3BC, 0xD9CB, 0xC8B6, 0x2000 }; - dgusdisplay.WriteVariable(VP_Z_Max_Acc_Speed_Dis, Z_Max_Acc_Speed_buf_ch, 16, true); + dgus.writeVariable(VP_Z_Max_Acc_Speed_Dis, Z_Max_Acc_Speed_buf_ch, 16, true); const uint16_t E0_Max_Acc_Speed_buf_ch[] = { 0x3045, 0xEED7, 0xF3B4, 0xD3BC, 0xD9CB, 0xC8B6, 0x2000 }; - dgusdisplay.WriteVariable(VP_E0_Max_Acc_Speed_Dis, E0_Max_Acc_Speed_buf_ch, 16, true); + dgus.writeVariable(VP_E0_Max_Acc_Speed_Dis, E0_Max_Acc_Speed_buf_ch, 16, true); const uint16_t E1_Max_Acc_Speed_buf_ch[] = { 0x3145, 0xEED7, 0xF3B4, 0xD3BC, 0xD9CB, 0xC8B6, 0x2000 }; - dgusdisplay.WriteVariable(VP_E1_Max_Acc_Speed_Dis, E1_Max_Acc_Speed_buf_ch, 16, true); + dgus.writeVariable(VP_E1_Max_Acc_Speed_Dis, E1_Max_Acc_Speed_buf_ch, 16, true); const uint16_t X_PARK_POS_buf_ch[] = { 0x2058, 0xDDD4, 0xA3CD, 0xBBCE, 0xC3D6, 0x2000 }; - dgusdisplay.WriteVariable(VP_X_PARK_POS_Dis, X_PARK_POS_buf_ch, 16, true); + dgus.writeVariable(VP_X_PARK_POS_Dis, X_PARK_POS_buf_ch, 16, true); const uint16_t Y_PARK_POS_buf_ch[] = { 0x2059, 0xDDD4, 0xA3CD, 0xBBCE, 0xC3D6, 0x2000 }; - dgusdisplay.WriteVariable(VP_Y_PARK_POS_Dis, Y_PARK_POS_buf_ch, 16, true); + dgus.writeVariable(VP_Y_PARK_POS_Dis, Y_PARK_POS_buf_ch, 16, true); const uint16_t Z_PARK_POS_buf_ch[] = { 0x205A, 0xDDD4, 0xA3CD, 0xBBCE, 0xC3D6, 0x2000 }; - dgusdisplay.WriteVariable(VP_Z_PARK_POS_Dis, Z_PARK_POS_buf_ch, 16, true); + dgus.writeVariable(VP_Z_PARK_POS_Dis, Z_PARK_POS_buf_ch, 16, true); const uint16_t Length_buf_ch[] = { 0xBDB2, 0xA4B3, 0x2000 }; - dgusdisplay.WriteVariable(VP_Length_Dis, Length_buf_ch, 8, true); + dgus.writeVariable(VP_Length_Dis, Length_buf_ch, 8, true); const uint16_t Speed_buf_ch[] = { 0xD9CB, 0xC8B6, 0x2000 }; - dgusdisplay.WriteVariable(VP_Speed_Dis, Speed_buf_ch, 8, true); + dgus.writeVariable(VP_Speed_Dis, Speed_buf_ch, 8, true); const uint16_t InOut_buf_ch[] = { 0xF8BD, 0xF6B3, 0x2000 }; - dgusdisplay.WriteVariable(VP_InOut_Dis, InOut_buf_ch, 8, true); + dgus.writeVariable(VP_InOut_Dis, InOut_buf_ch, 8, true); const uint16_t PrintTimet_buf_en[] = { 0xF2B4, 0xA1D3, 0xB1CA, 0xE4BC, 0x2000 }; - dgusdisplay.WriteVariable(VP_PrintTime_Dis, PrintTimet_buf_en, 16, true); + dgus.writeVariable(VP_PrintTime_Dis, PrintTimet_buf_en, 16, true); const uint16_t E0_Temp_buf_ch[] = { 0x3045, 0xC2CE, 0xC8B6, 0x2000 }; - dgusdisplay.WriteVariable(VP_E0_Temp_Dis, E0_Temp_buf_ch, 16, true); + dgus.writeVariable(VP_E0_Temp_Dis, E0_Temp_buf_ch, 16, true); const uint16_t E1_Temp_buf_ch[] = { 0x3145, 0xC2CE, 0xC8B6, 0x2000 }; - dgusdisplay.WriteVariable(VP_E1_Temp_Dis, E1_Temp_buf_ch, 16, true); + dgus.writeVariable(VP_E1_Temp_Dis, E1_Temp_buf_ch, 16, true); const uint16_t HB_Temp_buf_ch[] = { 0xC8C8, 0xB2B4, 0xC2CE, 0xC8B6, 0x2000 }; - dgusdisplay.WriteVariable(VP_HB_Temp_Dis, HB_Temp_buf_ch, 16, true); + dgus.writeVariable(VP_HB_Temp_Dis, HB_Temp_buf_ch, 16, true); const uint16_t Feedrate_buf_ch[] = { 0xB7BC, 0xF6B3, 0xD9CB, 0xC8B6, 0x2000 }; - dgusdisplay.WriteVariable(VP_Feedrate_Dis, Feedrate_buf_ch, 16, true); + dgus.writeVariable(VP_Feedrate_Dis, Feedrate_buf_ch, 16, true); const uint16_t PrintAcc_buf_ch[] = { 0xF2B4, 0xA1D3, 0xD9CB, 0xC8B6, 0x2000 }; - dgusdisplay.WriteVariable(VP_PrintAcc_Dis, PrintAcc_buf_ch, 16, true); + dgus.writeVariable(VP_PrintAcc_Dis, PrintAcc_buf_ch, 16, true); const uint16_t FAN_Speed_buf_ch[] = { 0xE7B7, 0xC8C9, 0xD9CB, 0xC8B6, 0x2000 }; - dgusdisplay.WriteVariable(VP_Fan_Speed_Dis, FAN_Speed_buf_ch, 16, true); + dgus.writeVariable(VP_Fan_Speed_Dis, FAN_Speed_buf_ch, 16, true); const uint16_t Printing_buf_ch[] = { 0xF2B4, 0xA1D3, 0xD0D6, 0x2000 }; - dgusdisplay.WriteVariable(VP_Printing_Dis, Printing_buf_ch, 16, true); + dgus.writeVariable(VP_Printing_Dis, Printing_buf_ch, 16, true); const uint16_t Info_EEPROM_1_buf_ch[] = { 0xC7CA, 0xF1B7, 0xA3B1, 0xE6B4, 0xE8C9, 0xC3D6, 0xBFA3, 0x2000 }; - dgusdisplay.WriteVariable(VP_Info_EEPROM_1_Dis, Info_EEPROM_1_buf_ch, 32, true); + dgus.writeVariable(VP_Info_EEPROM_1_Dis, Info_EEPROM_1_buf_ch, 32, true); const uint16_t Info_EEPROM_2_buf_ch[] = { 0xC7CA, 0xF1B7, 0xD6BB, 0xB4B8, 0xF6B3, 0xA7B3, 0xE8C9, 0xC3D6, 0xBFA3, 0x2000 }; - dgusdisplay.WriteVariable(VP_Info_EEPROM_2_Dis, Info_EEPROM_2_buf_ch, 32, true); + dgus.writeVariable(VP_Info_EEPROM_2_Dis, Info_EEPROM_2_buf_ch, 32, true); const uint16_t TMC_X_Step_buf_ch[] = { 0x2058, 0xE9C1, 0xF4C3, 0xC8B6, 0x2000 }; - dgusdisplay.WriteVariable(VP_TMC_X_Step_Dis, TMC_X_Step_buf_ch, 16, true); + dgus.writeVariable(VP_TMC_X_Step_Dis, TMC_X_Step_buf_ch, 16, true); const uint16_t TMC_Y_Step_buf_ch[] = { 0x2059, 0xE9C1, 0xF4C3, 0xC8B6, 0x2000 }; - dgusdisplay.WriteVariable(VP_TMC_Y_Step_Dis, TMC_Y_Step_buf_ch, 16, true); + dgus.writeVariable(VP_TMC_Y_Step_Dis, TMC_Y_Step_buf_ch, 16, true); const uint16_t TMC_Z_Step_buf_ch[] = { 0x205A, 0xE9C1, 0xF4C3, 0xC8B6, 0x2000 }; - dgusdisplay.WriteVariable(VP_TMC_Z_Step_Dis, TMC_Z_Step_buf_ch, 16, true); + dgus.writeVariable(VP_TMC_Z_Step_Dis, TMC_Z_Step_buf_ch, 16, true); const uint16_t Info_PrintFinish_1_buf_ch[] = { 0xF2B4, 0xA1D3, 0xEACD, 0xC9B3, 0x2000 }; - dgusdisplay.WriteVariable(VP_Info_PrintFinish_1_Dis, Info_PrintFinish_1_buf_ch, 32, true); + dgus.writeVariable(VP_Info_PrintFinish_1_Dis, Info_PrintFinish_1_buf_ch, 32, true); const uint16_t TMC_X_Current_buf_ch[] = { 0x2058, 0xE1D6, 0xE7B5, 0xF7C1, 0x2000 }; - dgusdisplay.WriteVariable(VP_TMC_X_Current_Dis, TMC_X_Current_buf_ch, 16, true); + dgus.writeVariable(VP_TMC_X_Current_Dis, TMC_X_Current_buf_ch, 16, true); const uint16_t TMC_Y_Current_buf_ch[] = { 0x2059, 0xE1D6, 0xE7B5, 0xF7C1, 0x2000 }; - dgusdisplay.WriteVariable(VP_TMC_Y_Current_Dis, TMC_Y_Current_buf_ch, 16, true); + dgus.writeVariable(VP_TMC_Y_Current_Dis, TMC_Y_Current_buf_ch, 16, true); const uint16_t TMC_Z_Current_buf_ch[] = { 0x205A, 0xE1D6, 0xE7B5, 0xF7C1, 0x2000 }; - dgusdisplay.WriteVariable(VP_TMC_Z_Current_Dis, TMC_Z_Current_buf_ch, 16, true); + dgus.writeVariable(VP_TMC_Z_Current_Dis, TMC_Z_Current_buf_ch, 16, true); const uint16_t TMC_E0_Current_buf_ch[] = { 0x3045, 0xE1D6, 0xE7B5, 0xF7C1, 0x2000 }; - dgusdisplay.WriteVariable(VP_TMC_E0_Current_Dis, TMC_E0_Current_buf_ch, 16, true); + dgus.writeVariable(VP_TMC_E0_Current_Dis, TMC_E0_Current_buf_ch, 16, true); const uint16_t TMC_X1_Current_buf_ch[] = { 0x3158, 0xE1D6, 0xE7B5, 0xF7C1, 0x2000 }; - dgusdisplay.WriteVariable(VP_TMC_X1_Current_Dis, TMC_X1_Current_buf_ch, 16, true); + dgus.writeVariable(VP_TMC_X1_Current_Dis, TMC_X1_Current_buf_ch, 16, true); const uint16_t TMC_Y1_Current_buf_ch[] = { 0x3159, 0xE1D6, 0xE7B5, 0xF7C1, 0x2000 }; - dgusdisplay.WriteVariable(VP_TMC_Y1_Current_Dis, TMC_Y1_Current_buf_ch, 16, true); + dgus.writeVariable(VP_TMC_Y1_Current_Dis, TMC_Y1_Current_buf_ch, 16, true); const uint16_t TMC_Z1_Current_buf_ch[] = { 0x315A, 0xE1D6, 0xE7B5, 0xF7C1, 0x2000 }; - dgusdisplay.WriteVariable(VP_TMC_Z1_Current_Dis, TMC_Z1_Current_buf_ch, 16, true); + dgus.writeVariable(VP_TMC_Z1_Current_Dis, TMC_Z1_Current_buf_ch, 16, true); const uint16_t TMC_E1_Current_buf_ch[] = { 0x3145, 0xE1D6, 0xE7B5, 0xF7C1, 0x2000 }; - dgusdisplay.WriteVariable(VP_TMC_E1_Current_Dis, TMC_E1_Current_buf_ch, 16, true); + dgus.writeVariable(VP_TMC_E1_Current_Dis, TMC_E1_Current_buf_ch, 16, true); const uint16_t Min_Ex_Temp_buf_ch[] = { 0xEED7, 0xA1D0, 0xB7BC, 0xF6B3, 0xC2CE, 0xC8B6, 0x2000 }; - dgusdisplay.WriteVariable(VP_Min_Ex_Temp_Dis, Min_Ex_Temp_buf_ch, 32, true); + dgus.writeVariable(VP_Min_Ex_Temp_Dis, Min_Ex_Temp_buf_ch, 32, true); const uint16_t AutoLEVEL_INFO1_buf_ch[] = { 0xEBC7, 0xB4B0, 0xC2CF, 0xB4B0, 0xA5C5, 0x2000 }; - dgusdisplay.WriteVariable(VP_AutoLEVEL_INFO1, AutoLEVEL_INFO1_buf_ch, 32, true); + dgus.writeVariable(VP_AutoLEVEL_INFO1, AutoLEVEL_INFO1_buf_ch, 32, true); const uint16_t EX_TEMP_INFO2_buf_ch[] = { 0xEBC7, 0xD4C9, 0xC8B5, 0x2000 }; - dgusdisplay.WriteVariable(VP_EX_TEMP_INFO2_Dis, EX_TEMP_INFO2_buf_ch, 32, true); + dgus.writeVariable(VP_EX_TEMP_INFO2_Dis, EX_TEMP_INFO2_buf_ch, 32, true); const uint16_t EX_TEMP_INFO3_buf_ch[] = { 0xA1C8, 0xFBCF, 0xD3BC, 0xC8C8, 0x2000 }; - dgusdisplay.WriteVariable(VP_EX_TEMP_INFO3_Dis, EX_TEMP_INFO3_buf_ch, 32, true); + dgus.writeVariable(VP_EX_TEMP_INFO3_Dis, EX_TEMP_INFO3_buf_ch, 32, true); const uint16_t PrintConfrim_Info_buf_ch[] = { 0xC7CA, 0xF1B7, 0xAABF, 0xBCCA, 0xF2B4, 0xA1D3, 0x2000 }; - dgusdisplay.WriteVariable(VP_PrintConfrim_Info_Dis, PrintConfrim_Info_buf_ch, 32, true); + dgus.writeVariable(VP_PrintConfrim_Info_Dis, PrintConfrim_Info_buf_ch, 32, true); const uint16_t StopPrintConfrim_Info_buf_ch[] = { 0xC7CA, 0xF1B7, 0xA3CD, 0xB9D6, 0xF2B4, 0xA1D3, 0x2000 }; - dgusdisplay.WriteVariable(VP_StopPrintConfrim_Info_Dis, StopPrintConfrim_Info_buf_ch, 32, true); + dgus.writeVariable(VP_StopPrintConfrim_Info_Dis, StopPrintConfrim_Info_buf_ch, 32, true); const uint16_t Printting_buf_ch[] = { 0xF2B4, 0xA1D3, 0xD0D6, 0x2000 }; - dgusdisplay.WriteVariable(VP_Printting_Dis, Printting_buf_ch, 32, true); + dgus.writeVariable(VP_Printting_Dis, Printting_buf_ch, 32, true); const uint16_t LCD_BLK_buf_ch[] = { 0xB3B1, 0xE2B9, 0xE8C9, 0xC3D6, 0x2000 }; - dgusdisplay.WriteVariable(VP_LCD_BLK_Dis, LCD_BLK_buf_ch, 32, true); + dgus.writeVariable(VP_LCD_BLK_Dis, LCD_BLK_buf_ch, 32, true); } } diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h index 69ded29ffbc7..9527badb5a79 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h @@ -23,7 +23,7 @@ #include "../DGUSScreenHandlerBase.h" -enum DGUSLCD_Screens : uint8_t; +enum DGUS_ScreenID : uint8_t; class DGUSScreenHandlerMKS : public DGUSScreenHandler { public: @@ -32,72 +32,72 @@ class DGUSScreenHandlerMKS : public DGUSScreenHandler { #if 0 static void sendinfoscreen_ch(const uint16_t *line1, const uint16_t *line2, const uint16_t *line3, const uint16_t *line4); static void sendinfoscreen_en(PGM_P const line1, PGM_P const line2, PGM_P const line3, PGM_P const line4); - static void sendinfoscreen(const void *line1, const void *line2, const void *line3, const void *line4, uint16_t language); + static void sendInfoScreen(const void *line1, const void *line2, const void *line3, const void *line4, uint16_t language); #endif - static void ScreenBackChange(DGUS_VP_Variable &var, void *val_ptr); - - static void EEPROM_CTRL(DGUS_VP_Variable &var, void *val_ptr); - static void LanguageChange(DGUS_VP_Variable &var, void *val_ptr); - static void GetOffsetValue(DGUS_VP_Variable &var, void *val_ptr); - static void Level_Ctrl(DGUS_VP_Variable &var, void *val_ptr); - static void MeshLevel(DGUS_VP_Variable &var, void *val_ptr); - static void MeshLevelDistanceConfig(DGUS_VP_Variable &var, void *val_ptr); - static void ManualAssistLeveling(DGUS_VP_Variable &var, void *val_ptr); - static void ZoffsetConfirm(DGUS_VP_Variable &var, void *val_ptr); - static void Z_offset_select(DGUS_VP_Variable &var, void *val_ptr); - static void GetManualMovestep(DGUS_VP_Variable &var, void *val_ptr); - static void GetZoffsetDistance(DGUS_VP_Variable &var, void *val_ptr); - static void GetMinExtrudeTemp(DGUS_VP_Variable &var, void *val_ptr); - static void GetParkPos(DGUS_VP_Variable &var, void *val_ptr); + static void screenBackChange(DGUS_VP_Variable &var, void *val_ptr); + + static void eepromControl(DGUS_VP_Variable &var, void *val_ptr); + static void languageChange(DGUS_VP_Variable &var, void *val_ptr); + static void getOffsetValue(DGUS_VP_Variable &var, void *val_ptr); + static void levelControl(DGUS_VP_Variable &var, void *val_ptr); + static void meshLevel(DGUS_VP_Variable &var, void *val_ptr); + static void meshLevelDistanceConfig(DGUS_VP_Variable &var, void *val_ptr); + static void manualAssistLeveling(DGUS_VP_Variable &var, void *val_ptr); + static void zOffsetConfirm(DGUS_VP_Variable &var, void *val_ptr); + static void zOffsetSelect(DGUS_VP_Variable &var, void *val_ptr); + static void getManualMovestep(DGUS_VP_Variable &var, void *val_ptr); + static void getZoffsetDistance(DGUS_VP_Variable &var, void *val_ptr); + static void getMinExtrudeTemp(DGUS_VP_Variable &var, void *val_ptr); + static void getParkPos(DGUS_VP_Variable &var, void *val_ptr); #if ENABLED(PREVENT_COLD_EXTRUSION) - static void HandleGetExMinTemp(DGUS_VP_Variable &var, void *val_ptr); + static void handleGetExMinTemp(DGUS_VP_Variable &var, void *val_ptr); #endif - static void DGUS_LanguageDisplay(uint8_t var); - static void TMC_ChangeConfig(DGUS_VP_Variable &var, void *val_ptr); - static void GetTurnOffCtrl(DGUS_VP_Variable &var, void *val_ptr); - static void LanguagePInit(); - static void DGUS_Runout_Idle(); - static void DGUS_RunoutInit(); - static void DGUS_ExtrudeLoadInit(); - static void LCD_BLK_Adjust(DGUS_VP_Variable &var, void *val_ptr); - static void SD_FileBack(DGUS_VP_Variable &var, void *val_ptr); - - static void HandleStepPerMMChanged(DGUS_VP_Variable &var, void *val_ptr); - static void HandleStepPerMMExtruderChanged(DGUS_VP_Variable &var, void *val_ptr); - static void HandleMaxSpeedChange(DGUS_VP_Variable &var, void *val_ptr); - static void HandleExtruderMaxSpeedChange(DGUS_VP_Variable &var, void *val_ptr); - static void HandleAccChange(DGUS_VP_Variable &var, void *val_ptr); - static void HandleMaxAccChange(DGUS_VP_Variable &var, void *val_ptr); - static void HandleExtruderAccChange(DGUS_VP_Variable &var, void *val_ptr); - static void HandleChangeLevelPoint(DGUS_VP_Variable &var, void *val_ptr); - static void HandleTravelAccChange(DGUS_VP_Variable &var, void *val_ptr); - static void HandleFeedRateMinChange(DGUS_VP_Variable &var, void *val_ptr); - static void HandleMin_T_F(DGUS_VP_Variable &var, void *val_ptr); + static void languageDisplay(uint8_t var); + static void tmcChangeConfig(DGUS_VP_Variable &var, void *val_ptr); + static void getTurnOffCtrl(DGUS_VP_Variable &var, void *val_ptr); + static void languagePInit(); + static void runoutIdle(); + static void runoutInit(); + static void extrudeLoadInit(); + static void lcdBLKAdjust(DGUS_VP_Variable &var, void *val_ptr); + static void sdFileBack(DGUS_VP_Variable &var, void *val_ptr); + + static void handleStepPerMMChanged(DGUS_VP_Variable &var, void *val_ptr); + static void handleStepPerMMExtruderChanged(DGUS_VP_Variable &var, void *val_ptr); + static void handleMaxSpeedChange(DGUS_VP_Variable &var, void *val_ptr); + static void handleExtruderMaxSpeedChange(DGUS_VP_Variable &var, void *val_ptr); + static void handleAccChange(DGUS_VP_Variable &var, void *val_ptr); + static void handleMaxAccChange(DGUS_VP_Variable &var, void *val_ptr); + static void handleExtruderAccChange(DGUS_VP_Variable &var, void *val_ptr); + static void handleChangeLevelPoint(DGUS_VP_Variable &var, void *val_ptr); + static void handleTravelAccChange(DGUS_VP_Variable &var, void *val_ptr); + static void handleFeedRateMinChange(DGUS_VP_Variable &var, void *val_ptr); + static void handleMin_T_F(DGUS_VP_Variable &var, void *val_ptr); #if HAS_PID_HEATING - static void FilamentLoadUnload(DGUS_VP_Variable &var, void *val_ptr, const int filamentDir); - static void FilamentLoad(DGUS_VP_Variable &var, void *val_ptr); - static void FilamentUnLoad(DGUS_VP_Variable &var, void *val_ptr); - static void GetManualFilament(DGUS_VP_Variable &var, void *val_ptr); - static void GetManualFilamentSpeed(DGUS_VP_Variable &var, void *val_ptr); + static void filamentLoadUnload(DGUS_VP_Variable &var, void *val_ptr, const int filamentDir); + static void filamentLoad(DGUS_VP_Variable &var, void *val_ptr); + static void filamentUnload(DGUS_VP_Variable &var, void *val_ptr); + static void getManualFilament(DGUS_VP_Variable &var, void *val_ptr); + static void getManualFilamentSpeed(DGUS_VP_Variable &var, void *val_ptr); #endif #if HAS_MEDIA // Marlin informed us about SD print completion. - static void SDPrintingFinished(); + static void sdPrintingFinished(); #else - static void PrintReturn(DGUS_VP_Variable &var, void *val_ptr); + static void printReturn(DGUS_VP_Variable &var, void *val_ptr); #endif - static void DGUSLCD_SendPrintTimeToDisplay(DGUS_VP_Variable &var); - static void DGUSLCD_SendBabyStepToDisplay(DGUS_VP_Variable &var); - static void DGUSLCD_SendFanToDisplay(DGUS_VP_Variable &var); - static void DGUSLCD_SendGbkToDisplay(DGUS_VP_Variable &var); - static void DGUSLCD_SendStringToDisplay_Language(DGUS_VP_Variable &var); - static void DGUSLCD_SendTMCStepValue(DGUS_VP_Variable &var); + static void sendPrintTimeToDisplay(DGUS_VP_Variable &var); + static void sendBabyStepToDisplay(DGUS_VP_Variable &var); + static void sendFanToDisplay(DGUS_VP_Variable &var); + static void sendGbkToDisplay(DGUS_VP_Variable &var); + static void sendStringToDisplay_Language(DGUS_VP_Variable &var); + static void sendTMCStepValue(DGUS_VP_Variable &var); - static void DGUSLCD_SetUint8(DGUS_VP_Variable &var, void *val_ptr); + static void setUint8(DGUS_VP_Variable &var, void *val_ptr); static bool loop(); }; diff --git a/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.cpp index c5711320ec18..d69041ebc5e0 100644 --- a/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.cpp +++ b/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.cpp @@ -108,17 +108,17 @@ const uint16_t VPList_SDFileList[] PROGMEM = { VP_SD_FileName0, VP_SD_ const uint16_t VPList_SD_PrintManipulation[] PROGMEM = { VP_PrintProgress_Percentage, VP_PrintTime, 0x0000 }; const struct VPMapping VPMap[] PROGMEM = { - { DGUSLCD_SCREEN_BOOT, VPList_Boot }, - { DGUSLCD_SCREEN_MAIN, VPList_Main }, - { DGUSLCD_SCREEN_TEMPERATURE, VPList_Temp }, - { DGUSLCD_SCREEN_STATUS, VPList_Status }, - { DGUSLCD_SCREEN_STATUS2, VPList_Status2 }, - { DGUSLCD_SCREEN_MANUALMOVE, VPList_ManualMove }, - { DGUSLCD_SCREEN_MANUALEXTRUDE, VPList_ManualExtrude }, - { DGUSLCD_SCREEN_FANANDFEEDRATE, VPList_FanAndFeedrate }, - { DGUSLCD_SCREEN_FLOWRATES, VPList_SD_FlowRates }, - { DGUSLCD_SCREEN_SDPRINTMANIPULATION, VPList_SD_PrintManipulation }, - { DGUSLCD_SCREEN_SDFILELIST, VPList_SDFileList }, + { DGUS_SCREEN_BOOT, VPList_Boot }, + { DGUS_SCREEN_MAIN, VPList_Main }, + { DGUS_SCREEN_TEMPERATURE, VPList_Temp }, + { DGUS_SCREEN_STATUS, VPList_Status }, + { DGUS_SCREEN_STATUS2, VPList_Status2 }, + { DGUS_SCREEN_MANUALMOVE, VPList_ManualMove }, + { DGUS_SCREEN_MANUALEXTRUDE, VPList_ManualExtrude }, + { DGUS_SCREEN_FANANDFEEDRATE, VPList_FanAndFeedrate }, + { DGUS_SCREEN_FLOWRATES, VPList_SD_FlowRates }, + { DGUS_SCREEN_SDPRINTMANIPULATION, VPList_SD_PrintManipulation }, + { DGUS_SCREEN_SDFILELIST, VPList_SDFileList }, { 0 , nullptr } // List is terminated with an nullptr as table entry. }; @@ -126,152 +126,152 @@ const char MarlinVersion[] PROGMEM = SHORT_BUILD_VERSION; const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { // Helper to detect touch events - VPHELPER(VP_SCREENCHANGE, nullptr, ScreenHandler.ScreenChangeHook, nullptr), - VPHELPER(VP_SCREENCHANGE_ASK, nullptr, ScreenHandler.ScreenChangeHookIfIdle, nullptr), + VPHELPER(VP_SCREENCHANGE, nullptr, screen.screenChangeHook, nullptr), + VPHELPER(VP_SCREENCHANGE_ASK, nullptr, screen.screenChangeHookIfIdle, nullptr), #if HAS_MEDIA - VPHELPER(VP_SCREENCHANGE_WHENSD, nullptr, ScreenHandler.ScreenChangeHookIfSD, nullptr), + VPHELPER(VP_SCREENCHANGE_WHENSD, nullptr, screen.screenChangeHookIfSD, nullptr), #endif - VPHELPER(VP_CONFIRMED, nullptr, ScreenHandler.ScreenConfirmedOK, nullptr), + VPHELPER(VP_CONFIRMED, nullptr, screen.screenConfirmedOK, nullptr), - VPHELPER(VP_TEMP_ALL_OFF, nullptr, ScreenHandler.HandleAllHeatersOff, nullptr), + VPHELPER(VP_TEMP_ALL_OFF, nullptr, screen.handleAllHeatersOff, nullptr), #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) - VPHELPER(VP_MOVE_OPTION, &distanceToMove, ScreenHandler.HandleManualMoveOption, nullptr), + VPHELPER(VP_MOVE_OPTION, &distanceToMove, screen.handleManualMoveOption, nullptr), #endif #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) - VPHELPER(VP_MOVE_X, &distanceToMove, ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Y, &distanceToMove, ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Z, &distanceToMove, ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_HOME_ALL, &distanceToMove, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_X, &distanceToMove, screen.handleManualMove, nullptr), + VPHELPER(VP_MOVE_Y, &distanceToMove, screen.handleManualMove, nullptr), + VPHELPER(VP_MOVE_Z, &distanceToMove, screen.handleManualMove, nullptr), + VPHELPER(VP_HOME_ALL, &distanceToMove, screen.handleManualMove, nullptr), #else - VPHELPER(VP_MOVE_X, nullptr, ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Y, nullptr, ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Z, nullptr, ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_HOME_ALL, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_X, nullptr, screen.handleManualMove, nullptr), + VPHELPER(VP_MOVE_Y, nullptr, screen.handleManualMove, nullptr), + VPHELPER(VP_MOVE_Z, nullptr, screen.handleManualMove, nullptr), + VPHELPER(VP_HOME_ALL, nullptr, screen.handleManualMove, nullptr), #endif - VPHELPER(VP_MOTOR_LOCK_UNLOK, nullptr, ScreenHandler.HandleMotorLockUnlock, nullptr), + VPHELPER(VP_MOTOR_LOCK_UNLOK, nullptr, screen.handleMotorLockUnlock, nullptr), #if ENABLED(POWER_LOSS_RECOVERY) - VPHELPER(VP_POWER_LOSS_RECOVERY, nullptr, ScreenHandler.HandlePowerLossRecovery, nullptr), + VPHELPER(VP_POWER_LOSS_RECOVERY, nullptr, screen.handlePowerLossRecovery, nullptr), #endif - VPHELPER(VP_SETTINGS, nullptr, ScreenHandler.HandleSettings, nullptr), + VPHELPER(VP_SETTINGS, nullptr, screen.handleSettings, nullptr), - { .VP = VP_MARLIN_VERSION, .memadr = (void*)MarlinVersion, .size = VP_MARLIN_VERSION_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + { .VP = VP_MARLIN_VERSION, .memadr = (void*)MarlinVersion, .size = VP_MARLIN_VERSION_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = screen.sendStringToDisplayPGM }, // M117 LCD String (We don't need the string in memory but "just" push it to the display on demand, hence the nullptr - { .VP = VP_M117, .memadr = nullptr, .size = VP_M117_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplay }, + { .VP = VP_M117, .memadr = nullptr, .size = VP_M117_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = screen.sendStringToDisplay }, // Temperature Data #if HAS_HOTEND - VPHELPER(VP_T_E0_Is, &thermalManager.temp_hotend[0].celsius, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<0>), - VPHELPER(VP_T_E0_Set, &thermalManager.temp_hotend[0].target, ScreenHandler.HandleTemperatureChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_Flowrate_E0, nullptr, ScreenHandler.HandleFlowRateChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_EPos, &destination.e, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), - VPHELPER(VP_MOVE_E0, nullptr, ScreenHandler.HandleManualExtrude, nullptr), - VPHELPER(VP_E0_CONTROL, &thermalManager.temp_hotend[0].target, ScreenHandler.HandleHeaterControl, nullptr), - VPHELPER(VP_E0_STATUS, &thermalManager.temp_hotend[0].target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), + VPHELPER(VP_T_E0_Is, &thermalManager.temp_hotend[0].celsius, nullptr, screen.sendFloatAsLongValueToDisplay<0>), + VPHELPER(VP_T_E0_Set, &thermalManager.temp_hotend[0].target, screen.handleTemperatureChanged, &screen.sendWordValueToDisplay), + VPHELPER(VP_Flowrate_E0, nullptr, screen.handleFlowRateChanged, screen.sendWordValueToDisplay), + VPHELPER(VP_EPos, &destination.e, nullptr, screen.sendFloatAsLongValueToDisplay<2>), + VPHELPER(VP_MOVE_E0, nullptr, screen.handleManualExtrude, nullptr), + VPHELPER(VP_E0_CONTROL, &thermalManager.temp_hotend[0].target, screen.handleHeaterControl, nullptr), + VPHELPER(VP_E0_STATUS, &thermalManager.temp_hotend[0].target, nullptr, screen.sendHeaterStatusToDisplay), #if ENABLED(DGUS_PREHEAT_UI) - VPHELPER(VP_E0_BED_PREHEAT, nullptr, ScreenHandler.HandlePreheat, nullptr), + VPHELPER(VP_E0_BED_PREHEAT, nullptr, screen.handlePreheat, nullptr), #endif #if ENABLED(PIDTEMP) - VPHELPER(VP_E0_PID_P, &thermalManager.temp_hotend[0].pid.Kp, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_E0_PID_I, &thermalManager.temp_hotend[0].pid.Ki, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_E0_PID_D, &thermalManager.temp_hotend[0].pid.Kd, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_PID_AUTOTUNE_E0, nullptr, ScreenHandler.HandlePIDAutotune, nullptr), + VPHELPER(VP_E0_PID_P, &thermalManager.temp_hotend[0].pid.Kp, screen.handleTemperaturePIDChanged, screen.sendTemperaturePID), + VPHELPER(VP_E0_PID_I, &thermalManager.temp_hotend[0].pid.Ki, screen.handleTemperaturePIDChanged, screen.sendTemperaturePID), + VPHELPER(VP_E0_PID_D, &thermalManager.temp_hotend[0].pid.Kd, screen.handleTemperaturePIDChanged, screen.sendTemperaturePID), + VPHELPER(VP_PID_AUTOTUNE_E0, nullptr, screen.handlePIDAutotune, nullptr), #endif #if ENABLED(DGUS_FILAMENT_LOADUNLOAD) - VPHELPER(VP_E0_FILAMENT_LOAD_UNLOAD, nullptr, ScreenHandler.HandleFilamentOption, ScreenHandler.HandleFilamentLoadUnload), + VPHELPER(VP_E0_FILAMENT_LOAD_UNLOAD, nullptr, screen.handleFilamentOption, screen.handleFilamentLoadUnload), #endif #endif #if HAS_MULTI_HOTEND - VPHELPER(VP_T_E1_Is, &thermalManager.temp_hotend[1].celsius, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<0>), - VPHELPER(VP_T_E1_Set, &thermalManager.temp_hotend[1].target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_Flowrate_E1, nullptr, ScreenHandler.HandleFlowRateChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_MOVE_E1, nullptr, ScreenHandler.HandleManualExtrude, nullptr), - VPHELPER(VP_E1_CONTROL, &thermalManager.temp_hotend[1].target, ScreenHandler.HandleHeaterControl, nullptr), - VPHELPER(VP_E1_STATUS, &thermalManager.temp_hotend[1].target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), + VPHELPER(VP_T_E1_Is, &thermalManager.temp_hotend[1].celsius, nullptr, screen.sendFloatAsLongValueToDisplay<0>), + VPHELPER(VP_T_E1_Set, &thermalManager.temp_hotend[1].target, screen.handleTemperatureChanged, screen.sendWordValueToDisplay), + VPHELPER(VP_Flowrate_E1, nullptr, screen.handleFlowRateChanged, screen.sendWordValueToDisplay), + VPHELPER(VP_MOVE_E1, nullptr, screen.handleManualExtrude, nullptr), + VPHELPER(VP_E1_CONTROL, &thermalManager.temp_hotend[1].target, screen.handleHeaterControl, nullptr), + VPHELPER(VP_E1_STATUS, &thermalManager.temp_hotend[1].target, nullptr, screen.sendHeaterStatusToDisplay), #if ENABLED(PIDTEMP) - VPHELPER(VP_PID_AUTOTUNE_E1, nullptr, ScreenHandler.HandlePIDAutotune, nullptr), + VPHELPER(VP_PID_AUTOTUNE_E1, nullptr, screen.handlePIDAutotune, nullptr), #endif #endif #if HAS_HEATED_BED - VPHELPER(VP_T_Bed_Is, &thermalManager.temp_bed.celsius, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<0>), - VPHELPER(VP_T_Bed_Set, &thermalManager.temp_bed.target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_BED_CONTROL, &thermalManager.temp_bed.target, ScreenHandler.HandleHeaterControl, nullptr), - VPHELPER(VP_BED_STATUS, &thermalManager.temp_bed.target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), + VPHELPER(VP_T_Bed_Is, &thermalManager.temp_bed.celsius, nullptr, screen.sendFloatAsLongValueToDisplay<0>), + VPHELPER(VP_T_Bed_Set, &thermalManager.temp_bed.target, screen.handleTemperatureChanged, screen.sendWordValueToDisplay), + VPHELPER(VP_BED_CONTROL, &thermalManager.temp_bed.target, screen.handleHeaterControl, nullptr), + VPHELPER(VP_BED_STATUS, &thermalManager.temp_bed.target, nullptr, screen.sendHeaterStatusToDisplay), #if ENABLED(PIDTEMPBED) - VPHELPER(VP_BED_PID_P, &thermalManager.temp_bed.pid.Kp, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_BED_PID_I, &thermalManager.temp_bed.pid.Ki, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_BED_PID_D, &thermalManager.temp_bed.pid.Kd, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), + VPHELPER(VP_BED_PID_P, &thermalManager.temp_bed.pid.Kp, screen.handleTemperaturePIDChanged, screen.sendTemperaturePID), + VPHELPER(VP_BED_PID_I, &thermalManager.temp_bed.pid.Ki, screen.handleTemperaturePIDChanged, screen.sendTemperaturePID), + VPHELPER(VP_BED_PID_D, &thermalManager.temp_bed.pid.Kd, screen.handleTemperaturePIDChanged, screen.sendTemperaturePID), #endif #endif // Fan Data #if HAS_FAN #define FAN_VPHELPER(N) \ - VPHELPER(VP_Fan##N##_Percentage, &thermalManager.fan_speed[N], ScreenHandler.DGUSLCD_PercentageToUint8, ScreenHandler.DGUSLCD_SendPercentageToDisplay), \ - VPHELPER(VP_FAN##N##_CONTROL, &thermalManager.fan_speed[N], ScreenHandler.HandleFanControl, nullptr), \ - VPHELPER(VP_FAN##N##_STATUS, &thermalManager.fan_speed[N], nullptr, ScreenHandler.DGUSLCD_SendFanStatusToDisplay), + VPHELPER(VP_Fan##N##_Percentage, &thermalManager.fan_speed[N], screen.percentageToUint8, screen.sendPercentageToDisplay), \ + VPHELPER(VP_FAN##N##_CONTROL, &thermalManager.fan_speed[N], screen.handleFanControl, nullptr), \ + VPHELPER(VP_FAN##N##_STATUS, &thermalManager.fan_speed[N], nullptr, screen.sendFanStatusToDisplay), REPEAT(FAN_COUNT, FAN_VPHELPER) #endif // Feedrate - VPHELPER(VP_Feedrate_Percentage, &feedrate_percentage, ScreenHandler.DGUSLCD_SetValueDirectly, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Feedrate_Percentage, &feedrate_percentage, screen.setValueDirectly, screen.sendWordValueToDisplay), // Position Data - VPHELPER(VP_XPos, ¤t_position.x, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), - VPHELPER(VP_YPos, ¤t_position.y, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), - VPHELPER(VP_ZPos, ¤t_position.z, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), + VPHELPER(VP_XPos, ¤t_position.x, nullptr, screen.sendFloatAsLongValueToDisplay<2>), + VPHELPER(VP_YPos, ¤t_position.y, nullptr, screen.sendFloatAsLongValueToDisplay<2>), + VPHELPER(VP_ZPos, ¤t_position.z, nullptr, screen.sendFloatAsLongValueToDisplay<2>), // Print Progress - VPHELPER(VP_PrintProgress_Percentage, nullptr, nullptr, ScreenHandler.DGUSLCD_SendPrintProgressToDisplay), + VPHELPER(VP_PrintProgress_Percentage, nullptr, nullptr, screen.sendPrintProgressToDisplay), // Print Time - VPHELPER_STR(VP_PrintTime, nullptr, VP_PrintTime_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintTimeToDisplay), + VPHELPER_STR(VP_PrintTime, nullptr, VP_PrintTime_LEN, nullptr, screen.sendPrintTimeToDisplay), #if ENABLED(PRINTCOUNTER) - VPHELPER_STR(VP_PrintAccTime, nullptr, VP_PrintAccTime_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintAccTimeToDisplay), - VPHELPER_STR(VP_PrintsTotal, nullptr, VP_PrintsTotal_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintsTotalToDisplay), + VPHELPER_STR(VP_PrintAccTime, nullptr, VP_PrintAccTime_LEN, nullptr, screen.sendPrintAccTimeToDisplay), + VPHELPER_STR(VP_PrintsTotal, nullptr, VP_PrintsTotal_LEN, nullptr, screen.sendPrintsTotalToDisplay), #endif - VPHELPER(VP_X_STEP_PER_MM, &planner.settings.axis_steps_per_mm[X_AXIS], ScreenHandler.HandleStepPerMMChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), - VPHELPER(VP_Y_STEP_PER_MM, &planner.settings.axis_steps_per_mm[Y_AXIS], ScreenHandler.HandleStepPerMMChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), - VPHELPER(VP_Z_STEP_PER_MM, &planner.settings.axis_steps_per_mm[Z_AXIS], ScreenHandler.HandleStepPerMMChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), + VPHELPER(VP_X_STEP_PER_MM, &planner.settings.axis_steps_per_mm[X_AXIS], screen.handleStepPerMMChanged, screen.sendFloatAsIntValueToDisplay<1>), + VPHELPER(VP_Y_STEP_PER_MM, &planner.settings.axis_steps_per_mm[Y_AXIS], screen.handleStepPerMMChanged, screen.sendFloatAsIntValueToDisplay<1>), + VPHELPER(VP_Z_STEP_PER_MM, &planner.settings.axis_steps_per_mm[Z_AXIS], screen.handleStepPerMMChanged, screen.sendFloatAsIntValueToDisplay<1>), #if HAS_HOTEND - VPHELPER(VP_E0_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(0)], ScreenHandler.HandleStepPerMMExtruderChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), + VPHELPER(VP_E0_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(0)], screen.handleStepPerMMExtruderChanged, screen.sendFloatAsIntValueToDisplay<1>), #if HAS_MULTI_HOTEND - VPHELPER(VP_E1_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(1)], ScreenHandler.HandleStepPerMMExtruderChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), + VPHELPER(VP_E1_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(1)], screen.handleStepPerMMExtruderChanged, screen.sendFloatAsIntValueToDisplay<1>), #endif #endif // SDCard File listing. #if HAS_MEDIA - VPHELPER(VP_SD_ScrollEvent, nullptr, ScreenHandler.DGUSLCD_SD_ScrollFilelist, nullptr), - VPHELPER(VP_SD_FileSelected, nullptr, ScreenHandler.DGUSLCD_SD_FileSelected, nullptr), - VPHELPER(VP_SD_FileSelectConfirm, nullptr, ScreenHandler.DGUSLCD_SD_StartPrint, nullptr), - VPHELPER_STR(VP_SD_FileName0, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), - VPHELPER_STR(VP_SD_FileName1, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), - VPHELPER_STR(VP_SD_FileName2, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), - VPHELPER_STR(VP_SD_FileName3, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), - VPHELPER_STR(VP_SD_FileName4, nullptr, VP_SD_FileName_LEN, nullptr, ScreenHandler.DGUSLCD_SD_SendFilename), - VPHELPER(VP_SD_ResumePauseAbort, nullptr, ScreenHandler.DGUSLCD_SD_ResumePauseAbort, nullptr), - VPHELPER(VP_SD_AbortPrintConfirmed, nullptr, ScreenHandler.DGUSLCD_SD_ReallyAbort, nullptr), - VPHELPER(VP_SD_Print_Setting, nullptr, ScreenHandler.DGUSLCD_SD_PrintTune, nullptr), + VPHELPER(VP_SD_ScrollEvent, nullptr, screen.sdScrollFilelist, nullptr), + VPHELPER(VP_SD_FileSelected, nullptr, screen.sdFileSelected, nullptr), + VPHELPER(VP_SD_FileSelectConfirm, nullptr, screen.sdStartPrint, nullptr), + VPHELPER_STR(VP_SD_FileName0, nullptr, VP_SD_FileName_LEN, nullptr, screen.sdSendFilename), + VPHELPER_STR(VP_SD_FileName1, nullptr, VP_SD_FileName_LEN, nullptr, screen.sdSendFilename), + VPHELPER_STR(VP_SD_FileName2, nullptr, VP_SD_FileName_LEN, nullptr, screen.sdSendFilename), + VPHELPER_STR(VP_SD_FileName3, nullptr, VP_SD_FileName_LEN, nullptr, screen.sdSendFilename), + VPHELPER_STR(VP_SD_FileName4, nullptr, VP_SD_FileName_LEN, nullptr, screen.sdSendFilename), + VPHELPER(VP_SD_ResumePauseAbort, nullptr, screen.sdResumePauseAbort, nullptr), + VPHELPER(VP_SD_AbortPrintConfirmed, nullptr, screen.sdReallyAbort, nullptr), + VPHELPER(VP_SD_Print_Setting, nullptr, screen.sdPrintTune, nullptr), #if HAS_BED_PROBE - VPHELPER(VP_SD_Print_ProbeOffsetZ, &probe.offset.z, ScreenHandler.HandleProbeOffsetZChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<2>), + VPHELPER(VP_SD_Print_ProbeOffsetZ, &probe.offset.z, screen.handleProbeOffsetZChanged, screen.sendFloatAsIntValueToDisplay<2>), #if ENABLED(BABYSTEPPING) - VPHELPER(VP_SD_Print_LiveAdjustZ, nullptr, ScreenHandler.HandleLiveAdjustZ, nullptr), + VPHELPER(VP_SD_Print_LiveAdjustZ, nullptr, screen.handleLiveAdjustZ, nullptr), #endif #endif #endif #if ENABLED(DGUS_UI_WAITING) - VPHELPER(VP_WAITING_STATUS, nullptr, nullptr, ScreenHandler.DGUSLCD_SendWaitingStatusToDisplay), + VPHELPER(VP_WAITING_STATUS, nullptr, nullptr, screen.sendWaitingStatusToDisplay), #endif // Messages for the User, shared by the popup and the kill screen. They can't be autouploaded as we do not buffer content. - { .VP = VP_MSGSTR1, .memadr = nullptr, .size = VP_MSGSTR1_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, - { .VP = VP_MSGSTR2, .memadr = nullptr, .size = VP_MSGSTR2_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, - { .VP = VP_MSGSTR3, .memadr = nullptr, .size = VP_MSGSTR3_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, - { .VP = VP_MSGSTR4, .memadr = nullptr, .size = VP_MSGSTR4_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + { .VP = VP_MSGSTR1, .memadr = nullptr, .size = VP_MSGSTR1_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = screen.sendStringToDisplayPGM }, + { .VP = VP_MSGSTR2, .memadr = nullptr, .size = VP_MSGSTR2_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = screen.sendStringToDisplayPGM }, + { .VP = VP_MSGSTR3, .memadr = nullptr, .size = VP_MSGSTR3_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = screen.sendStringToDisplayPGM }, + { .VP = VP_MSGSTR4, .memadr = nullptr, .size = VP_MSGSTR4_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = screen.sendStringToDisplayPGM }, VPHELPER(0, 0, 0, 0) // must be last entry. }; diff --git a/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.h b/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.h index d529b0adfe60..e601abd25518 100644 --- a/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.h +++ b/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.h @@ -23,30 +23,30 @@ #include "../DGUSDisplayDef.h" -enum DGUSLCD_Screens : uint8_t { - DGUSLCD_SCREEN_BOOT = 0, - DGUSLCD_SCREEN_MAIN = 10, - DGUSLCD_SCREEN_TEMPERATURE = 20, - DGUSLCD_SCREEN_STATUS = 30, - DGUSLCD_SCREEN_STATUS2 = 32, - DGUSLCD_SCREEN_MANUALMOVE = 40, - DGUSLCD_SCREEN_MANUALEXTRUDE = 42, - DGUSLCD_SCREEN_FANANDFEEDRATE = 44, - DGUSLCD_SCREEN_FLOWRATES = 46, - DGUSLCD_SCREEN_SDFILELIST = 50, - DGUSLCD_SCREEN_SDPRINTMANIPULATION = 52, - DGUSLCD_SCREEN_POWER_LOSS = 100, - DGUSLCD_SCREEN_PREHEAT = 120, - DGUSLCD_SCREEN_UTILITY = 110, - DGUSLCD_SCREEN_FILAMENT_HEATING = 146, - DGUSLCD_SCREEN_FILAMENT_LOADING = 148, - DGUSLCD_SCREEN_FILAMENT_UNLOADING = 158, - DGUSLCD_SCREEN_SDPRINTTUNE = 170, - DGUSLCD_SCREEN_CONFIRM = 240, - DGUSLCD_SCREEN_KILL = 250, ///< Kill Screen. Must always be 250 (to be able to display "Error wrong LCD Version") - DGUSLCD_SCREEN_WAITING = 251, - DGUSLCD_SCREEN_POPUP = 252, ///< special target, popup screen will also return this code to say "return to previous screen" - DGUSLCD_SCREEN_UNUSED = 255 +enum DGUS_ScreenID : uint8_t { + DGUS_SCREEN_BOOT = 0, + DGUS_SCREEN_MAIN = 10, + DGUS_SCREEN_TEMPERATURE = 20, + DGUS_SCREEN_STATUS = 30, + DGUS_SCREEN_STATUS2 = 32, + DGUS_SCREEN_MANUALMOVE = 40, + DGUS_SCREEN_MANUALEXTRUDE = 42, + DGUS_SCREEN_FANANDFEEDRATE = 44, + DGUS_SCREEN_FLOWRATES = 46, + DGUS_SCREEN_SDFILELIST = 50, + DGUS_SCREEN_SDPRINTMANIPULATION = 52, + DGUS_SCREEN_POWER_LOSS = 100, + DGUS_SCREEN_PREHEAT = 120, + DGUS_SCREEN_UTILITY = 110, + DGUS_SCREEN_FILAMENT_HEATING = 146, + DGUS_SCREEN_FILAMENT_LOADING = 148, + DGUS_SCREEN_FILAMENT_UNLOADING = 158, + DGUS_SCREEN_SDPRINTTUNE = 170, + DGUS_SCREEN_CONFIRM = 240, + DGUS_SCREEN_KILL = 250, ///< Kill Screen. Must always be 250 (to be able to display "Error wrong LCD Version") + DGUS_SCREEN_WAITING = 251, + DGUS_SCREEN_POPUP = 252, ///< special target, popup screen will also return this code to say "return to previous screen" + DGUS_SCREEN_UNUSED = 255 }; // Display Memory layout used (T5UID) diff --git a/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp index 44f4a95cad2a..943d8c50a55e 100644 --- a/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp @@ -44,7 +44,7 @@ extern ExtUI::FileList filelist; - void DGUSScreenHandler::DGUSLCD_SD_FileSelected(DGUS_VP_Variable &var, void *val_ptr) { + void DGUSScreenHandler::sdFileSelected(DGUS_VP_Variable &var, void *val_ptr) { uint16_t touched_nr = (int16_t)swap16(*(uint16_t*)val_ptr) + top_file; if (touched_nr > filelist.count()) return; if (!filelist.seek(touched_nr)) return; @@ -52,28 +52,28 @@ if (filelist.isDir()) { filelist.changeDir(filelist.filename()); top_file = 0; - ForceCompleteUpdate(); + forceCompleteUpdate(); return; } #if ENABLED(DGUS_PRINT_FILENAME) // Send print filename - dgusdisplay.WriteVariable(VP_SD_Print_Filename, filelist.filename(), VP_SD_FileName_LEN, true); + dgus.writeVariable(VP_SD_Print_Filename, filelist.filename(), VP_SD_FileName_LEN, true); #endif // Setup Confirmation screen file_to_print = touched_nr; - HandleUserConfirmationPopUp(VP_SD_FileSelectConfirm, nullptr, PSTR("Print file"), filelist.filename(), PSTR("from SD Card?"), true, true, false, true); + handleUserConfirmationPopUp(VP_SD_FileSelectConfirm, nullptr, PSTR("Print file"), filelist.filename(), PSTR("from SD Card?"), true, true, false, true); } - void DGUSScreenHandler::DGUSLCD_SD_StartPrint(DGUS_VP_Variable &var, void *val_ptr) { + void DGUSScreenHandler::sdStartPrint(DGUS_VP_Variable &var, void *val_ptr) { if (!filelist.seek(file_to_print)) return; ExtUI::printFile(filelist.shortFilename()); - GotoScreen(DGUSLCD_SCREEN_STATUS); + gotoScreen(DGUS_SCREEN_STATUS); } - void DGUSScreenHandler::DGUSLCD_SD_ResumePauseAbort(DGUS_VP_Variable &var, void *val_ptr) { + void DGUSScreenHandler::sdResumePauseAbort(DGUS_VP_Variable &var, void *val_ptr) { if (!ExtUI::isPrintingFromMedia()) return; // avoid race condition when user stays in this menu and printer finishes. switch (swap16(*(uint16_t*)val_ptr)) { @@ -85,19 +85,19 @@ case 1: // Pause - GotoScreen(DGUSLCD_SCREEN_SDPRINTMANIPULATION); + gotoScreen(DGUS_SCREEN_SDPRINTMANIPULATION); if (!ExtUI::isPrintingFromMediaPaused()) { ExtUI::pausePrint(); //ExtUI::mks_pausePrint(); } break; case 2: // Abort - HandleUserConfirmationPopUp(VP_SD_AbortPrintConfirmed, nullptr, PSTR("Abort printing"), filelist.filename(), PSTR("?"), true, true, false, true); + handleUserConfirmationPopUp(VP_SD_AbortPrintConfirmed, nullptr, PSTR("Abort printing"), filelist.filename(), PSTR("?"), true, true, false, true); break; } } - void DGUSScreenHandler::DGUSLCD_SD_SendFilename(DGUS_VP_Variable& var) { + void DGUSScreenHandler::sdSendFilename(DGUS_VP_Variable& var) { uint16_t target_line = (var.VP - VP_SD_FileName0) / VP_SD_FileName_LEN; if (target_line > DGUS_SD_FILESPERSCREEN) return; char tmpfilename[VP_SD_FileName_LEN + 1] = ""; @@ -106,49 +106,49 @@ if (filelist.seek(top_file + target_line)) { snprintf_P(tmpfilename, VP_SD_FileName_LEN, PSTR("%s%c"), filelist.filename(), filelist.isDir() ? '/' : 0); // snprintf_P(tmpfilename, VP_SD_FileName_LEN, PSTR("%s"), filelist.filename()); } - DGUSLCD_SendStringToDisplay(var); + sendStringToDisplay(var); } - void DGUSScreenHandler::SDCardInserted() { + void DGUSScreenHandler::sdCardInserted() { top_file = 0; filelist.refresh(); auto cs = getCurrentScreen(); - if (cs == DGUSLCD_SCREEN_MAIN || cs == DGUSLCD_SCREEN_STATUS) - GotoScreen(DGUSLCD_SCREEN_SDFILELIST); + if (cs == DGUS_SCREEN_MAIN || cs == DGUS_SCREEN_STATUS) + gotoScreen(DGUS_SCREEN_SDFILELIST); } - void DGUSScreenHandler::SDCardRemoved() { - if (current_screen == DGUSLCD_SCREEN_SDFILELIST - || (current_screen == DGUSLCD_SCREEN_CONFIRM && (ConfirmVP == VP_SD_AbortPrintConfirmed || ConfirmVP == VP_SD_FileSelectConfirm)) - || current_screen == DGUSLCD_SCREEN_SDPRINTMANIPULATION - ) GotoScreen(DGUSLCD_SCREEN_MAIN); + void DGUSScreenHandler::sdCardRemoved() { + if (current_screenID == DGUS_SCREEN_SDFILELIST + || (current_screenID == DGUS_SCREEN_CONFIRM && (confirmVP == VP_SD_AbortPrintConfirmed || confirmVP == VP_SD_FileSelectConfirm)) + || current_screenID == DGUS_SCREEN_SDPRINTMANIPULATION + ) gotoScreen(DGUS_SCREEN_MAIN); } #endif // HAS_MEDIA -void DGUSScreenHandler::ScreenChangeHook(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandler::screenChangeHook(DGUS_VP_Variable &var, void *val_ptr) { uint8_t *tmp = (uint8_t*)val_ptr; // The keycode in target is coded as , so 0x0100A means - // from screen 1 (main) to 10 (temperature). DGUSLCD_SCREEN_POPUP is special, + // from screen 1 (main) to 10 (temperature). DGUS_SCREEN_POPUP is special, // meaning "return to previous screen" - DGUSLCD_Screens target = (DGUSLCD_Screens)tmp[1]; + DGUS_ScreenID target = (DGUS_ScreenID)tmp[1]; - if (target == DGUSLCD_SCREEN_POPUP) { + if (target == DGUS_SCREEN_POPUP) { // Special handling for popup is to return to previous menu - if (current_screen == DGUSLCD_SCREEN_POPUP && confirm_action_cb) confirm_action_cb(); - PopToOldScreen(); + if (current_screenID == DGUS_SCREEN_POPUP && confirm_action_cb) confirm_action_cb(); + popToOldScreen(); return; } - UpdateNewScreen(target); + updateNewScreen(target); #ifdef DEBUG_DGUSLCD - if (!DGUSLCD_FindScreenVPMapList(target)) DEBUG_ECHOLNPGM("WARNING: No screen Mapping found for ", target); + if (!findScreenVPMapList(target)) DEBUG_ECHOLNPGM("WARNING: No screen Mapping found for ", target); #endif } -void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { +void DGUSScreenHandler::handleManualMove(DGUS_VP_Variable &var, void *val_ptr) { int16_t movevalue = swap16(*(uint16_t*)val_ptr); #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) if (movevalue) { @@ -196,7 +196,7 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { char buf[6] = "G28 X"; buf[4] = axiscode; queue.enqueue_one_now(buf); - ForceCompleteUpdate(); + forceCompleteUpdate(); return; } else { @@ -219,14 +219,14 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { if (!old_relative_mode) queue.enqueue_now(F("G90")); } - ForceCompleteUpdate(); + forceCompleteUpdate(); cannotmove: return; } #if HAS_PID_HEATING - void DGUSScreenHandler::HandleTemperaturePIDChanged(DGUS_VP_Variable &var, void *val_ptr) { + void DGUSScreenHandler::handleTemperaturePIDChanged(DGUS_VP_Variable &var, void *val_ptr) { uint16_t rawvalue = swap16(*(uint16_t*)val_ptr); float value = (float)rawvalue / 10; float newvalue = 0; @@ -257,17 +257,17 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { #endif // HAS_PID_HEATING #if ENABLED(BABYSTEPPING) - void DGUSScreenHandler::HandleLiveAdjustZ(DGUS_VP_Variable &var, void *val_ptr) { + void DGUSScreenHandler::handleLiveAdjustZ(DGUS_VP_Variable &var, void *val_ptr) { int16_t flag = swap16(*(uint16_t*)val_ptr), steps = flag ? -20 : 20; ExtUI::smartAdjustAxis_steps(steps, ExtUI::axis_t::Z, true); - ForceCompleteUpdate(); + forceCompleteUpdate(); } #endif #if ENABLED(DGUS_FILAMENT_LOADUNLOAD) - void DGUSScreenHandler::HandleFilamentOption(DGUS_VP_Variable &var, void *val_ptr) { + void DGUSScreenHandler::handleFilamentOption(DGUS_VP_Variable &var, void *val_ptr) { uint8_t e_temp = 0; filament_data.heated = false; uint16_t preheat_option = swap16(*(uint16_t*)val_ptr); @@ -315,7 +315,7 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { thermalManager.setTargetHotend(e_temp, ExtUI::extruder_t::E1); #endif #endif - GotoScreen(DGUSLCD_SCREEN_UTILITY); + gotoScreen(DGUS_SCREEN_UTILITY); } else { // Go to the preheat screen to show the heating progress switch (var.VP) { @@ -333,11 +333,11 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { break; #endif } - GotoScreen(DGUSLCD_SCREEN_FILAMENT_HEATING); + gotoScreen(DGUS_SCREEN_FILAMENT_HEATING); } } - void DGUSScreenHandler::HandleFilamentLoadUnload(DGUS_VP_Variable &var) { + void DGUSScreenHandler::handleFilamentLoadUnload(DGUS_VP_Variable &var) { if (filament_data.action <= 0) return; // If we close to the target temperature, we can start load or unload the filament @@ -347,14 +347,14 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { if (filament_data.action == 1) { // load filament if (!filament_data.heated) { - //GotoScreen(DGUSLCD_SCREEN_FILAMENT_LOADING); + //gotoScreen(DGUS_SCREEN_FILAMENT_LOADING); filament_data.heated = true; } movevalue = ExtUI::getAxisPosition_mm(filament_data.extruder) + movevalue; } else { // unload filament if (!filament_data.heated) { - GotoScreen(DGUSLCD_SCREEN_FILAMENT_UNLOADING); + gotoScreen(DGUS_SCREEN_FILAMENT_UNLOADING); filament_data.heated = true; } // Before unloading extrude to prevent jamming @@ -372,14 +372,14 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { #endif // DGUS_FILAMENT_LOADUNLOAD bool DGUSScreenHandler::loop() { - dgusdisplay.loop(); + dgus.loop(); const millis_t ms = millis(); static millis_t next_event_ms = 0; - if (!IsScreenComplete() || ELAPSED(ms, next_event_ms)) { + if (!isScreenComplete() || ELAPSED(ms, next_event_ms)) { next_event_ms = ms + DGUS_UPDATE_INTERVAL_MS; - UpdateScreenVPData(); + updateScreenVPData(); } #if ENABLED(SHOW_BOOTSCREEN) @@ -390,11 +390,11 @@ bool DGUSScreenHandler::loop() { if (!booted && ELAPSED(ms, BOOTSCREEN_TIMEOUT)) { booted = true; - GotoScreen(TERN0(POWER_LOSS_RECOVERY, recovery.valid()) ? DGUSLCD_SCREEN_POWER_LOSS : DGUSLCD_SCREEN_MAIN); + gotoScreen(TERN0(POWER_LOSS_RECOVERY, recovery.valid()) ? DGUS_SCREEN_POWER_LOSS : DGUS_SCREEN_MAIN); } #endif - return IsScreenComplete(); + return isScreenComplete(); } #endif // DGUS_LCD_UI_ORIGIN diff --git a/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.h index 73e3527d7e7c..16c5dec408d6 100644 --- a/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.h +++ b/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.h @@ -26,6 +26,6 @@ typedef DGUSScreenHandler DGUSScreenHandlerClass; #if ENABLED(POWER_LOSS_RECOVERY) - #define PLR_SCREEN_RECOVER DGUSLCD_SCREEN_SDPRINTMANIPULATION - #define PLR_SCREEN_CANCEL DGUSLCD_SCREEN_STATUS + #define PLR_SCREEN_RECOVER DGUS_SCREEN_SDPRINTMANIPULATION + #define PLR_SCREEN_CANCEL DGUS_SCREEN_STATUS #endif diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSDisplay.cpp b/Marlin/src/lcd/extui/dgus_reloaded/DGUSDisplay.cpp index 7e215f887c5b..31272681804f 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSDisplay.cpp +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSDisplay.cpp @@ -50,26 +50,26 @@ uint8_t DGUSDisplay::rx_datagram_len = 0; bool DGUSDisplay::initialized = false; -void DGUSDisplay::Loop() { - ProcessRx(); +void DGUSDisplay::loop() { + processRx(); } -void DGUSDisplay::Init() { +void DGUSDisplay::init() { LCD_SERIAL.begin(LCD_BAUDRATE); - ReadVersions(); + readVersions(); } -void DGUSDisplay::Read(uint16_t addr, uint8_t size) { - WriteHeader(addr, DGUS_READVAR, size); +void DGUSDisplay::read(uint16_t addr, uint8_t size) { + writeHeader(addr, DGUS_READVAR, size); LCD_SERIAL.write(size); } -void DGUSDisplay::Write(uint16_t addr, const void* data_ptr, uint8_t size) { +void DGUSDisplay::write(uint16_t addr, const void* data_ptr, uint8_t size) { if (!data_ptr) return; - WriteHeader(addr, DGUS_WRITEVAR, size); + writeHeader(addr, DGUS_WRITEVAR, size); const char* data = static_cast(data_ptr); @@ -78,10 +78,10 @@ void DGUSDisplay::Write(uint16_t addr, const void* data_ptr, uint8_t size) { } } -void DGUSDisplay::WriteString(uint16_t addr, const void* data_ptr, uint8_t size, bool left, bool right, bool use_space) { +void DGUSDisplay::writeString(uint16_t addr, const void* data_ptr, uint8_t size, bool left, bool right, bool use_space) { if (!data_ptr) return; - WriteHeader(addr, DGUS_WRITEVAR, size); + writeHeader(addr, DGUS_WRITEVAR, size); const char* data = static_cast(data_ptr); size_t len = strlen(data); @@ -118,10 +118,10 @@ void DGUSDisplay::WriteString(uint16_t addr, const void* data_ptr, uint8_t size, } } -void DGUSDisplay::WriteStringPGM(uint16_t addr, const void* data_ptr, uint8_t size, bool left, bool right, bool use_space) { +void DGUSDisplay::writeStringPGM(uint16_t addr, const void* data_ptr, uint8_t size, bool left, bool right, bool use_space) { if (!data_ptr) return; - WriteHeader(addr, DGUS_WRITEVAR, size); + writeHeader(addr, DGUS_WRITEVAR, size); const char* data = static_cast(data_ptr); size_t len = strlen_P(data); @@ -151,61 +151,61 @@ void DGUSDisplay::WriteStringPGM(uint16_t addr, const void* data_ptr, uint8_t si while (right_spaces--) LCD_SERIAL.write(use_space ? ' ' : '\0'); } -void DGUSDisplay::ReadVersions() { +void DGUSDisplay::readVersions() { if (gui_version != 0 && os_version != 0) return; - Read(DGUS_VERSION, 1); + read(DGUS_VERSION, 1); } -void DGUSDisplay::SwitchScreen(DGUS_Screen screen) { - const uint8_t command[] = { 0x5A, 0x01, 0x00, (uint8_t)screen }; - Write(0x84, command, sizeof(command)); +void DGUSDisplay::switchScreen(const DGUS_ScreenID screenID) { + const uint8_t command[] = { 0x5A, 0x01, 0x00, (uint8_t)screenID }; + write(0x84, command, sizeof(command)); } -void DGUSDisplay::PlaySound(uint8_t start, uint8_t len, uint8_t volume) { +void DGUSDisplay::playSound(uint8_t start, uint8_t len, uint8_t volume) { if (volume == 0) volume = DGUSDisplay::volume; if (volume == 0) return; const uint8_t command[] = { start, len, volume, 0x00 }; - Write(0xA0, command, sizeof(command)); + write(0xA0, command, sizeof(command)); } -void DGUSDisplay::EnableControl(DGUS_Screen screen, DGUS_ControlType type, DGUS_Control control) { - const uint8_t command[] = { 0x5A, 0xA5, 0x00, (uint8_t)screen, (uint8_t)control, type, 0x00, 0x01 }; - Write(0xB0, command, sizeof(command)); +void DGUSDisplay::enableControl(const DGUS_ScreenID screenID, DGUS_ControlType type, DGUS_Control control) { + const uint8_t command[] = { 0x5A, 0xA5, 0x00, (uint8_t)screenID, (uint8_t)control, type, 0x00, 0x01 }; + write(0xB0, command, sizeof(command)); - FlushTx(); + flushTx(); delay(50); } -void DGUSDisplay::DisableControl(DGUS_Screen screen, DGUS_ControlType type, DGUS_Control control) { - const uint8_t command[] = { 0x5A, 0xA5, 0x00, (uint8_t)screen, (uint8_t)control, type, 0x00, 0x00 }; - Write(0xB0, command, sizeof(command)); +void DGUSDisplay::disableControl(const DGUS_ScreenID screenID, DGUS_ControlType type, DGUS_Control control) { + const uint8_t command[] = { 0x5A, 0xA5, 0x00, (uint8_t)screenID, (uint8_t)control, type, 0x00, 0x00 }; + write(0xB0, command, sizeof(command)); - FlushTx(); + flushTx(); delay(50); } -uint8_t DGUSDisplay::GetBrightness() { +uint8_t DGUSDisplay::getBrightness() { return brightness; } -uint8_t DGUSDisplay::GetVolume() { +uint8_t DGUSDisplay::getVolume() { return map_precise(volume, 0, 255, 0, 100); } -void DGUSDisplay::SetBrightness(uint8_t new_brightness) { +void DGUSDisplay::setBrightness(uint8_t new_brightness) { brightness = constrain(new_brightness, 0, 100); new_brightness = map_precise(brightness, 0, 100, 5, 100); const uint8_t command[] = { new_brightness, new_brightness }; - Write(0x82, command, sizeof(command)); + write(0x82, command, sizeof(command)); } -void DGUSDisplay::SetVolume(uint8_t new_volume) { +void DGUSDisplay::setVolume(uint8_t new_volume) { volume = map_precise(constrain(new_volume, 0, 100), 0, 100, 0, 255); const uint8_t command[] = { volume, 0x00 }; - Write(0xA1, command, sizeof(command)); + write(0xA1, command, sizeof(command)); } -void DGUSDisplay::ProcessRx() { +void DGUSDisplay::processRx() { #if ENABLED(LCD_SERIAL_STATS_RX_BUFFER_OVERRUNS) if (!LCD_SERIAL.available() && LCD_SERIAL.buffer_overruns()) { @@ -274,7 +274,7 @@ void DGUSDisplay::ProcessRx() { } DGUS_VP vp; - if (!DGUS_PopulateVP((DGUS_Addr)addr, &vp)) { + if (!populateVP((DGUS_Addr)addr, &vp)) { rx_datagram_state = DGUS_IDLE; break; } @@ -332,7 +332,7 @@ void DGUSDisplay::ProcessRx() { } } -size_t DGUSDisplay::GetFreeTxBuffer() { +size_t DGUSDisplay::getFreeTxBuffer() { return ( #ifdef LCD_SERIAL_GET_TX_BUFFER_FREE LCD_SERIAL_GET_TX_BUFFER_FREE() @@ -342,7 +342,7 @@ size_t DGUSDisplay::GetFreeTxBuffer() { ); } -void DGUSDisplay::FlushTx() { +void DGUSDisplay::flushTx() { #ifdef ARDUINO_ARCH_STM32 LCD_SERIAL.flush(); #else @@ -350,7 +350,7 @@ void DGUSDisplay::FlushTx() { #endif } -void DGUSDisplay::WriteHeader(uint16_t addr, uint8_t command, uint8_t len) { +void DGUSDisplay::writeHeader(uint16_t addr, uint8_t command, uint8_t len) { LCD_SERIAL.write(DGUS_HEADER1); LCD_SERIAL.write(DGUS_HEADER2); LCD_SERIAL.write(len + 3); @@ -359,7 +359,7 @@ void DGUSDisplay::WriteHeader(uint16_t addr, uint8_t command, uint8_t len) { LCD_SERIAL.write(addr & 0xFF); } -bool DGUS_PopulateVP(const DGUS_Addr addr, DGUS_VP * const buffer) { +bool populateVP(const DGUS_Addr addr, DGUS_VP * const buffer) { const DGUS_VP *ret = vp_list; do { diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSDisplay.h b/Marlin/src/lcd/extui/dgus_reloaded/DGUSDisplay.h index bfea5780a1f0..7c27162ce657 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSDisplay.h +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSDisplay.h @@ -26,7 +26,7 @@ * Updated for STM32G0B1RE by Protomosh in 2022. */ -#include "config/DGUS_Screen.h" +#include "config/DGUS_ScreenID.h" #include "config/DGUS_Control.h" #include "definition/DGUS_VP.h" @@ -58,58 +58,58 @@ class DGUSDisplay { DGUSDisplay() = default; - static void Init(); + static void init(); - static void Read(uint16_t addr, uint8_t size); - static void Write(uint16_t addr, const void* data_ptr, uint8_t size); + static void read(uint16_t addr, uint8_t size); + static void write(uint16_t addr, const void* data_ptr, uint8_t size); - static void WriteString(uint16_t addr, const void* data_ptr, uint8_t size, bool left=true, bool right=false, bool use_space=true); - static void WriteStringPGM(uint16_t addr, const void* data_ptr, uint8_t size, bool left=true, bool right=false, bool use_space=true); - static void WriteString(uint16_t addr, FSTR_P const fstr, uint8_t size, bool left=true, bool right=false, bool use_space=true) { - WriteStringPGM(addr, FTOP(fstr), size, left, right, use_space); + static void writeString(uint16_t addr, const void* data_ptr, uint8_t size, bool left=true, bool right=false, bool use_space=true); + static void writeStringPGM(uint16_t addr, const void* data_ptr, uint8_t size, bool left=true, bool right=false, bool use_space=true); + static void writeString(uint16_t addr, FSTR_P const fstr, uint8_t size, bool left=true, bool right=false, bool use_space=true) { + writeStringPGM(addr, FTOP(fstr), size, left, right, use_space); } template - static void Write(uint16_t addr, T data) { - Write(addr, static_cast(&data), sizeof(T)); + static void write(uint16_t addr, T data) { + write(addr, static_cast(&data), sizeof(T)); } // Until now I did not need to actively read from the display. That's why there is no ReadVariable // (I extensively use the auto upload of the display) // Read GUI and OS version from screen - static void ReadVersions(); + static void readVersions(); // Force display into another screen. - static void SwitchScreen(DGUS_Screen screen); + static void switchScreen(const DGUS_ScreenID screenID); // Play sounds using the display speaker. // start: position at which the sound was stored on the display. // len: how many sounds to play. Sounds will play consecutively from start to start+len-1. // volume: playback volume. 0 keeps the current volume. - static void PlaySound(uint8_t start, uint8_t len=1, uint8_t volume=0); + static void playSound(uint8_t start, uint8_t len=1, uint8_t volume=0); // Enable/disable a specific touch control. // type: control type. // control: index of the control on the page (set during screen development). - static void EnableControl(DGUS_Screen screen, DGUS_ControlType type, DGUS_Control control); - static void DisableControl(DGUS_Screen screen, DGUS_ControlType type, DGUS_Control control); + static void enableControl(const DGUS_ScreenID screenID, DGUS_ControlType type, DGUS_Control control); + static void disableControl(const DGUS_ScreenID screenID, DGUS_ControlType type, DGUS_Control control); - static uint8_t GetBrightness(); - static uint8_t GetVolume(); + static uint8_t getBrightness(); + static uint8_t getVolume(); // Set the display brightness/volume, ranging 0 - 100 - static void SetBrightness(uint8_t brightness); - static void SetVolume(uint8_t volume); + static void setBrightness(uint8_t brightness); + static void setVolume(uint8_t volume); // Periodic tasks, eg. Rx-Queue handling. - static void Loop(); + static void loop(); // Helper for users of this class to estimate if an interaction would be blocking. - static size_t GetFreeTxBuffer(); - static void FlushTx(); + static size_t getFreeTxBuffer(); + static void flushTx(); // Checks two things: Can we confirm the presence of the display and has we initialized it. // (both boils down that the display answered to our chatting) - static bool IsInitialized() { + static bool isInitialized() { return initialized; } @@ -117,24 +117,24 @@ class DGUSDisplay { static uint8_t os_version; template - static T SwapBytes(const T value) { + static T swapBytes(const T value) { union { T val; char byte[sizeof(T)]; } src, dst; src.val = value; - LOOP_L_N(i, sizeof(T)) dst.byte[i] = src.byte[sizeof(T) - i - 1]; + for (uint8_t i = 0; i < sizeof(T); ++i) dst.byte[i] = src.byte[sizeof(T) - i - 1]; return dst.val; } template - T_out FromFixedPoint(const T_in value) { + T_out fromFixedPoint(const T_in value) { return (T_out)((float)value / POW(10, decimals)); } template - T_out ToFixedPoint(const T_in value) { + T_out toFixedPoint(const T_in value) { return (T_out)LROUND((float)value * POW(10, decimals)); } @@ -160,8 +160,8 @@ class DGUSDisplay { DGUS_VERSION = 0x000F // OS/GUI version }; - static void WriteHeader(uint16_t addr, uint8_t command, uint8_t len); - static void ProcessRx(); + static void writeHeader(uint16_t addr, uint8_t command, uint8_t len); + static void processRx(); static uint8_t volume; static uint8_t brightness; @@ -172,11 +172,11 @@ class DGUSDisplay { static bool initialized; }; -template<> inline uint16_t DGUSDisplay::SwapBytes(const uint16_t value) { +template<> inline uint16_t DGUSDisplay::swapBytes(const uint16_t value) { return ((value << 8) | (value >> 8)); } -extern DGUSDisplay dgus_display; +extern DGUSDisplay dgus; /// Helper to populate a DGUS_VP for a given VP. Return false if not found. -extern bool DGUS_PopulateVP(const DGUS_Addr addr, DGUS_VP * const buffer); +extern bool populateVP(const DGUS_Addr addr, DGUS_VP * const buffer); diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.cpp b/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.cpp index 97ae7638c941..aa58e8569229 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.cpp +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.cpp @@ -27,7 +27,7 @@ #include "DGUSRxHandler.h" #include "DGUSScreenHandler.h" -#include "config/DGUS_Screen.h" +#include "config/DGUS_ScreenID.h" #include "../ui_api.h" #include "../../../core/language.h" @@ -42,73 +42,73 @@ #include "../../../feature/powerloss.h" #endif -void DGUSRxHandler::ScreenChange(DGUS_VP &vp, void *data_ptr) { - const DGUS_Screen screen = (DGUS_Screen)((uint8_t*)data_ptr)[1]; +void DGUSRxHandler::screenChange(DGUS_VP &vp, void *data_ptr) { + const DGUS_ScreenID screenID = (DGUS_ScreenID)((uint8_t*)data_ptr)[1]; if (vp.addr == DGUS_Addr::SCREENCHANGE_SD) { #if HAS_MEDIA IF_DISABLED(HAS_SD_DETECT, card.mount()); if (!ExtUI::isMediaInserted()) { - dgus_screen_handler.SetStatusMessage(GET_TEXT_F(MSG_NO_MEDIA)); + screen.setStatusMessage(GET_TEXT_F(MSG_NO_MEDIA)); return; } card.cdroot(); #else - dgus_screen_handler.SetStatusMessage(GET_TEXT_F(MSG_NO_MEDIA)); + screen.setStatusMessage(GET_TEXT_F(MSG_NO_MEDIA)); return; #endif } if (vp.addr == DGUS_Addr::SCREENCHANGE_Idle && (ExtUI::isPrinting() || ExtUI::isPrintingPaused())) { - dgus_screen_handler.SetStatusMessage(GET_TEXT_F(DGUS_MSG_NOT_WHILE_PRINTING)); + screen.setStatusMessage(GET_TEXT_F(DGUS_MSG_NOT_WHILE_PRINTING)); return; } if (vp.addr == DGUS_Addr::SCREENCHANGE_Printing && (!ExtUI::isPrinting() && !ExtUI::isPrintingPaused())) { - dgus_screen_handler.SetStatusMessage(GET_TEXT_F(DGUS_MSG_NOT_WHILE_IDLE)); + screen.setStatusMessage(GET_TEXT_F(DGUS_MSG_NOT_WHILE_IDLE)); return; } - dgus_screen_handler.TriggerScreenChange(screen); + screen.triggerScreenChange(screenID); } #if HAS_MEDIA - void DGUSRxHandler::Scroll(DGUS_VP &vp, void *data_ptr) { + void DGUSRxHandler::scroll(DGUS_VP &vp, void *data_ptr) { UNUSED(vp); const DGUS_Data::Scroll scroll = (DGUS_Data::Scroll)((uint8_t*)data_ptr)[1]; switch (scroll) { case DGUS_Data::Scroll::GO_BACK: - if (dgus_screen_handler.filelist.isAtRootDir()) { + if (screen.filelist.isAtRootDir()) { return; } - dgus_screen_handler.filelist_offset = 0; - dgus_screen_handler.filelist_selected = -1; - dgus_screen_handler.filelist.upDir(); + screen.filelist_offset = 0; + screen.filelist_selected = -1; + screen.filelist.upDir(); break; case DGUS_Data::Scroll::UP: - if (dgus_screen_handler.filelist_offset < 1) { + if (screen.filelist_offset < 1) { return; } - --dgus_screen_handler.filelist_offset; + --screen.filelist_offset; break; case DGUS_Data::Scroll::DOWN: - if (dgus_screen_handler.filelist_offset + 1 + DGUS_FILE_COUNT > dgus_screen_handler.filelist.count()) { + if (screen.filelist_offset + 1 + DGUS_FILE_COUNT > screen.filelist.count()) { return; } - ++dgus_screen_handler.filelist_offset; + ++screen.filelist_offset; break; } - dgus_screen_handler.TriggerFullUpdate(); + screen.triggerFullUpdate(); } void DGUSRxHandler::selectFile(DGUS_VP &vp, void *data_ptr) { @@ -116,47 +116,47 @@ void DGUSRxHandler::ScreenChange(DGUS_VP &vp, void *data_ptr) { const uint8_t index = ((uint8_t*)data_ptr)[1]; - if (!dgus_screen_handler.filelist.seek(dgus_screen_handler.filelist_offset + index)) { + if (!screen.filelist.seek(screen.filelist_offset + index)) { return; } - if (dgus_screen_handler.filelist.isDir()) { - dgus_screen_handler.filelist_offset = 0; - dgus_screen_handler.filelist_selected = -1; - dgus_screen_handler.filelist.changeDir(dgus_screen_handler.filelist.filename()); + if (screen.filelist.isDir()) { + screen.filelist_offset = 0; + screen.filelist_selected = -1; + screen.filelist.changeDir(screen.filelist.filename()); } else { - dgus_screen_handler.filelist_selected = dgus_screen_handler.filelist_offset + index; + screen.filelist_selected = screen.filelist_offset + index; } - dgus_screen_handler.TriggerFullUpdate(); + screen.triggerFullUpdate(); } - void DGUSRxHandler::PrintFile(DGUS_VP &vp, void *data_ptr) { + void DGUSRxHandler::printFile(DGUS_VP &vp, void *data_ptr) { UNUSED(vp); UNUSED(data_ptr); - if (dgus_screen_handler.filelist_selected < 0) { - dgus_screen_handler.SetStatusMessage(GET_TEXT_F(DGUS_MSG_NO_FILE_SELECTED)); + if (screen.filelist_selected < 0) { + screen.setStatusMessage(GET_TEXT_F(DGUS_MSG_NO_FILE_SELECTED)); return; } - if (!dgus_screen_handler.filelist.seek(dgus_screen_handler.filelist_selected) - || dgus_screen_handler.filelist.isDir()) { + if (!screen.filelist.seek(screen.filelist_selected) + || screen.filelist.isDir()) { return; } - if (!dgus_screen_handler.IsPrinterIdle()) { - dgus_screen_handler.SetStatusMessage(GET_TEXT_F(DGUS_MSG_BUSY)); + if (!screen.isPrinterIdle()) { + screen.setStatusMessage(GET_TEXT_F(DGUS_MSG_BUSY)); return; } - ExtUI::printFile(dgus_screen_handler.filelist.shortFilename()); - dgus_screen_handler.TriggerScreenChange(DGUS_Screen::PRINT_STATUS); + ExtUI::printFile(screen.filelist.shortFilename()); + screen.triggerScreenChange(DGUS_ScreenID::PRINT_STATUS); } #endif // HAS_MEDIA -void DGUSRxHandler::PrintAbort(DGUS_VP &vp, void *data_ptr) { +void DGUSRxHandler::printAbort(DGUS_VP &vp, void *data_ptr) { UNUSED(vp); const DGUS_Data::Popup result = (DGUS_Data::Popup)((uint8_t*)data_ptr)[1]; @@ -166,14 +166,14 @@ void DGUSRxHandler::PrintAbort(DGUS_VP &vp, void *data_ptr) { } if (!ExtUI::isPrinting() && !ExtUI::isPrintingPaused()) { - dgus_screen_handler.TriggerFullUpdate(); + screen.triggerFullUpdate(); return; } ExtUI::stopPrint(); } -void DGUSRxHandler::PrintPause(DGUS_VP &vp, void *data_ptr) { +void DGUSRxHandler::printPause(DGUS_VP &vp, void *data_ptr) { UNUSED(vp); const DGUS_Data::Popup result = (DGUS_Data::Popup)((uint8_t*)data_ptr)[1]; @@ -183,14 +183,14 @@ void DGUSRxHandler::PrintPause(DGUS_VP &vp, void *data_ptr) { } if (!ExtUI::isPrinting()) { - dgus_screen_handler.TriggerFullUpdate(); + screen.triggerFullUpdate(); return; } ExtUI::pausePrint(); } -void DGUSRxHandler::PrintResume(DGUS_VP &vp, void *data_ptr) { +void DGUSRxHandler::printResume(DGUS_VP &vp, void *data_ptr) { UNUSED(vp); const DGUS_Data::Popup result = (DGUS_Data::Popup)((uint8_t*)data_ptr)[1]; @@ -200,29 +200,29 @@ void DGUSRxHandler::PrintResume(DGUS_VP &vp, void *data_ptr) { } if (!ExtUI::isPrintingPaused()) { - dgus_screen_handler.TriggerFullUpdate(); + screen.triggerFullUpdate(); return; } - if (!dgus_screen_handler.IsPrinterIdle()) { - dgus_screen_handler.SetStatusMessage(GET_TEXT_F(DGUS_MSG_BUSY)); + if (!screen.isPrinterIdle()) { + screen.setStatusMessage(GET_TEXT_F(DGUS_MSG_BUSY)); return; } ExtUI::resumePrint(); } -void DGUSRxHandler::Feedrate(DGUS_VP &vp, void *data_ptr) { +void DGUSRxHandler::feedrate(DGUS_VP &vp, void *data_ptr) { UNUSED(vp); const int16_t feedrate = BE16_P(data_ptr); ExtUI::setFeedrate_percent(feedrate); - dgus_screen_handler.TriggerFullUpdate(); + screen.triggerFullUpdate(); } -void DGUSRxHandler::Flowrate(DGUS_VP &vp, void *data_ptr) { +void DGUSRxHandler::flowrate(DGUS_VP &vp, void *data_ptr) { const int16_t flowrate = BE16_P(data_ptr); switch (vp.addr) { @@ -240,24 +240,24 @@ void DGUSRxHandler::Flowrate(DGUS_VP &vp, void *data_ptr) { #endif } - dgus_screen_handler.TriggerFullUpdate(); + screen.triggerFullUpdate(); } -void DGUSRxHandler::BabystepSet(DGUS_VP &vp, void *data_ptr) { +void DGUSRxHandler::babystepSet(DGUS_VP &vp, void *data_ptr) { UNUSED(vp); const int16_t data = BE16_P(data_ptr); - const float offset = dgus_display.FromFixedPoint(data); + const float offset = dgus.fromFixedPoint(data); const int16_t steps = ExtUI::mmToWholeSteps(offset - ExtUI::getZOffset_mm(), ExtUI::Z); ExtUI::smartAdjustAxis_steps(steps, ExtUI::Z, true); - dgus_screen_handler.TriggerEEPROMSave(); - dgus_screen_handler.TriggerFullUpdate(); + screen.triggerEEPROMSave(); + screen.triggerFullUpdate(); } -void DGUSRxHandler::Babystep(DGUS_VP &vp, void *data_ptr) { +void DGUSRxHandler::babystep(DGUS_VP &vp, void *data_ptr) { UNUSED(vp); const DGUS_Data::Adjust adjust = (DGUS_Data::Adjust)((uint8_t*)data_ptr)[1]; @@ -275,11 +275,11 @@ void DGUSRxHandler::Babystep(DGUS_VP &vp, void *data_ptr) { ExtUI::smartAdjustAxis_steps(steps, ExtUI::Z, true); - dgus_screen_handler.TriggerEEPROMSave(); - dgus_screen_handler.TriggerFullUpdate(); + screen.triggerEEPROMSave(); + screen.triggerFullUpdate(); } -void DGUSRxHandler::TempPreset(DGUS_VP &vp, void *data_ptr) { +void DGUSRxHandler::tempPreset(DGUS_VP &vp, void *data_ptr) { UNUSED(vp); const DGUS_Data::TempPreset preset = (DGUS_Data::TempPreset)((uint8_t*)data_ptr)[1]; @@ -311,10 +311,10 @@ void DGUSRxHandler::TempPreset(DGUS_VP &vp, void *data_ptr) { break; } - dgus_screen_handler.TriggerFullUpdate(); + screen.triggerFullUpdate(); } -void DGUSRxHandler::TempTarget(DGUS_VP &vp, void *data_ptr) { +void DGUSRxHandler::tempTarget(DGUS_VP &vp, void *data_ptr) { const int16_t temp = BE16_P(data_ptr); switch (vp.addr) { @@ -332,10 +332,10 @@ void DGUSRxHandler::TempTarget(DGUS_VP &vp, void *data_ptr) { #endif } - dgus_screen_handler.TriggerFullUpdate(); + screen.triggerFullUpdate(); } -void DGUSRxHandler::TempCool(DGUS_VP &vp, void *data_ptr) { +void DGUSRxHandler::tempCool(DGUS_VP &vp, void *data_ptr) { UNUSED(vp); const DGUS_Data::Heater heater = (DGUS_Data::Heater)BE16_P(data_ptr); @@ -362,12 +362,12 @@ void DGUSRxHandler::TempCool(DGUS_VP &vp, void *data_ptr) { #endif } - dgus_screen_handler.SetStatusMessage(GET_TEXT_F(MSG_COOLING)); + screen.setStatusMessage(GET_TEXT_F(MSG_COOLING)); - dgus_screen_handler.TriggerFullUpdate(); + screen.triggerFullUpdate(); } -void DGUSRxHandler::Steppers(DGUS_VP &vp, void *data_ptr) { +void DGUSRxHandler::steppers(DGUS_VP &vp, void *data_ptr) { UNUSED(vp); const DGUS_Data::Control control = (DGUS_Data::Control)((uint8_t*)data_ptr)[1]; @@ -381,50 +381,50 @@ void DGUSRxHandler::Steppers(DGUS_VP &vp, void *data_ptr) { break; } - dgus_screen_handler.TriggerFullUpdate(); + screen.triggerFullUpdate(); } -void DGUSRxHandler::ZOffset(DGUS_VP &vp, void *data_ptr) { +void DGUSRxHandler::zOffset(DGUS_VP &vp, void *data_ptr) { UNUSED(vp); if (TERN0(NO_MOTION_BEFORE_HOMING, !ExtUI::isAxisPositionKnown(ExtUI::Z))) { - dgus_screen_handler.SetStatusMessage(GET_TEXT_F(DGUS_MSG_HOMING_REQUIRED)); + screen.setStatusMessage(GET_TEXT_F(DGUS_MSG_HOMING_REQUIRED)); return; } - if (!dgus_screen_handler.IsPrinterIdle()) { - dgus_screen_handler.SetStatusMessage(GET_TEXT_F(DGUS_MSG_BUSY)); + if (!screen.isPrinterIdle()) { + screen.setStatusMessage(GET_TEXT_F(DGUS_MSG_BUSY)); return; } const int16_t data = BE16_P(data_ptr); - const float offset = dgus_display.FromFixedPoint(data); + const float offset = dgus.fromFixedPoint(data); const int16_t steps = ExtUI::mmToWholeSteps(offset - ExtUI::getZOffset_mm(), ExtUI::Z); ExtUI::smartAdjustAxis_steps(steps, ExtUI::Z, true); - dgus_screen_handler.TriggerEEPROMSave(); - dgus_screen_handler.TriggerFullUpdate(); + screen.triggerEEPROMSave(); + screen.triggerFullUpdate(); } -void DGUSRxHandler::ZOffsetStep(DGUS_VP &vp, void *data_ptr) { +void DGUSRxHandler::zOffsetStep(DGUS_VP &vp, void *data_ptr) { UNUSED(vp); if (TERN0(NO_MOTION_BEFORE_HOMING, !ExtUI::isAxisPositionKnown(ExtUI::Z))) { - dgus_screen_handler.SetStatusMessage(GET_TEXT_F(DGUS_MSG_HOMING_REQUIRED)); + screen.setStatusMessage(GET_TEXT_F(DGUS_MSG_HOMING_REQUIRED)); return; } - if (!dgus_screen_handler.IsPrinterIdle()) { - dgus_screen_handler.SetStatusMessage(GET_TEXT_F(DGUS_MSG_BUSY)); + if (!screen.isPrinterIdle()) { + screen.setStatusMessage(GET_TEXT_F(DGUS_MSG_BUSY)); return; } const DGUS_Data::Adjust adjust = (DGUS_Data::Adjust)((uint8_t*)data_ptr)[1]; int16_t steps; - switch (dgus_screen_handler.offset_steps) { + switch (screen.offset_steps) { default: return; case DGUS_Data::StepSize::MMP1: steps = ExtUI::mmToWholeSteps((adjust == DGUS_Data::Adjust::INCREMENT ? 0.1f : -0.1f), ExtUI::Z); @@ -436,30 +436,30 @@ void DGUSRxHandler::ZOffsetStep(DGUS_VP &vp, void *data_ptr) { ExtUI::smartAdjustAxis_steps(steps, ExtUI::Z, true); - dgus_screen_handler.TriggerEEPROMSave(); - dgus_screen_handler.TriggerFullUpdate(); + screen.triggerEEPROMSave(); + screen.triggerFullUpdate(); } -void DGUSRxHandler::ZOffsetSetStep(DGUS_VP &vp, void *data_ptr) { +void DGUSRxHandler::zOffsetSetStep(DGUS_VP &vp, void *data_ptr) { UNUSED(vp); const DGUS_Data::StepSize size = (DGUS_Data::StepSize)((uint8_t*)data_ptr)[1]; - dgus_screen_handler.offset_steps = size; + screen.offset_steps = size; - dgus_screen_handler.TriggerFullUpdate(); + screen.triggerFullUpdate(); } -void DGUSRxHandler::MoveToPoint(DGUS_VP &vp, void *data_ptr) { +void DGUSRxHandler::moveToPoint(DGUS_VP &vp, void *data_ptr) { UNUSED(vp); if (!ExtUI::isPositionKnown()) { - dgus_screen_handler.SetStatusMessage(GET_TEXT_F(DGUS_MSG_HOMING_REQUIRED)); + screen.setStatusMessage(GET_TEXT_F(DGUS_MSG_HOMING_REQUIRED)); return; } - if (!dgus_screen_handler.IsPrinterIdle()) { - dgus_screen_handler.SetStatusMessage(GET_TEXT_F(DGUS_MSG_BUSY)); + if (!screen.isPrinterIdle()) { + screen.setStatusMessage(GET_TEXT_F(DGUS_MSG_BUSY)); return; } @@ -499,26 +499,26 @@ void DGUSRxHandler::MoveToPoint(DGUS_VP &vp, void *data_ptr) { ExtUI::setAxisPosition_mm(Z_MIN_POS + BED_TRAMMING_HEIGHT, ExtUI::Z); } -void DGUSRxHandler::Probe(DGUS_VP &vp, void *data_ptr) { +void DGUSRxHandler::probe(DGUS_VP &vp, void *data_ptr) { UNUSED(vp); UNUSED(data_ptr); #if ENABLED(MESH_BED_LEVELING) - dgus_screen_handler.SetStatusMessage(FPSTR(DGUS_MSG_ABL_REQUIRED)); + screen.setStatusMessage(FPSTR(DGUS_MSG_ABL_REQUIRED)); return; #endif if (!ExtUI::isPositionKnown()) { - dgus_screen_handler.SetStatusMessage(GET_TEXT_F(DGUS_MSG_HOMING_REQUIRED)); + screen.setStatusMessage(GET_TEXT_F(DGUS_MSG_HOMING_REQUIRED)); return; } - if (!dgus_screen_handler.IsPrinterIdle()) { - dgus_screen_handler.SetStatusMessage(GET_TEXT_F(DGUS_MSG_BUSY)); + if (!screen.isPrinterIdle()) { + screen.setStatusMessage(GET_TEXT_F(DGUS_MSG_BUSY)); return; } - dgus_screen_handler.TriggerScreenChange(DGUS_Screen::LEVELING_PROBING); + screen.triggerScreenChange(DGUS_ScreenID::LEVELING_PROBING); #if ENABLED(AUTO_BED_LEVELING_UBL) queue.enqueue_now(F("G29P1\nG29P3\nG29P5C")); @@ -528,22 +528,22 @@ void DGUSRxHandler::Probe(DGUS_VP &vp, void *data_ptr) { queue.enqueue_now(F("M500")); } -void DGUSRxHandler::DisableABL(DGUS_VP &vp, void *data_ptr) { +void DGUSRxHandler::disableABL(DGUS_VP &vp, void *data_ptr) { UNUSED(vp); UNUSED(data_ptr); - if (!dgus_screen_handler.IsPrinterIdle()) { - dgus_screen_handler.SetStatusMessage(GET_TEXT_F(DGUS_MSG_BUSY)); + if (!screen.isPrinterIdle()) { + screen.setStatusMessage(GET_TEXT_F(DGUS_MSG_BUSY)); return; } ExtUI::setLevelingActive(false); - dgus_screen_handler.TriggerEEPROMSave(); - dgus_screen_handler.TriggerFullUpdate(); + screen.triggerEEPROMSave(); + screen.triggerFullUpdate(); } -void DGUSRxHandler::FilamentSelect(DGUS_VP &vp, void *data_ptr) { +void DGUSRxHandler::filamentSelect(DGUS_VP &vp, void *data_ptr) { UNUSED(vp); const DGUS_Data::Extruder extruder = (DGUS_Data::Extruder)BE16_P(data_ptr); @@ -553,34 +553,34 @@ void DGUSRxHandler::FilamentSelect(DGUS_VP &vp, void *data_ptr) { case DGUS_Data::Extruder::CURRENT: case DGUS_Data::Extruder::E0: E_TERN_(case DGUS_Data::Extruder::E1:) - dgus_screen_handler.filament_extruder = extruder; + screen.filament_extruder = extruder; break; } - dgus_screen_handler.TriggerFullUpdate(); + screen.triggerFullUpdate(); } -void DGUSRxHandler::FilamentLength(DGUS_VP &vp, void *data_ptr) { +void DGUSRxHandler::filamentLength(DGUS_VP &vp, void *data_ptr) { UNUSED(vp); const uint16_t length = BE16_P(data_ptr); - dgus_screen_handler.filament_length = constrain(length, 0, EXTRUDE_MAXLENGTH); + screen.filament_length = constrain(length, 0, EXTRUDE_MAXLENGTH); - dgus_screen_handler.TriggerFullUpdate(); + screen.triggerFullUpdate(); } -void DGUSRxHandler::FilamentMove(DGUS_VP &vp, void *data_ptr) { +void DGUSRxHandler::filamentMove(DGUS_VP &vp, void *data_ptr) { UNUSED(vp); - if (!dgus_screen_handler.IsPrinterIdle()) { - dgus_screen_handler.SetStatusMessage(GET_TEXT_F(DGUS_MSG_BUSY)); + if (!screen.isPrinterIdle()) { + screen.setStatusMessage(GET_TEXT_F(DGUS_MSG_BUSY)); return; } ExtUI::extruder_t extruder; - switch (dgus_screen_handler.filament_extruder) { + switch (screen.filament_extruder) { default: return; case DGUS_Data::Extruder::CURRENT: #if HAS_MULTI_EXTRUDER @@ -598,7 +598,7 @@ void DGUSRxHandler::FilamentMove(DGUS_VP &vp, void *data_ptr) { } if (ExtUI::getActualTemp_celsius(extruder) < (float)EXTRUDE_MINTEMP) { - dgus_screen_handler.SetStatusMessage(GET_TEXT_F(DGUS_MSG_TEMP_TOO_LOW)); + screen.setStatusMessage(GET_TEXT_F(DGUS_MSG_TEMP_TOO_LOW)); return; } @@ -606,25 +606,25 @@ void DGUSRxHandler::FilamentMove(DGUS_VP &vp, void *data_ptr) { switch (move) { case DGUS_Data::FilamentMove::RETRACT: - UI_DECREMENT_BY(AxisPosition_mm, (float)dgus_screen_handler.filament_length, extruder); + UI_DECREMENT_BY(AxisPosition_mm, (float)screen.filament_length, extruder); break; case DGUS_Data::FilamentMove::EXTRUDE: - UI_INCREMENT_BY(AxisPosition_mm, (float)dgus_screen_handler.filament_length, extruder); + UI_INCREMENT_BY(AxisPosition_mm, (float)screen.filament_length, extruder); break; } } -void DGUSRxHandler::Home(DGUS_VP &vp, void *data_ptr) { +void DGUSRxHandler::home(DGUS_VP &vp, void *data_ptr) { UNUSED(vp); - if (!dgus_screen_handler.IsPrinterIdle()) { - dgus_screen_handler.SetStatusMessage(GET_TEXT_F(DGUS_MSG_BUSY)); + if (!screen.isPrinterIdle()) { + screen.setStatusMessage(GET_TEXT_F(DGUS_MSG_BUSY)); return; } DGUS_Data::Axis axis = (DGUS_Data::Axis)((uint8_t*)data_ptr)[1]; - dgus_screen_handler.ShowWaitScreen(GET_TEXT_F(DGUS_MSG_HOMING), dgus_screen_handler.GetCurrentScreen()); + screen.showWaitScreen(GET_TEXT_F(DGUS_MSG_HOMING), screen.getCurrentScreen()); switch (axis) { case DGUS_Data::Axis::X_Y_Z: @@ -639,9 +639,9 @@ void DGUSRxHandler::Home(DGUS_VP &vp, void *data_ptr) { } } -void DGUSRxHandler::Move(DGUS_VP &vp, void *data_ptr) { +void DGUSRxHandler::move(DGUS_VP &vp, void *data_ptr) { const int16_t data = BE16_P(data_ptr); - const float position = dgus_display.FromFixedPoint(data); + const float position = dgus.fromFixedPoint(data); ExtUI::axis_t axis; switch (vp.addr) { @@ -652,20 +652,20 @@ void DGUSRxHandler::Move(DGUS_VP &vp, void *data_ptr) { } if (TERN0(NO_MOTION_BEFORE_HOMING, !ExtUI::isAxisPositionKnown(axis))) { - dgus_screen_handler.SetStatusMessage(GET_TEXT_F(DGUS_MSG_HOMING_REQUIRED)); + screen.setStatusMessage(GET_TEXT_F(DGUS_MSG_HOMING_REQUIRED)); return; } ExtUI::setAxisPosition_mm(position, axis); - dgus_screen_handler.TriggerFullUpdate(); + screen.triggerFullUpdate(); } -void DGUSRxHandler::MoveStep(DGUS_VP &vp, void *data_ptr) { +void DGUSRxHandler::moveStep(DGUS_VP &vp, void *data_ptr) { UNUSED(vp); float offset; - switch (dgus_screen_handler.move_steps) { + switch (screen.move_steps) { default: return; case DGUS_Data::StepSize::MM10: offset = 10.0f; break; case DGUS_Data::StepSize::MM1: offset = 1.0f; break; @@ -686,58 +686,58 @@ void DGUSRxHandler::MoveStep(DGUS_VP &vp, void *data_ptr) { } if (TERN0(NO_MOTION_BEFORE_HOMING, !ExtUI::isAxisPositionKnown(axis))) { - dgus_screen_handler.SetStatusMessage(GET_TEXT_F(DGUS_MSG_HOMING_REQUIRED)); + screen.setStatusMessage(GET_TEXT_F(DGUS_MSG_HOMING_REQUIRED)); return; } UI_INCREMENT_BY(AxisPosition_mm, offset, axis); - dgus_screen_handler.TriggerFullUpdate(); + screen.triggerFullUpdate(); } -void DGUSRxHandler::MoveSetStep(DGUS_VP &vp, void *data_ptr) { +void DGUSRxHandler::moveSetStep(DGUS_VP &vp, void *data_ptr) { UNUSED(vp); const DGUS_Data::StepSize size = (DGUS_Data::StepSize)((uint8_t*)data_ptr)[1]; - dgus_screen_handler.move_steps = size; + screen.move_steps = size; - dgus_screen_handler.TriggerFullUpdate(); + screen.triggerFullUpdate(); } -void DGUSRxHandler::GcodeClear(DGUS_VP &vp, void *data_ptr) { +void DGUSRxHandler::gcodeClear(DGUS_VP &vp, void *data_ptr) { UNUSED(vp); UNUSED(data_ptr); - ZERO(dgus_screen_handler.gcode); + ZERO(screen.gcode); - dgus_screen_handler.TriggerFullUpdate(); + screen.triggerFullUpdate(); } -void DGUSRxHandler::GcodeExecute(DGUS_VP &vp, void *data_ptr) { +void DGUSRxHandler::gcodeExecute(DGUS_VP &vp, void *data_ptr) { UNUSED(vp); UNUSED(data_ptr); - if (!strlen(dgus_screen_handler.gcode)) return; + if (!strlen(screen.gcode)) return; - if (!dgus_screen_handler.IsPrinterIdle()) { - dgus_screen_handler.SetStatusMessage(GET_TEXT_F(DGUS_MSG_BUSY)); + if (!screen.isPrinterIdle()) { + screen.setStatusMessage(GET_TEXT_F(DGUS_MSG_BUSY)); return; } - dgus_screen_handler.ShowWaitScreen(GET_TEXT_F(DGUS_MSG_EXECUTING_COMMAND), DGUS_Screen::GCODE); + screen.showWaitScreen(GET_TEXT_F(DGUS_MSG_EXECUTING_COMMAND), DGUS_ScreenID::GCODE); - queue.enqueue_one_now(dgus_screen_handler.gcode); + queue.enqueue_one_now(screen.gcode); } -void DGUSRxHandler::ResetEEPROM(DGUS_VP &vp, void *data_ptr) { +void DGUSRxHandler::resetEEPROM(DGUS_VP &vp, void *data_ptr) { UNUSED(vp); const DGUS_Data::Popup result = (DGUS_Data::Popup)((uint8_t*)data_ptr)[1]; if (result != DGUS_Data::Popup::CONFIRMED) return; - if (!dgus_screen_handler.IsPrinterIdle()) { - dgus_screen_handler.SetStatusMessage(GET_TEXT_F(DGUS_MSG_BUSY)); + if (!screen.isPrinterIdle()) { + screen.setStatusMessage(GET_TEXT_F(DGUS_MSG_BUSY)); return; } @@ -745,7 +745,7 @@ void DGUSRxHandler::ResetEEPROM(DGUS_VP &vp, void *data_ptr) { queue.enqueue_now(F("M500")); } -void DGUSRxHandler::SettingsExtra(DGUS_VP &vp, void *data_ptr) { +void DGUSRxHandler::settingsExtra(DGUS_VP &vp, void *data_ptr) { UNUSED(vp); const DGUS_Data::Extra extra = (DGUS_Data::Extra)((uint8_t*)data_ptr)[1]; @@ -754,25 +754,25 @@ void DGUSRxHandler::SettingsExtra(DGUS_VP &vp, void *data_ptr) { default: return; case DGUS_Data::Extra::BUTTON1: #if ENABLED(BLTOUCH) - if (!dgus_screen_handler.IsPrinterIdle()) { - dgus_screen_handler.SetStatusMessage(GET_TEXT_F(DGUS_MSG_BUSY)); + if (!screen.isPrinterIdle()) { + screen.setStatusMessage(GET_TEXT_F(DGUS_MSG_BUSY)); return; } queue.enqueue_now(F(DGUS_RESET_BLTOUCH)); #else - dgus_screen_handler.TriggerScreenChange(DGUS_Screen::INFOS); + screen.triggerScreenChange(DGUS_ScreenID::INFOS); #endif break; #if ENABLED(BLTOUCH) case DGUS_Data::Extra::BUTTON2: - dgus_screen_handler.TriggerScreenChange(DGUS_Screen::INFOS); + screen.triggerScreenChange(DGUS_ScreenID::INFOS); break; #endif } } -void DGUSRxHandler::PIDSelect(DGUS_VP &vp, void *data_ptr) { +void DGUSRxHandler::pidSelect(DGUS_VP &vp, void *data_ptr) { UNUSED(vp); const DGUS_Data::Heater heater = (DGUS_Data::Heater)BE16_P(data_ptr); @@ -780,34 +780,34 @@ void DGUSRxHandler::PIDSelect(DGUS_VP &vp, void *data_ptr) { switch (heater) { default: return; case DGUS_Data::Heater::BED: - dgus_screen_handler.pid_temp = DGUS_PLA_TEMP_BED; - dgus_screen_handler.pid_heater = heater; + screen.pid_temp = DGUS_PLA_TEMP_BED; + screen.pid_heater = heater; break; case DGUS_Data::Heater::H0: #if HAS_MULTI_HOTEND case DGUS_Data::Heater::H1: #endif - dgus_screen_handler.pid_temp = DGUS_PLA_TEMP_HOTEND; - dgus_screen_handler.pid_heater = heater; + screen.pid_temp = DGUS_PLA_TEMP_HOTEND; + screen.pid_heater = heater; break; } - dgus_screen_handler.pid_cycles = 5; + screen.pid_cycles = 5; - dgus_screen_handler.TriggerFullUpdate(); + screen.triggerFullUpdate(); } -void DGUSRxHandler::PIDSetTemp(DGUS_VP &vp, void *data_ptr) { +void DGUSRxHandler::pidSetTemp(DGUS_VP &vp, void *data_ptr) { UNUSED(vp); - if (!dgus_screen_handler.IsPrinterIdle()) { - dgus_screen_handler.SetStatusMessage(GET_TEXT_F(DGUS_MSG_BUSY)); + if (!screen.isPrinterIdle()) { + screen.setStatusMessage(GET_TEXT_F(DGUS_MSG_BUSY)); return; } uint16_t temp = BE16_P(data_ptr); - switch (dgus_screen_handler.pid_heater) { + switch (screen.pid_heater) { default: return; case DGUS_Data::Heater::BED: temp = constrain(temp, BED_MINTEMP, BED_MAX_TARGET); @@ -822,31 +822,31 @@ void DGUSRxHandler::PIDSetTemp(DGUS_VP &vp, void *data_ptr) { #endif } - dgus_screen_handler.pid_temp = temp; + screen.pid_temp = temp; - dgus_screen_handler.TriggerFullUpdate(); + screen.triggerFullUpdate(); } -void DGUSRxHandler::PIDRun(DGUS_VP &vp, void *data_ptr) { +void DGUSRxHandler::pidRun(DGUS_VP &vp, void *data_ptr) { UNUSED(vp); UNUSED(data_ptr); - if (!dgus_screen_handler.IsPrinterIdle()) { - dgus_screen_handler.SetStatusMessage(GET_TEXT_F(DGUS_MSG_BUSY)); + if (!screen.isPrinterIdle()) { + screen.setStatusMessage(GET_TEXT_F(DGUS_MSG_BUSY)); return; } heater_id_t heater; - uint8_t cycles = constrain(dgus_screen_handler.pid_cycles, 3, 10); + uint8_t cycles = constrain(screen.pid_cycles, 3, 10); - switch (dgus_screen_handler.pid_heater) { + switch (screen.pid_heater) { default: return; case DGUS_Data::Heater::BED: #if ENABLED(PIDTEMPBED) heater = H_BED; break; #else - dgus_screen_handler.SetStatusMessage(GET_TEXT_F(DGUS_MSG_BED_PID_DISABLED)); + screen.setStatusMessage(GET_TEXT_F(DGUS_MSG_BED_PID_DISABLED)); return; #endif case DGUS_Data::Heater::H0: @@ -854,7 +854,7 @@ void DGUSRxHandler::PIDRun(DGUS_VP &vp, void *data_ptr) { heater = H_E0; break; #else - dgus_screen_handler.SetStatusMessage(GET_TEXT_F(DGUS_MSG_PID_DISABLED)); + screen.setStatusMessage(GET_TEXT_F(DGUS_MSG_PID_DISABLED)); return; #endif #if HAS_MULTI_HOTEND @@ -863,23 +863,23 @@ void DGUSRxHandler::PIDRun(DGUS_VP &vp, void *data_ptr) { heater = H_E1; break; #else - dgus_screen_handler.SetStatusMessage(GET_TEXT_F(DGUS_MSG_PID_DISABLED)); + screen.setStatusMessage(GET_TEXT_F(DGUS_MSG_PID_DISABLED)); return; #endif #endif } char buffer[24]; - snprintf_P(buffer, sizeof(buffer), PSTR("M303C%dE%dS%dU1"), cycles, heater, dgus_screen_handler.pid_temp); + snprintf_P(buffer, sizeof(buffer), PSTR("M303C%dE%dS%dU1"), cycles, heater, screen.pid_temp); - dgus_screen_handler.ShowWaitScreen(GET_TEXT_F(DGUS_MSG_PID_AUTOTUNING), DGUS_Screen::PID); + screen.showWaitScreen(GET_TEXT_F(DGUS_MSG_PID_AUTOTUNING), DGUS_ScreenID::PID); queue.enqueue_one_now(buffer); queue.enqueue_now(F("M500")); } #if ENABLED(POWER_LOSS_RECOVERY) - void DGUSRxHandler::PowerLossAbort(DGUS_VP &vp, void *data_ptr) { + void DGUSRxHandler::powerLossAbort(DGUS_VP &vp, void *data_ptr) { UNUSED(vp); const DGUS_Data::Popup result = (DGUS_Data::Popup)((uint8_t*)data_ptr)[1]; @@ -888,17 +888,17 @@ void DGUSRxHandler::PIDRun(DGUS_VP &vp, void *data_ptr) { return; } - if (!dgus_screen_handler.IsPrinterIdle()) { - dgus_screen_handler.SetStatusMessage(GET_TEXT_F(DGUS_MSG_BUSY)); + if (!screen.isPrinterIdle()) { + screen.setStatusMessage(GET_TEXT_F(DGUS_MSG_BUSY)); return; } - dgus_screen_handler.TriggerScreenChange(DGUS_Screen::HOME); + screen.triggerScreenChange(DGUS_ScreenID::HOME); queue.enqueue_now(F("M1000C")); } - void DGUSRxHandler::PowerLossResume(DGUS_VP &vp, void *data_ptr) { + void DGUSRxHandler::powerLossResume(DGUS_VP &vp, void *data_ptr) { UNUSED(vp); const DGUS_Data::Popup result = (DGUS_Data::Popup)((uint8_t*)data_ptr)[1]; @@ -907,23 +907,23 @@ void DGUSRxHandler::PIDRun(DGUS_VP &vp, void *data_ptr) { return; } - if (!dgus_screen_handler.IsPrinterIdle()) { - dgus_screen_handler.SetStatusMessage(GET_TEXT_F(DGUS_MSG_BUSY)); + if (!screen.isPrinterIdle()) { + screen.setStatusMessage(GET_TEXT_F(DGUS_MSG_BUSY)); return; } if (!recovery.valid()) { - dgus_screen_handler.SetStatusMessage(GET_TEXT_F(DGUS_MSG_INVALID_RECOVERY_DATA)); + screen.setStatusMessage(GET_TEXT_F(DGUS_MSG_INVALID_RECOVERY_DATA)); return; } - dgus_screen_handler.TriggerScreenChange(DGUS_Screen::PRINT_STATUS); + screen.triggerScreenChange(DGUS_ScreenID::PRINT_STATUS); queue.enqueue_now(F("M1000")); } #endif // POWER_LOSS_RECOVERY -void DGUSRxHandler::WaitAbort(DGUS_VP &vp, void *data_ptr) { +void DGUSRxHandler::waitAbort(DGUS_VP &vp, void *data_ptr) { UNUSED(vp); const DGUS_Data::Popup result = (DGUS_Data::Popup)((uint8_t*)data_ptr)[1]; @@ -933,25 +933,25 @@ void DGUSRxHandler::WaitAbort(DGUS_VP &vp, void *data_ptr) { } if (!ExtUI::isPrintingPaused()) { - dgus_screen_handler.TriggerFullUpdate(); + screen.triggerFullUpdate(); return; } ExtUI::stopPrint(); - dgus_screen_handler.TriggerFullUpdate(); + screen.triggerFullUpdate(); } -void DGUSRxHandler::WaitContinue(DGUS_VP &vp, void *data_ptr) { +void DGUSRxHandler::waitContinue(DGUS_VP &vp, void *data_ptr) { UNUSED(vp); UNUSED(data_ptr); ExtUI::setUserConfirmed(); - dgus_screen_handler.TriggerFullUpdate(); + screen.triggerFullUpdate(); } -void DGUSRxHandler::FanSpeed(DGUS_VP &vp, void *data_ptr) { +void DGUSRxHandler::fanSpeed(DGUS_VP &vp, void *data_ptr) { uint8_t speed = ((uint8_t*)data_ptr)[1]; switch (vp.addr) { default: return; @@ -961,36 +961,36 @@ void DGUSRxHandler::FanSpeed(DGUS_VP &vp, void *data_ptr) { } } -void DGUSRxHandler::Volume(DGUS_VP &vp, void *data_ptr) { +void DGUSRxHandler::volume(DGUS_VP &vp, void *data_ptr) { UNUSED(vp); uint8_t volume = ((uint8_t*)data_ptr)[1]; - dgus_display.SetVolume(volume); + dgus.setVolume(volume); - dgus_screen_handler.TriggerEEPROMSave(); + screen.triggerEEPROMSave(); } -void DGUSRxHandler::Brightness(DGUS_VP &vp, void *data_ptr) { +void DGUSRxHandler::brightness(DGUS_VP &vp, void *data_ptr) { UNUSED(vp); uint8_t brightness = ((uint8_t*)data_ptr)[1]; - dgus_display.SetBrightness(brightness); + dgus.setBrightness(brightness); - dgus_screen_handler.TriggerEEPROMSave(); + screen.triggerEEPROMSave(); } -void DGUSRxHandler::Debug(DGUS_VP &vp, void *data_ptr) { +void DGUSRxHandler::debug(DGUS_VP &vp, void *data_ptr) { UNUSED(vp); UNUSED(data_ptr); - ++dgus_screen_handler.debug_count; + ++screen.debug_count; - if (dgus_screen_handler.debug_count >= 10) { - dgus_screen_handler.TriggerScreenChange(DGUS_Screen::DEBUG); + if (screen.debug_count >= 10) { + screen.triggerScreenChange(DGUS_ScreenID::DEBUG); } } -void DGUSRxHandler::StringToExtra(DGUS_VP &vp, void *data_ptr) { +void DGUSRxHandler::stringToExtra(DGUS_VP &vp, void *data_ptr) { if (!vp.size || !vp.extra) return; memcpy(vp.extra, data_ptr, vp.size); } diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.h b/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.h index b81b142d8411..9143b83554ee 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.h +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.h @@ -26,78 +26,78 @@ namespace DGUSRxHandler { - void ScreenChange(DGUS_VP &, void *); + void screenChange(DGUS_VP &, void *); #if HAS_MEDIA - void Scroll(DGUS_VP &, void *); + void scroll(DGUS_VP &, void *); void selectFile(DGUS_VP &, void *); - void PrintFile(DGUS_VP &, void *); + void printFile(DGUS_VP &, void *); #endif - void PrintAbort(DGUS_VP &, void *); - void PrintPause(DGUS_VP &, void *); - void PrintResume(DGUS_VP &, void *); + void printAbort(DGUS_VP &, void *); + void printPause(DGUS_VP &, void *); + void printResume(DGUS_VP &, void *); - void Feedrate(DGUS_VP &, void *); - void Flowrate(DGUS_VP &, void *); - void BabystepSet(DGUS_VP &, void *); - void Babystep(DGUS_VP &, void *); + void feedrate(DGUS_VP &, void *); + void flowrate(DGUS_VP &, void *); + void babystepSet(DGUS_VP &, void *); + void babystep(DGUS_VP &, void *); - void TempPreset(DGUS_VP &, void *); - void TempTarget(DGUS_VP &, void *); - void TempCool(DGUS_VP &, void *); + void tempPreset(DGUS_VP &, void *); + void tempTarget(DGUS_VP &, void *); + void tempCool(DGUS_VP &, void *); - void Steppers(DGUS_VP &, void *); + void steppers(DGUS_VP &, void *); - void ZOffset(DGUS_VP &, void *); - void ZOffsetStep(DGUS_VP &, void *); - void ZOffsetSetStep(DGUS_VP &, void *); + void zOffset(DGUS_VP &, void *); + void zOffsetStep(DGUS_VP &, void *); + void zOffsetSetStep(DGUS_VP &, void *); - void MoveToPoint(DGUS_VP &, void *); + void moveToPoint(DGUS_VP &, void *); - void Probe(DGUS_VP &, void *); - void DisableABL(DGUS_VP &, void *); + void probe(DGUS_VP &, void *); + void disableABL(DGUS_VP &, void *); - void FilamentSelect(DGUS_VP &, void *); - void FilamentLength(DGUS_VP &, void *); - void FilamentMove(DGUS_VP &, void *); + void filamentSelect(DGUS_VP &, void *); + void filamentLength(DGUS_VP &, void *); + void filamentMove(DGUS_VP &, void *); - void Home(DGUS_VP &, void *); - void Move(DGUS_VP &, void *); - void MoveStep(DGUS_VP &, void *); - void MoveSetStep(DGUS_VP &, void *); + void home(DGUS_VP &, void *); + void move(DGUS_VP &, void *); + void moveStep(DGUS_VP &, void *); + void moveSetStep(DGUS_VP &, void *); - void GcodeClear(DGUS_VP &, void *); - void GcodeExecute(DGUS_VP &, void *); + void gcodeClear(DGUS_VP &, void *); + void gcodeExecute(DGUS_VP &, void *); - void ResetEEPROM(DGUS_VP &, void *); + void resetEEPROM(DGUS_VP &, void *); - void SettingsExtra(DGUS_VP &, void *); + void settingsExtra(DGUS_VP &, void *); - void PIDSelect(DGUS_VP &, void *); - void PIDSetTemp(DGUS_VP &, void *); - void PIDRun(DGUS_VP &, void *); + void pidSelect(DGUS_VP &, void *); + void pidSetTemp(DGUS_VP &, void *); + void pidRun(DGUS_VP &, void *); #if ENABLED(POWER_LOSS_RECOVERY) - void PowerLossAbort(DGUS_VP &, void *); - void PowerLossResume(DGUS_VP &, void *); + void powerLossAbort(DGUS_VP &, void *); + void powerLossResume(DGUS_VP &, void *); #endif - void WaitAbort(DGUS_VP &, void *); - void WaitContinue(DGUS_VP &, void *); + void waitAbort(DGUS_VP &, void *); + void waitContinue(DGUS_VP &, void *); - void FanSpeed(DGUS_VP &, void *); + void fanSpeed(DGUS_VP &, void *); - void Volume(DGUS_VP &, void *); + void volume(DGUS_VP &, void *); - void Brightness(DGUS_VP &, void *); + void brightness(DGUS_VP &, void *); - void Debug(DGUS_VP &, void *); + void debug(DGUS_VP &, void *); - void StringToExtra(DGUS_VP &, void *); + void stringToExtra(DGUS_VP &, void *); template - void IntegerToExtra(DGUS_VP &vp, void *data_ptr) { + void integerToExtra(DGUS_VP &vp, void *data_ptr) { if (!vp.size || !vp.extra) return; switch (vp.size) { default: return; @@ -112,7 +112,7 @@ namespace DGUSRxHandler { break; } case 4: { - const uint32_t data = dgus_display.SwapBytes(*(uint32_t*)data_ptr); + const uint32_t data = dgus.swapBytes(*(uint32_t*)data_ptr); *(T*)vp.extra = (T)data; break; } diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.cpp index 6a430e74a6d0..793a2c15796f 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.cpp @@ -57,11 +57,11 @@ uint8_t DGUSScreenHandler::pid_cycles = 5; bool DGUSScreenHandler::settings_ready = false; bool DGUSScreenHandler::booted = false; -DGUS_Screen DGUSScreenHandler::current_screen = DGUS_Screen::BOOT; -DGUS_Screen DGUSScreenHandler::new_screen = DGUS_Screen::BOOT; +DGUS_ScreenID DGUSScreenHandler::current_screenID = DGUS_ScreenID::BOOT; +DGUS_ScreenID DGUSScreenHandler::new_screenID = DGUS_ScreenID::BOOT; bool DGUSScreenHandler::full_update = false; -DGUS_Screen DGUSScreenHandler::wait_return_screen = DGUS_Screen::HOME; +DGUS_ScreenID DGUSScreenHandler::wait_return_screenID = DGUS_ScreenID::HOME; bool DGUSScreenHandler::wait_continue = false; bool DGUSScreenHandler::leveling_active = false; @@ -69,41 +69,41 @@ bool DGUSScreenHandler::leveling_active = false; millis_t DGUSScreenHandler::status_expire = 0; millis_t DGUSScreenHandler::eeprom_save = 0; -void DGUSScreenHandler::Init() { - dgus_display.Init(); +void DGUSScreenHandler::init() { + dgus.init(); - MoveToScreen(DGUS_Screen::BOOT, true); + moveToScreen(DGUS_ScreenID::BOOT, true); } -void DGUSScreenHandler::Ready() { - dgus_display.PlaySound(1); +void DGUSScreenHandler::ready() { + dgus.playSound(1); } -void DGUSScreenHandler::Loop() { - if (!settings_ready || current_screen == DGUS_Screen::KILL) { +void DGUSScreenHandler::loop() { + if (!settings_ready || current_screenID == DGUS_ScreenID::KILL) { return; } const millis_t ms = ExtUI::safe_millis(); static millis_t next_event_ms = 0; - if (new_screen != DGUS_Screen::BOOT) { - const DGUS_Screen screen = new_screen; - new_screen = DGUS_Screen::BOOT; - if (current_screen == screen) - TriggerFullUpdate(); + if (new_screenID != DGUS_ScreenID::BOOT) { + const DGUS_ScreenID screenID = new_screenID; + new_screenID = DGUS_ScreenID::BOOT; + if (current_screenID == screenID) + triggerFullUpdate(); else - MoveToScreen(screen); + moveToScreen(screenID); return; } if (!booted && ELAPSED(ms, 3000)) { booted = true; - dgus_display.ReadVersions(); + dgus.readVersions(); - if (current_screen == DGUS_Screen::BOOT) - MoveToScreen(DGUS_Screen::HOME); + if (current_screenID == DGUS_ScreenID::BOOT) + moveToScreen(DGUS_ScreenID::HOME); return; } @@ -111,164 +111,163 @@ void DGUSScreenHandler::Loop() { if (ELAPSED(ms, next_event_ms) || full_update) { next_event_ms = ms + DGUS_UPDATE_INTERVAL_MS; - if (!SendScreenVPData(current_screen, full_update)) - DEBUG_ECHOLNPGM("SendScreenVPData failed"); + if (!sendScreenVPData(current_screenID, full_update)) + DEBUG_ECHOLNPGM("sendScreenVPData failed"); return; } - if (current_screen == DGUS_Screen::WAIT - && ((wait_continue && !wait_for_user) - || (!wait_continue && IsPrinterIdle())) + if (current_screenID == DGUS_ScreenID::WAIT + && ((wait_continue && !wait_for_user) || (!wait_continue && isPrinterIdle())) ) { - MoveToScreen(wait_return_screen, true); + moveToScreen(wait_return_screenID, true); return; } - if (current_screen == DGUS_Screen::LEVELING_PROBING && IsPrinterIdle()) { - dgus_display.PlaySound(3); + if (current_screenID == DGUS_ScreenID::LEVELING_PROBING && isPrinterIdle()) { + dgus.playSound(3); - SetStatusMessage(ExtUI::getMeshValid() ? GET_TEXT_F(DGUS_MSG_PROBING_SUCCESS) : GET_TEXT_F(DGUS_MSG_PROBING_FAILED)); + setStatusMessage(ExtUI::getLevelingIsValid() ? GET_TEXT_F(DGUS_MSG_PROBING_SUCCESS) : GET_TEXT_F(DGUS_MSG_PROBING_FAILED)); - MoveToScreen(DGUS_Screen::LEVELING_AUTOMATIC); + moveToScreen(DGUS_ScreenID::LEVELING_AUTOMATIC); return; } if (status_expire > 0 && ELAPSED(ms, status_expire)) { - SetStatusMessage(FPSTR(NUL_STR), 0); + setStatusMessage(FPSTR(NUL_STR), 0); return; } - if (eeprom_save > 0 && ELAPSED(ms, eeprom_save) && IsPrinterIdle()) { + if (eeprom_save > 0 && ELAPSED(ms, eeprom_save) && isPrinterIdle()) { eeprom_save = 0; queue.enqueue_now(F("M500")); return; } - dgus_display.Loop(); + dgus.loop(); } void DGUSScreenHandler::printerKilled(FSTR_P const error, FSTR_P const component) { - SetMessageLine(error, 1); - SetMessageLine(component, 2); - SetMessageLinePGM(NUL_STR, 3); - SetMessageLine(GET_TEXT_F(MSG_PLEASE_RESET), 4); + setMessageLine(error, 1); + setMessageLine(component, 2); + setMessageLinePGM(NUL_STR, 3); + setMessageLine(GET_TEXT_F(MSG_PLEASE_RESET), 4); - dgus_display.PlaySound(3, 1, 200); + dgus.playSound(3, 1, 200); - MoveToScreen(DGUS_Screen::KILL, true); + moveToScreen(DGUS_ScreenID::KILL, true); } -void DGUSScreenHandler::UserConfirmRequired(const char * const msg) { - SetMessageLinePGM(NUL_STR, 1); - SetMessageLine(msg, 2); - SetMessageLinePGM(NUL_STR, 3); - SetMessageLinePGM(NUL_STR, 4); +void DGUSScreenHandler::userConfirmRequired(const char * const msg) { + setMessageLinePGM(NUL_STR, 1); + setMessageLine(msg, 2); + setMessageLinePGM(NUL_STR, 3); + setMessageLinePGM(NUL_STR, 4); - dgus_display.PlaySound(3); + dgus.playSound(3); - ShowWaitScreen(current_screen, true); + showWaitScreen(current_screenID, true); } -void DGUSScreenHandler::SettingsReset() { - dgus_display.SetVolume(DGUS_DEFAULT_VOLUME); - dgus_display.SetBrightness(DGUS_DEFAULT_BRIGHTNESS); +void DGUSScreenHandler::settingsReset() { + dgus.setVolume(DGUS_DEFAULT_VOLUME); + dgus.setBrightness(DGUS_DEFAULT_BRIGHTNESS); if (!settings_ready) { settings_ready = true; - Ready(); + ready(); } - SetStatusMessage(GET_TEXT_F(DGUS_MSG_RESET_EEPROM)); + setStatusMessage(GET_TEXT_F(DGUS_MSG_RESET_EEPROM)); } -void DGUSScreenHandler::StoreSettings(char *buff) { +void DGUSScreenHandler::storeSettings(char *buff) { eeprom_data_t data; static_assert(sizeof(data) <= ExtUI::eeprom_data_size, "sizeof(eeprom_data_t) > eeprom_data_size."); data.initialized = true; - data.volume = dgus_display.GetVolume(); - data.brightness = dgus_display.GetBrightness(); - data.abl_okay = (ExtUI::getLevelingActive() && ExtUI::getMeshValid()); + data.volume = dgus.getVolume(); + data.brightness = dgus.getBrightness(); + data.abl_okay = (ExtUI::getLevelingActive() && ExtUI::getLevelingIsValid()); memcpy(buff, &data, sizeof(data)); } -void DGUSScreenHandler::LoadSettings(const char *buff) { +void DGUSScreenHandler::loadSettings(const char *buff) { eeprom_data_t data; static_assert(sizeof(data) <= ExtUI::eeprom_data_size, "sizeof(eeprom_data_t) > eeprom_data_size."); memcpy(&data, buff, sizeof(data)); - dgus_display.SetVolume(data.initialized ? data.volume : DGUS_DEFAULT_VOLUME); - dgus_display.SetBrightness(data.initialized ? data.brightness : DGUS_DEFAULT_BRIGHTNESS); + dgus.setVolume(data.initialized ? data.volume : DGUS_DEFAULT_VOLUME); + dgus.setBrightness(data.initialized ? data.brightness : DGUS_DEFAULT_BRIGHTNESS); if (data.initialized) { - leveling_active = (data.abl_okay && ExtUI::getMeshValid()); + leveling_active = (data.abl_okay && ExtUI::getLevelingIsValid()); ExtUI::setLevelingActive(leveling_active); } } -void DGUSScreenHandler::ConfigurationStoreWritten(bool success) { +void DGUSScreenHandler::configurationStoreWritten(bool success) { if (!success) - SetStatusMessage(GET_TEXT_F(DGUS_MSG_WRITE_EEPROM_FAILED)); + setStatusMessage(GET_TEXT_F(DGUS_MSG_WRITE_EEPROM_FAILED)); } -void DGUSScreenHandler::ConfigurationStoreRead(bool success) { +void DGUSScreenHandler::configurationStoreRead(bool success) { if (!success) { - SetStatusMessage(GET_TEXT_F(DGUS_MSG_READ_EEPROM_FAILED)); + setStatusMessage(GET_TEXT_F(DGUS_MSG_READ_EEPROM_FAILED)); } else if (!settings_ready) { settings_ready = true; - Ready(); + ready(); } } -void DGUSScreenHandler::PlayTone(const uint16_t frequency, const uint16_t duration) { +void DGUSScreenHandler::playTone(const uint16_t frequency, const uint16_t duration) { UNUSED(duration); if (frequency >= 1 && frequency <= 255) { if (duration >= 1 && duration <= 255) - dgus_display.PlaySound((uint8_t)frequency, (uint8_t)duration); + dgus.playSound((uint8_t)frequency, (uint8_t)duration); else - dgus_display.PlaySound((uint8_t)frequency); + dgus.playSound((uint8_t)frequency); } } -void DGUSScreenHandler::MeshUpdate(const int8_t xpos, const int8_t ypos) { - if (current_screen != DGUS_Screen::LEVELING_PROBING) { - if (current_screen == DGUS_Screen::LEVELING_AUTOMATIC) - TriggerFullUpdate(); +void DGUSScreenHandler::meshUpdate(const int8_t xpos, const int8_t ypos) { + if (current_screenID != DGUS_ScreenID::LEVELING_PROBING) { + if (current_screenID == DGUS_ScreenID::LEVELING_AUTOMATIC) + triggerFullUpdate(); return; } uint8_t point = ypos * GRID_MAX_POINTS_X + xpos; probing_icons[point < 16 ? 0 : 1] |= (1U << (point % 16)); - if (xpos >= GRID_MAX_POINTS_X - 1 && ypos >= GRID_MAX_POINTS_Y - 1 && !ExtUI::getMeshValid()) + if (xpos >= GRID_MAX_POINTS_X - 1 && ypos >= GRID_MAX_POINTS_Y - 1 && !ExtUI::getLevelingIsValid()) probing_icons[0] = probing_icons[1] = 0; - TriggerFullUpdate(); + triggerFullUpdate(); } -void DGUSScreenHandler::PrintTimerStarted() { - TriggerScreenChange(DGUS_Screen::PRINT_STATUS); +void DGUSScreenHandler::printTimerStarted() { + triggerScreenChange(DGUS_ScreenID::PRINT_STATUS); } -void DGUSScreenHandler::PrintTimerPaused() { - dgus_display.PlaySound(3); - TriggerFullUpdate(); +void DGUSScreenHandler::printTimerPaused() { + dgus.playSound(3); + triggerFullUpdate(); } -void DGUSScreenHandler::PrintTimerStopped() { - if (current_screen != DGUS_Screen::PRINT_STATUS && current_screen != DGUS_Screen::PRINT_ADJUST) +void DGUSScreenHandler::printTimerStopped() { + if (current_screenID != DGUS_ScreenID::PRINT_STATUS && current_screenID != DGUS_ScreenID::PRINT_ADJUST) return; - dgus_display.PlaySound(3); + dgus.playSound(3); - TriggerScreenChange(DGUS_Screen::PRINT_FINISHED); + triggerScreenChange(DGUS_ScreenID::PRINT_FINISHED); } void DGUSScreenHandler::filamentRunout(const ExtUI::extruder_t extruder) { @@ -276,161 +275,161 @@ void DGUSScreenHandler::filamentRunout(const ExtUI::extruder_t extruder) { snprintf_P(buffer, sizeof(buffer), GET_TEXT(DGUS_MSG_FILAMENT_RUNOUT), extruder); - SetStatusMessage(buffer); + setStatusMessage(buffer); - dgus_display.PlaySound(3); + dgus.playSound(3); } #if HAS_MEDIA - void DGUSScreenHandler::SDCardInserted() { - if (current_screen == DGUS_Screen::HOME) - TriggerScreenChange(DGUS_Screen::PRINT); + void DGUSScreenHandler::sdCardInserted() { + if (current_screenID == DGUS_ScreenID::HOME) + triggerScreenChange(DGUS_ScreenID::PRINT); } - void DGUSScreenHandler::SDCardRemoved() { - if (current_screen == DGUS_Screen::PRINT) - TriggerScreenChange(DGUS_Screen::HOME); + void DGUSScreenHandler::sdCardRemoved() { + if (current_screenID == DGUS_ScreenID::PRINT) + triggerScreenChange(DGUS_ScreenID::HOME); } - void DGUSScreenHandler::SDCardError() { - SetStatusMessage(GET_TEXT_F(MSG_MEDIA_READ_ERROR)); - if (current_screen == DGUS_Screen::PRINT) - TriggerScreenChange(DGUS_Screen::HOME); + void DGUSScreenHandler::sdCardError() { + setStatusMessage(GET_TEXT_F(MSG_MEDIA_READ_ERROR)); + if (current_screenID == DGUS_ScreenID::PRINT) + triggerScreenChange(DGUS_ScreenID::HOME); } #endif // HAS_MEDIA #if ENABLED(POWER_LOSS_RECOVERY) - void DGUSScreenHandler::PowerLossResume() { - MoveToScreen(DGUS_Screen::POWERLOSS, true); + void DGUSScreenHandler::powerLossResume() { + moveToScreen(DGUS_ScreenID::POWERLOSS, true); } #endif // POWER_LOSS_RECOVERY #if HAS_PID_HEATING - void DGUSScreenHandler::PidTuning(const ExtUI::result_t rst) { + void DGUSScreenHandler::pidTuning(const ExtUI::result_t rst) { switch (rst) { case ExtUI::PID_STARTED: - SetStatusMessage(GET_TEXT_F(MSG_PID_AUTOTUNE)); + setStatusMessage(GET_TEXT_F(MSG_PID_AUTOTUNE)); break; case ExtUI::PID_BAD_HEATER_ID: - SetStatusMessage(GET_TEXT_F(MSG_PID_BAD_HEATER_ID)); + setStatusMessage(GET_TEXT_F(MSG_PID_BAD_HEATER_ID)); break; case ExtUI::PID_TEMP_TOO_HIGH: - SetStatusMessage(GET_TEXT_F(MSG_PID_TEMP_TOO_HIGH)); + setStatusMessage(GET_TEXT_F(MSG_PID_TEMP_TOO_HIGH)); break; case ExtUI::PID_TUNING_TIMEOUT: - SetStatusMessage(GET_TEXT_F(MSG_PID_TIMEOUT)); + setStatusMessage(GET_TEXT_F(MSG_PID_TIMEOUT)); break; case ExtUI::PID_DONE: - SetStatusMessage(GET_TEXT_F(MSG_PID_AUTOTUNE_DONE)); + setStatusMessage(GET_TEXT_F(MSG_PID_AUTOTUNE_DONE)); break; default: return; } - dgus_display.PlaySound(3); + dgus.playSound(3); } #endif // HAS_PID_HEATING -void DGUSScreenHandler::SetMessageLine(const char * const msg, const uint8_t line) { +void DGUSScreenHandler::setMessageLine(const char * const msg, const uint8_t line) { switch (line) { default: return; case 1: - dgus_display.WriteString((uint16_t)DGUS_Addr::MESSAGE_Line1, msg, DGUS_LINE_LEN, true, true); + dgus.writeString((uint16_t)DGUS_Addr::MESSAGE_Line1, msg, DGUS_LINE_LEN, true, true); break; case 2: - dgus_display.WriteString((uint16_t)DGUS_Addr::MESSAGE_Line2, msg, DGUS_LINE_LEN, true, true); + dgus.writeString((uint16_t)DGUS_Addr::MESSAGE_Line2, msg, DGUS_LINE_LEN, true, true); break; case 3: - dgus_display.WriteString((uint16_t)DGUS_Addr::MESSAGE_Line3, msg, DGUS_LINE_LEN, true, true); + dgus.writeString((uint16_t)DGUS_Addr::MESSAGE_Line3, msg, DGUS_LINE_LEN, true, true); break; case 4: - dgus_display.WriteString((uint16_t)DGUS_Addr::MESSAGE_Line4, msg, DGUS_LINE_LEN, true, true); + dgus.writeString((uint16_t)DGUS_Addr::MESSAGE_Line4, msg, DGUS_LINE_LEN, true, true); break; } } -void DGUSScreenHandler::SetMessageLinePGM(PGM_P const msg, const uint8_t line) { +void DGUSScreenHandler::setMessageLinePGM(PGM_P const msg, const uint8_t line) { switch (line) { default: return; case 1: - dgus_display.WriteStringPGM((uint16_t)DGUS_Addr::MESSAGE_Line1, msg, DGUS_LINE_LEN, true, true); + dgus.writeStringPGM((uint16_t)DGUS_Addr::MESSAGE_Line1, msg, DGUS_LINE_LEN, true, true); break; case 2: - dgus_display.WriteStringPGM((uint16_t)DGUS_Addr::MESSAGE_Line2, msg, DGUS_LINE_LEN, true, true); + dgus.writeStringPGM((uint16_t)DGUS_Addr::MESSAGE_Line2, msg, DGUS_LINE_LEN, true, true); break; case 3: - dgus_display.WriteStringPGM((uint16_t)DGUS_Addr::MESSAGE_Line3, msg, DGUS_LINE_LEN, true, true); + dgus.writeStringPGM((uint16_t)DGUS_Addr::MESSAGE_Line3, msg, DGUS_LINE_LEN, true, true); break; case 4: - dgus_display.WriteStringPGM((uint16_t)DGUS_Addr::MESSAGE_Line4, msg, DGUS_LINE_LEN, true, true); + dgus.writeStringPGM((uint16_t)DGUS_Addr::MESSAGE_Line4, msg, DGUS_LINE_LEN, true, true); break; } } -void DGUSScreenHandler::SetStatusMessage(const char* msg, const millis_t duration) { - dgus_display.WriteString((uint16_t)DGUS_Addr::MESSAGE_Status, msg, DGUS_STATUS_LEN, false, true); +void DGUSScreenHandler::setStatusMessage(const char* msg, const millis_t duration) { + dgus.writeString((uint16_t)DGUS_Addr::MESSAGE_Status, msg, DGUS_STATUS_LEN, false, true); status_expire = (duration > 0 ? ExtUI::safe_millis() + duration : 0); } -void DGUSScreenHandler::SetStatusMessage(FSTR_P const fmsg, const millis_t duration) { - dgus_display.WriteString((uint16_t)DGUS_Addr::MESSAGE_Status, fmsg, DGUS_STATUS_LEN, false, true); +void DGUSScreenHandler::setStatusMessage(FSTR_P const fmsg, const millis_t duration) { + dgus.writeString((uint16_t)DGUS_Addr::MESSAGE_Status, fmsg, DGUS_STATUS_LEN, false, true); status_expire = (duration > 0 ? ExtUI::safe_millis() + duration : 0); } -void DGUSScreenHandler::ShowWaitScreen(const DGUS_Screen return_screen, const bool has_continue/*=false*/) { - if (return_screen != DGUS_Screen::WAIT) { - wait_return_screen = return_screen; +void DGUSScreenHandler::showWaitScreen(const DGUS_ScreenID return_screenID, const bool has_continue/*=false*/) { + if (return_screenID != DGUS_ScreenID::WAIT) { + wait_return_screenID = return_screenID; } wait_continue = has_continue; - TriggerScreenChange(DGUS_Screen::WAIT); + triggerScreenChange(DGUS_ScreenID::WAIT); } -void DGUSScreenHandler::ShowWaitScreen(FSTR_P const msg, const DGUS_Screen return_screen, const bool has_continue/*=false*/) { - SetMessageLinePGM(NUL_STR, 1); - SetMessageLine(msg, 2); - SetMessageLinePGM(NUL_STR, 3); - SetMessageLinePGM(NUL_STR, 4); - ShowWaitScreen(return_screen, has_continue); +void DGUSScreenHandler::showWaitScreen(FSTR_P const msg, const DGUS_ScreenID return_screenID, const bool has_continue/*=false*/) { + setMessageLinePGM(NUL_STR, 1); + setMessageLine(msg, 2); + setMessageLinePGM(NUL_STR, 3); + setMessageLinePGM(NUL_STR, 4); + showWaitScreen(return_screenID, has_continue); } -DGUS_Screen DGUSScreenHandler::GetCurrentScreen() { - return current_screen; +DGUS_ScreenID DGUSScreenHandler::getCurrentScreen() { + return current_screenID; } -void DGUSScreenHandler::TriggerScreenChange(DGUS_Screen screen) { - new_screen = screen; +void DGUSScreenHandler::triggerScreenChange(const DGUS_ScreenID screenID) { + new_screenID = screenID; } -void DGUSScreenHandler::TriggerFullUpdate() { +void DGUSScreenHandler::triggerFullUpdate() { full_update = true; } -void DGUSScreenHandler::TriggerEEPROMSave() { +void DGUSScreenHandler::triggerEEPROMSave() { eeprom_save = ExtUI::safe_millis() + 500; } -bool DGUSScreenHandler::IsPrinterIdle() { +bool DGUSScreenHandler::isPrinterIdle() { return (!ExtUI::commandsInQueue() && !ExtUI::isMoving()); } -const DGUS_Addr* DGUSScreenHandler::FindScreenAddrList(DGUS_Screen screen) { +const DGUS_Addr* DGUSScreenHandler::findScreenAddrList(const DGUS_ScreenID screenID) { DGUS_ScreenAddrList list; const DGUS_ScreenAddrList *map = screen_addr_list_map; do { memcpy_P(&list, map, sizeof(*map)); if (!list.addr_list) break; - if (list.screen == screen) { + if (list.screenID == screenID) { return list.addr_list; } } while (++map); @@ -438,14 +437,14 @@ const DGUS_Addr* DGUSScreenHandler::FindScreenAddrList(DGUS_Screen screen) { return nullptr; } -bool DGUSScreenHandler::CallScreenSetup(DGUS_Screen screen) { +bool DGUSScreenHandler::callScreenSetup(const DGUS_ScreenID screenID) { DGUS_ScreenSetup setup; const DGUS_ScreenSetup *list = screen_setup_list; do { memcpy_P(&setup, list, sizeof(*list)); if (!setup.setup_fn) break; - if (setup.screen == screen) { + if (setup.screenID == screenID) { return setup.setup_fn(); } } while (++list); @@ -453,14 +452,14 @@ bool DGUSScreenHandler::CallScreenSetup(DGUS_Screen screen) { return true; } -void DGUSScreenHandler::MoveToScreen(DGUS_Screen screen, bool abort_wait) { - if (current_screen == DGUS_Screen::KILL) { +void DGUSScreenHandler::moveToScreen(const DGUS_ScreenID screenID, bool abort_wait) { + if (current_screenID == DGUS_ScreenID::KILL) { return; } - if (current_screen == DGUS_Screen::WAIT) { - if (screen != DGUS_Screen::WAIT) { - wait_return_screen = screen; + if (current_screenID == DGUS_ScreenID::WAIT) { + if (screenID != DGUS_ScreenID::WAIT) { + wait_return_screenID = screenID; } if (!abort_wait) return; @@ -470,18 +469,18 @@ void DGUSScreenHandler::MoveToScreen(DGUS_Screen screen, bool abort_wait) { } } - if (!CallScreenSetup(screen)) return; + if (!callScreenSetup(screenID)) return; - if (!SendScreenVPData(screen, true)) return; + if (!sendScreenVPData(screenID, true)) return; - current_screen = screen; - dgus_display.SwitchScreen(current_screen); + current_screenID = screenID; + dgus.switchScreen(current_screenID); } -bool DGUSScreenHandler::SendScreenVPData(DGUS_Screen screen, bool complete_update) { +bool DGUSScreenHandler::sendScreenVPData(const DGUS_ScreenID screenID, bool complete_update) { if (complete_update) full_update = false; - const DGUS_Addr *list = FindScreenAddrList(screen); + const DGUS_Addr *list = findScreenAddrList(screenID); while (true) { if (!list) return true; // Nothing left to send @@ -490,17 +489,17 @@ bool DGUSScreenHandler::SendScreenVPData(DGUS_Screen screen, bool complete_updat if (!addr) return true; // Nothing left to send DGUS_VP vp; - if (!DGUS_PopulateVP((DGUS_Addr)addr, &vp)) continue; // Invalid VP + if (!populateVP((DGUS_Addr)addr, &vp)) continue; // Invalid VP if (!vp.tx_handler) continue; // Nothing to send if (!complete_update && !(vp.flags & VPFLAG_AUTOUPLOAD)) continue; // Unnecessary VP uint8_t expected_tx = 6 + vp.size; // 6 bytes header + payload. const millis_t try_until = ExtUI::safe_millis() + 1000; - while (expected_tx > dgus_display.GetFreeTxBuffer()) { + while (expected_tx > dgus.getFreeTxBuffer()) { if (ELAPSED(ExtUI::safe_millis(), try_until)) return false; // Stop trying after 1 second - dgus_display.FlushTx(); // Flush the TX buffer + dgus.flushTx(); // Flush the TX buffer delay(50); } diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.h index 2ecf7192fe41..27f7f92517ca 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.h +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.h @@ -23,7 +23,7 @@ #include "config/DGUS_Addr.h" #include "config/DGUS_Data.h" -#include "config/DGUS_Screen.h" +#include "config/DGUS_ScreenID.h" #include "config/DGUS_Constants.h" #include "../ui_api.h" @@ -33,59 +33,59 @@ class DGUSScreenHandler { public: DGUSScreenHandler() = default; - static void Init(); - static void Ready(); - static void Loop(); + static void init(); + static void ready(); + static void loop(); static void printerKilled(FSTR_P const error, FSTR_P const component); - static void UserConfirmRequired(const char * const msg); - static void SettingsReset(); - static void StoreSettings(char *buff); - static void LoadSettings(const char *buff); - static void ConfigurationStoreWritten(bool success); - static void ConfigurationStoreRead(bool success); - - static void PlayTone(const uint16_t frequency, const uint16_t duration); - static void MeshUpdate(const int8_t xpos, const int8_t ypos); - static void PrintTimerStarted(); - static void PrintTimerPaused(); - static void PrintTimerStopped(); + static void userConfirmRequired(const char * const msg); + static void settingsReset(); + static void storeSettings(char *buff); + static void loadSettings(const char *buff); + static void configurationStoreWritten(bool success); + static void configurationStoreRead(bool success); + + static void playTone(const uint16_t frequency, const uint16_t duration); + static void meshUpdate(const int8_t xpos, const int8_t ypos); + static void printTimerStarted(); + static void printTimerPaused(); + static void printTimerStopped(); static void filamentRunout(const ExtUI::extruder_t extruder); #if HAS_MEDIA /// Marlin informed us that a new SD has been inserted. - static void SDCardInserted(); + static void sdCardInserted(); /// Marlin informed us that the SD Card has been removed(). - static void SDCardRemoved(); + static void sdCardRemoved(); /// Marlin informed us about a bad SD Card. - static void SDCardError(); + static void sdCardError(); #endif #if ENABLED(POWER_LOSS_RECOVERY) - static void PowerLossResume(); + static void powerLossResume(); #endif #if HAS_PID_HEATING - static void PidTuning(const ExtUI::result_t rst); + static void pidTuning(const ExtUI::result_t rst); #endif - static void SetMessageLine(const char * const msg, const uint8_t line); - static void SetMessageLinePGM(PGM_P const msg, const uint8_t line); - static void SetMessageLine(FSTR_P const msg, const uint8_t line) { SetMessageLinePGM(FTOP(msg), line); } + static void setMessageLine(const char * const msg, const uint8_t line); + static void setMessageLinePGM(PGM_P const msg, const uint8_t line); + static void setMessageLine(FSTR_P const msg, const uint8_t line) { setMessageLinePGM(FTOP(msg), line); } - static void SetStatusMessage(const char* msg, const millis_t duration=DGUS_STATUS_EXPIRATION_MS); - static void SetStatusMessage(FSTR_P const msg, const millis_t duration=DGUS_STATUS_EXPIRATION_MS); + static void setStatusMessage(const char* msg, const millis_t duration=DGUS_STATUS_EXPIRATION_MS); + static void setStatusMessage(FSTR_P const msg, const millis_t duration=DGUS_STATUS_EXPIRATION_MS); - static void ShowWaitScreen(const DGUS_Screen return_screen, const bool has_continue=false); - static void ShowWaitScreen(FSTR_P const msg, const DGUS_Screen return_screen, const bool has_continue=false); + static void showWaitScreen(const DGUS_ScreenID return_screenID, const bool has_continue=false); + static void showWaitScreen(FSTR_P const msg, const DGUS_ScreenID return_screenID, const bool has_continue=false); - static DGUS_Screen GetCurrentScreen(); - static void TriggerScreenChange(DGUS_Screen screen); - static void TriggerFullUpdate(); + static DGUS_ScreenID getCurrentScreen(); + static void triggerScreenChange(const DGUS_ScreenID screenID); + static void triggerFullUpdate(); - static void TriggerEEPROMSave(); + static void triggerEEPROMSave(); - static bool IsPrinterIdle(); + static bool isPrinterIdle(); static uint8_t debug_count; @@ -114,20 +114,20 @@ class DGUSScreenHandler { static bool leveling_active; private: - static const DGUS_Addr* FindScreenAddrList(DGUS_Screen screen); - static bool CallScreenSetup(DGUS_Screen screen); + static const DGUS_Addr* findScreenAddrList(const DGUS_ScreenID screenID); + static bool callScreenSetup(const DGUS_ScreenID screenID); - static void MoveToScreen(DGUS_Screen screen, bool abort_wait=false); - static bool SendScreenVPData(DGUS_Screen screen, bool complete_update); + static void moveToScreen(const DGUS_ScreenID screenID, bool abort_wait=false); + static bool sendScreenVPData(const DGUS_ScreenID screenID, bool complete_update); static bool settings_ready; static bool booted; - static DGUS_Screen current_screen; - static DGUS_Screen new_screen; + static DGUS_ScreenID current_screenID; + static DGUS_ScreenID new_screenID; static bool full_update; - static DGUS_Screen wait_return_screen; + static DGUS_ScreenID wait_return_screenID; static millis_t status_expire; static millis_t eeprom_save; @@ -140,4 +140,4 @@ class DGUSScreenHandler { } eeprom_data_t; }; -extern DGUSScreenHandler dgus_screen_handler; +extern DGUSScreenHandler screen; diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSSetupHandler.cpp b/Marlin/src/lcd/extui/dgus_reloaded/DGUSSetupHandler.cpp index 3b1a38502db6..b0aeacbfdffe 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSSetupHandler.cpp +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSSetupHandler.cpp @@ -33,14 +33,14 @@ #if HAS_MEDIA bool DGUSSetupHandler::Print() { - dgus_screen_handler.filelist.refresh(); + screen.filelist.refresh(); - while (!dgus_screen_handler.filelist.isAtRootDir()) { - dgus_screen_handler.filelist.upDir(); + while (!screen.filelist.isAtRootDir()) { + screen.filelist.upDir(); } - dgus_screen_handler.filelist_offset = 0; - dgus_screen_handler.filelist_selected = -1; + screen.filelist_offset = 0; + screen.filelist_selected = -1; return true; } @@ -51,7 +51,7 @@ bool DGUSSetupHandler::PrintStatus() { return true; } - dgus_screen_handler.TriggerScreenChange(DGUS_Screen::PRINT_FINISHED); + screen.triggerScreenChange(DGUS_ScreenID::PRINT_FINISHED); return false; } @@ -60,15 +60,15 @@ bool DGUSSetupHandler::PrintAdjust() { return true; } - dgus_screen_handler.TriggerScreenChange(DGUS_Screen::PRINT_FINISHED); + screen.triggerScreenChange(DGUS_ScreenID::PRINT_FINISHED); return false; } bool DGUSSetupHandler::LevelingMenu() { - ExtUI::setLevelingActive(dgus_screen_handler.leveling_active); + ExtUI::setLevelingActive(screen.leveling_active); - if (!dgus_screen_handler.IsPrinterIdle()) { - dgus_screen_handler.SetStatusMessage(GET_TEXT_F(DGUS_MSG_BUSY)); + if (!screen.isPrinterIdle()) { + screen.setStatusMessage(GET_TEXT_F(DGUS_MSG_BUSY)); return false; } @@ -80,7 +80,7 @@ bool DGUSSetupHandler::LevelingMenu() { return true; } - dgus_screen_handler.ShowWaitScreen(GET_TEXT_F(DGUS_MSG_HOMING), DGUS_Screen::LEVELING_MENU); + screen.showWaitScreen(GET_TEXT_F(DGUS_MSG_HOMING), DGUS_ScreenID::LEVELING_MENU); queue.enqueue_now(F("G28")); @@ -94,12 +94,12 @@ bool DGUSSetupHandler::LevelingManual() { return true; } - if (!dgus_screen_handler.IsPrinterIdle()) { - dgus_screen_handler.SetStatusMessage(GET_TEXT_F(DGUS_MSG_BUSY)); + if (!screen.isPrinterIdle()) { + screen.setStatusMessage(GET_TEXT_F(DGUS_MSG_BUSY)); return false; } - dgus_screen_handler.ShowWaitScreen(GET_TEXT_F(DGUS_MSG_HOMING), DGUS_Screen::LEVELING_MANUAL); + screen.showWaitScreen(GET_TEXT_F(DGUS_MSG_HOMING), DGUS_ScreenID::LEVELING_MANUAL); queue.enqueue_now(F("G28")); @@ -107,10 +107,10 @@ bool DGUSSetupHandler::LevelingManual() { } bool DGUSSetupHandler::LevelingOffset() { - dgus_screen_handler.offset_steps = DGUS_Data::StepSize::MMP1; + screen.offset_steps = DGUS_Data::StepSize::MMP1; - if (!dgus_screen_handler.IsPrinterIdle()) { - dgus_screen_handler.SetStatusMessage(GET_TEXT_F(DGUS_MSG_BUSY)); + if (!screen.isPrinterIdle()) { + screen.setStatusMessage(GET_TEXT_F(DGUS_MSG_BUSY)); return false; } @@ -128,7 +128,7 @@ bool DGUSSetupHandler::LevelingOffset() { return true; } - dgus_screen_handler.ShowWaitScreen(GET_TEXT_F(DGUS_MSG_HOMING), DGUS_Screen::LEVELING_OFFSET); + screen.showWaitScreen(GET_TEXT_F(DGUS_MSG_HOMING), DGUS_ScreenID::LEVELING_OFFSET); queue.enqueue_now(F("G28")); @@ -136,8 +136,8 @@ bool DGUSSetupHandler::LevelingOffset() { } bool DGUSSetupHandler::LevelingAutomatic() { - if (ExtUI::getMeshValid()) { - dgus_screen_handler.leveling_active = true; + if (ExtUI::getLevelingIsValid()) { + screen.leveling_active = true; ExtUI::setLevelingActive(true); } @@ -146,24 +146,24 @@ bool DGUSSetupHandler::LevelingAutomatic() { } bool DGUSSetupHandler::LevelingProbing() { - dgus_screen_handler.probing_icons[0] = 0; - dgus_screen_handler.probing_icons[1] = 0; + screen.probing_icons[0] = 0; + screen.probing_icons[1] = 0; return true; } bool DGUSSetupHandler::Filament() { - dgus_screen_handler.filament_extruder = DGUS_Data::Extruder::CURRENT; - dgus_screen_handler.filament_length = DGUS_DEFAULT_FILAMENT_LEN; + screen.filament_extruder = DGUS_Data::Extruder::CURRENT; + screen.filament_length = DGUS_DEFAULT_FILAMENT_LEN; return true; } bool DGUSSetupHandler::Move() { - dgus_screen_handler.move_steps = DGUS_Data::StepSize::MM10; + screen.move_steps = DGUS_Data::StepSize::MM10; - if (!dgus_screen_handler.IsPrinterIdle()) { - dgus_screen_handler.SetStatusMessage(GET_TEXT_F(DGUS_MSG_BUSY)); + if (!screen.isPrinterIdle()) { + screen.setStatusMessage(GET_TEXT_F(DGUS_MSG_BUSY)); return false; } @@ -171,10 +171,10 @@ bool DGUSSetupHandler::Move() { } bool DGUSSetupHandler::Gcode() { - ZERO(dgus_screen_handler.gcode); + ZERO(screen.gcode); - if (dgus_display.gui_version < 0x30 || dgus_display.os_version < 0x21) { - dgus_screen_handler.SetStatusMessage(GET_TEXT_F(DGUS_MSG_FW_OUTDATED)); + if (dgus.gui_version < 0x30 || dgus.os_version < 0x21) { + screen.setStatusMessage(GET_TEXT_F(DGUS_MSG_FW_OUTDATED)); return false; } @@ -182,14 +182,14 @@ bool DGUSSetupHandler::Gcode() { } bool DGUSSetupHandler::PID() { - dgus_screen_handler.pid_heater = DGUS_Data::Heater::H0; - dgus_screen_handler.pid_temp = DGUS_PLA_TEMP_HOTEND; + screen.pid_heater = DGUS_Data::Heater::H0; + screen.pid_temp = DGUS_PLA_TEMP_HOTEND; return true; } bool DGUSSetupHandler::Infos() { - dgus_screen_handler.debug_count = 0; + screen.debug_count = 0; return true; } diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.cpp b/Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.cpp index c7d650c03ec8..037eafcc9424 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.cpp +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.cpp @@ -37,7 +37,7 @@ #endif #if HAS_MEDIA - void DGUSTxHandler::SetFileControlState(int16_t file, bool state) { + void DGUSTxHandler::setFileControlState(int16_t file, bool state) { DGUS_Control control; switch (file) { @@ -60,40 +60,40 @@ } if (state) { - dgus_display.EnableControl(DGUS_Screen::PRINT, + dgus.enableControl(DGUS_ScreenID::PRINT, DGUSDisplay::RETURN_KEY_CODE, control); } else { - dgus_display.DisableControl(DGUS_Screen::PRINT, + dgus.disableControl(DGUS_ScreenID::PRINT, DGUSDisplay::RETURN_KEY_CODE, control); } } - void DGUSTxHandler::FileType(DGUS_VP &vp) { + void DGUSTxHandler::fileType(DGUS_VP &vp) { // Batch send uint16_t data[DGUS_FILE_COUNT]; for (int16_t i = 0; i < DGUS_FILE_COUNT; i++) { - if (!dgus_screen_handler.filelist.seek(dgus_screen_handler.filelist_offset + i)) { + if (!screen.filelist.seek(screen.filelist_offset + i)) { data[i] = Swap16(DGUS_Data::SDType::NONE); - SetFileControlState(i, false); + setFileControlState(i, false); continue; } - data[i] = dgus_screen_handler.filelist.isDir() ? + data[i] = screen.filelist.isDir() ? Swap16(DGUS_Data::SDType::DIRECTORY) : Swap16(DGUS_Data::SDType::FILE); - SetFileControlState(i, true); + setFileControlState(i, true); } - dgus_display.Write((uint16_t)vp.addr, data, sizeof(*data) * DGUS_FILE_COUNT); + dgus.write((uint16_t)vp.addr, data, sizeof(*data) * DGUS_FILE_COUNT); } - void DGUSTxHandler::FileName(DGUS_VP &vp) { + void DGUSTxHandler::fileName(DGUS_VP &vp) { uint8_t offset; switch (vp.addr) { @@ -115,84 +115,84 @@ break; } - if (dgus_screen_handler.filelist.seek(dgus_screen_handler.filelist_offset + offset)) { - dgus_display.WriteString((uint16_t)vp.addr, dgus_screen_handler.filelist.filename(), vp.size); + if (screen.filelist.seek(screen.filelist_offset + offset)) { + dgus.writeString((uint16_t)vp.addr, screen.filelist.filename(), vp.size); } else { - dgus_display.WriteStringPGM((uint16_t)vp.addr, NUL_STR, vp.size); + dgus.writeStringPGM((uint16_t)vp.addr, NUL_STR, vp.size); } } - void DGUSTxHandler::ScrollIcons(DGUS_VP &vp) { + void DGUSTxHandler::scrollIcons(DGUS_VP &vp) { uint16_t icons = 0; - if (!dgus_screen_handler.filelist.isAtRootDir()) { + if (!screen.filelist.isAtRootDir()) { icons |= (uint16_t)DGUS_Data::ScrollIcon::GO_BACK; - dgus_display.EnableControl(DGUS_Screen::PRINT, + dgus.enableControl(DGUS_ScreenID::PRINT, DGUSDisplay::RETURN_KEY_CODE, DGUS_Control::GO_BACK); } else { - dgus_display.DisableControl(DGUS_Screen::PRINT, + dgus.disableControl(DGUS_ScreenID::PRINT, DGUSDisplay::RETURN_KEY_CODE, DGUS_Control::GO_BACK); } - if (dgus_screen_handler.filelist_offset > 0) { + if (screen.filelist_offset > 0) { icons |= (uint16_t)DGUS_Data::ScrollIcon::UP; - dgus_display.EnableControl(DGUS_Screen::PRINT, + dgus.enableControl(DGUS_ScreenID::PRINT, DGUSDisplay::RETURN_KEY_CODE, DGUS_Control::SCROLL_UP); } else { - dgus_display.DisableControl(DGUS_Screen::PRINT, + dgus.disableControl(DGUS_ScreenID::PRINT, DGUSDisplay::RETURN_KEY_CODE, DGUS_Control::SCROLL_UP); } - if (dgus_screen_handler.filelist_offset + DGUS_FILE_COUNT < dgus_screen_handler.filelist.count()) { + if (screen.filelist_offset + DGUS_FILE_COUNT < screen.filelist.count()) { icons |= (uint16_t)DGUS_Data::ScrollIcon::DOWN; - dgus_display.EnableControl(DGUS_Screen::PRINT, + dgus.enableControl(DGUS_ScreenID::PRINT, DGUSDisplay::RETURN_KEY_CODE, DGUS_Control::SCROLL_DOWN); } else { - dgus_display.DisableControl(DGUS_Screen::PRINT, + dgus.disableControl(DGUS_ScreenID::PRINT, DGUSDisplay::RETURN_KEY_CODE, DGUS_Control::SCROLL_DOWN); } - dgus_display.Write((uint16_t)vp.addr, Swap16(icons)); + dgus.write((uint16_t)vp.addr, Swap16(icons)); } - void DGUSTxHandler::SelectedFileName(DGUS_VP &vp) { - if (dgus_screen_handler.filelist_selected < 0 - || !dgus_screen_handler.filelist.seek(dgus_screen_handler.filelist_selected)) { - dgus_display.WriteStringPGM((uint16_t)vp.addr, NUL_STR, vp.size); + void DGUSTxHandler::selectedFileName(DGUS_VP &vp) { + if (screen.filelist_selected < 0 + || !screen.filelist.seek(screen.filelist_selected)) { + dgus.writeStringPGM((uint16_t)vp.addr, NUL_STR, vp.size); return; } - dgus_display.WriteString((uint16_t)vp.addr, dgus_screen_handler.filelist.filename(), vp.size); + dgus.writeString((uint16_t)vp.addr, screen.filelist.filename(), vp.size); } #endif // HAS_MEDIA -void DGUSTxHandler::PositionZ(DGUS_VP &vp) { +void DGUSTxHandler::zPosition(DGUS_VP &vp) { const float position = ExtUI::isAxisPositionKnown(ExtUI::Z) ? planner.get_axis_position_mm(Z_AXIS) : 0; - const int32_t data = dgus_display.ToFixedPoint(int32_t(position * 50.0f) / 50.0f); // Round to 0.02 - dgus_display.Write((uint16_t)vp.addr, dgus_display.SwapBytes(data)); + const int32_t data = dgus.toFixedPoint(int32_t(position * 50.0f) / 50.0f); // Round to 0.02 + dgus.write((uint16_t)vp.addr, dgus.swapBytes(data)); } -void DGUSTxHandler::Elapsed(DGUS_VP &vp) { +void DGUSTxHandler::elapsed(DGUS_VP &vp) { char buffer[21]; duration_t(print_job_timer.duration()).toString(buffer); - dgus_display.WriteString((uint16_t)vp.addr, buffer, vp.size); + dgus.writeString((uint16_t)vp.addr, buffer, vp.size); } -void DGUSTxHandler::Percent(DGUS_VP &vp) { +void DGUSTxHandler::percent(DGUS_VP &vp) { uint16_t progress; switch (vp.addr) { @@ -205,21 +205,21 @@ void DGUSTxHandler::Percent(DGUS_VP &vp) { break; } - dgus_display.Write((uint16_t)DGUS_Addr::STATUS_Percent, Swap16(progress)); + dgus.write((uint16_t)DGUS_Addr::STATUS_Percent, Swap16(progress)); } -void DGUSTxHandler::StatusIcons(DGUS_VP &vp) { +void DGUSTxHandler::statusIcons(DGUS_VP &vp) { uint16_t icons = 0; if (ExtUI::isPrinting()) { icons |= (uint16_t)DGUS_Data::StatusIcon::PAUSE; - dgus_display.EnableControl(DGUS_Screen::PRINT_STATUS, + dgus.enableControl(DGUS_ScreenID::PRINT_STATUS, DGUSDisplay::POPUP_WINDOW, DGUS_Control::PAUSE); } else { - dgus_display.DisableControl(DGUS_Screen::PRINT_STATUS, + dgus.disableControl(DGUS_ScreenID::PRINT_STATUS, DGUSDisplay::POPUP_WINDOW, DGUS_Control::PAUSE); } @@ -227,20 +227,20 @@ void DGUSTxHandler::StatusIcons(DGUS_VP &vp) { if (ExtUI::isPrintingPaused()) { icons |= (uint16_t)DGUS_Data::StatusIcon::RESUME; - dgus_display.EnableControl(DGUS_Screen::PRINT_STATUS, + dgus.enableControl(DGUS_ScreenID::PRINT_STATUS, DGUSDisplay::POPUP_WINDOW, DGUS_Control::RESUME); } else { - dgus_display.DisableControl(DGUS_Screen::PRINT_STATUS, + dgus.disableControl(DGUS_ScreenID::PRINT_STATUS, DGUSDisplay::POPUP_WINDOW, DGUS_Control::RESUME); } - dgus_display.Write((uint16_t)vp.addr, Swap16(icons)); + dgus.write((uint16_t)vp.addr, Swap16(icons)); } -void DGUSTxHandler::Flowrate(DGUS_VP &vp) { +void DGUSTxHandler::flowrate(DGUS_VP &vp) { int16_t flowrate; switch (vp.addr) { @@ -258,10 +258,10 @@ void DGUSTxHandler::Flowrate(DGUS_VP &vp) { #endif } - dgus_display.Write((uint16_t)vp.addr, Swap16(flowrate)); + dgus.write((uint16_t)vp.addr, Swap16(flowrate)); } -void DGUSTxHandler::TempMax(DGUS_VP &vp) { +void DGUSTxHandler::tempMax(DGUS_VP &vp) { uint16_t temp; switch (vp.addr) { @@ -279,15 +279,15 @@ void DGUSTxHandler::TempMax(DGUS_VP &vp) { #endif } - dgus_display.Write((uint16_t)vp.addr, Swap16(temp)); + dgus.write((uint16_t)vp.addr, Swap16(temp)); } -void DGUSTxHandler::StepperStatus(DGUS_VP &vp) { +void DGUSTxHandler::stepperStatus(DGUS_VP &vp) { const bool motor_on = stepper.axis_enabled.bits & (_BV(NUM_AXES) - 1); - dgus_display.Write((uint16_t)vp.addr, Swap16(motor_on ? DGUS_Data::Status::ENABLED : DGUS_Data::Status::DISABLED)); + dgus.write((uint16_t)vp.addr, Swap16(motor_on ? DGUS_Data::Status::ENABLED : DGUS_Data::Status::DISABLED)); } -void DGUSTxHandler::StepIcons(DGUS_VP &vp) { +void DGUSTxHandler::stepIcons(DGUS_VP &vp) { if (!vp.extra) return; uint16_t icons = 0; DGUS_Data::StepSize size = *(DGUS_Data::StepSize*)vp.extra; @@ -307,31 +307,31 @@ void DGUSTxHandler::StepIcons(DGUS_VP &vp) { break; } - dgus_display.Write((uint16_t)vp.addr, Swap16(icons)); + dgus.write((uint16_t)vp.addr, Swap16(icons)); } -void DGUSTxHandler::ABLDisableIcon(DGUS_VP &vp) { +void DGUSTxHandler::ablDisableIcon(DGUS_VP &vp) { uint16_t data; if (ExtUI::getLevelingActive()) { data = (uint16_t)DGUS_Data::Status::ENABLED; - dgus_display.EnableControl(DGUS_Screen::LEVELING_AUTOMATIC, + dgus.enableControl(DGUS_ScreenID::LEVELING_AUTOMATIC, DGUSDisplay::RETURN_KEY_CODE, DGUS_Control::DISABLE); } else { data = (uint16_t)DGUS_Data::Status::DISABLED; - dgus_display.DisableControl(DGUS_Screen::LEVELING_AUTOMATIC, + dgus.disableControl(DGUS_ScreenID::LEVELING_AUTOMATIC, DGUSDisplay::RETURN_KEY_CODE, DGUS_Control::DISABLE); } - dgus_display.Write((uint16_t)vp.addr, Swap16(data)); + dgus.write((uint16_t)vp.addr, Swap16(data)); } -void DGUSTxHandler::ABLGrid(DGUS_VP &vp) { +void DGUSTxHandler::ablGrid(DGUS_VP &vp) { // Batch send int16_t data[DGUS_LEVEL_GRID_SIZE]; xy_uint8_t point; @@ -340,17 +340,17 @@ void DGUSTxHandler::ABLGrid(DGUS_VP &vp) { for (int16_t i = 0; i < DGUS_LEVEL_GRID_SIZE; i++) { point.x = i % (GRID_MAX_POINTS_X); point.y = i / (GRID_MAX_POINTS_X); - fixed = dgus_display.ToFixedPoint(ExtUI::getMeshPoint(point)); + fixed = dgus.toFixedPoint(ExtUI::getMeshPoint(point)); data[i] = Swap16(fixed); } - dgus_display.Write((uint16_t)vp.addr, data, sizeof(*data) * DGUS_LEVEL_GRID_SIZE); + dgus.write((uint16_t)vp.addr, data, sizeof(*data) * DGUS_LEVEL_GRID_SIZE); } -void DGUSTxHandler::FilamentIcons(DGUS_VP &vp) { +void DGUSTxHandler::filamentIcons(DGUS_VP &vp) { uint16_t icons = 0; - switch (dgus_screen_handler.filament_extruder) { + switch (screen.filament_extruder) { default: return; case DGUS_Data::Extruder::CURRENT: #if HAS_MULTI_EXTRUDER @@ -373,29 +373,29 @@ void DGUSTxHandler::FilamentIcons(DGUS_VP &vp) { break; } - dgus_display.Write((uint16_t)vp.addr, Swap16(icons)); + dgus.write((uint16_t)vp.addr, Swap16(icons)); } -void DGUSTxHandler::BLTouch(DGUS_VP &vp) { +void DGUSTxHandler::blTouch(DGUS_VP &vp) { #if ENABLED(BLTOUCH) - dgus_display.EnableControl(DGUS_Screen::SETTINGS_MENU2, + dgus.enableControl(DGUS_ScreenID::SETTINGS_MENU2, DGUSDisplay::RETURN_KEY_CODE, DGUS_Control::EXTRA2); - dgus_display.Write((uint16_t)vp.addr, Swap16(DGUS_Data::Status::ENABLED)); + dgus.write((uint16_t)vp.addr, Swap16(DGUS_Data::Status::ENABLED)); #else - dgus_display.DisableControl(DGUS_Screen::SETTINGS_MENU2, + dgus.disableControl(DGUS_ScreenID::SETTINGS_MENU2, DGUSDisplay::RETURN_KEY_CODE, DGUS_Control::EXTRA2); - dgus_display.Write((uint16_t)vp.addr, Swap16(DGUS_Data::Status::DISABLED)); + dgus.write((uint16_t)vp.addr, Swap16(DGUS_Data::Status::DISABLED)); #endif } -void DGUSTxHandler::PIDIcons(DGUS_VP &vp) { +void DGUSTxHandler::pidIcons(DGUS_VP &vp) { uint16_t icons = 0; - switch (dgus_screen_handler.pid_heater) { + switch (screen.pid_heater) { default: return; case DGUS_Data::Heater::BED: icons |= (uint16_t)DGUS_Data::HeaterIcon::BED; @@ -408,13 +408,13 @@ void DGUSTxHandler::PIDIcons(DGUS_VP &vp) { break; } - dgus_display.Write((uint16_t)vp.addr, Swap16(icons)); + dgus.write((uint16_t)vp.addr, Swap16(icons)); } -void DGUSTxHandler::PIDKp(DGUS_VP &vp) { +void DGUSTxHandler::pidKp(DGUS_VP &vp) { float value; - switch (dgus_screen_handler.pid_heater) { + switch (screen.pid_heater) { default: return; #if ENABLED(PIDTEMPBED) case DGUS_Data::Heater::BED: @@ -433,14 +433,14 @@ void DGUSTxHandler::PIDKp(DGUS_VP &vp) { #endif } - const int32_t data = dgus_display.ToFixedPoint(value); - dgus_display.Write((uint16_t)vp.addr, dgus_display.SwapBytes(data)); + const int32_t data = dgus.toFixedPoint(value); + dgus.write((uint16_t)vp.addr, dgus.swapBytes(data)); } -void DGUSTxHandler::PIDKi(DGUS_VP &vp) { +void DGUSTxHandler::pidKi(DGUS_VP &vp) { float value; - switch (dgus_screen_handler.pid_heater) { + switch (screen.pid_heater) { default: return; #if ENABLED(PIDTEMPBED) case DGUS_Data::Heater::BED: @@ -459,14 +459,14 @@ void DGUSTxHandler::PIDKi(DGUS_VP &vp) { #endif } - const int32_t data = dgus_display.ToFixedPoint(value); - dgus_display.Write((uint16_t)vp.addr, dgus_display.SwapBytes(data)); + const int32_t data = dgus.toFixedPoint(value); + dgus.write((uint16_t)vp.addr, dgus.swapBytes(data)); } -void DGUSTxHandler::PIDKd(DGUS_VP &vp) { +void DGUSTxHandler::pidKd(DGUS_VP &vp) { float value; - switch (dgus_screen_handler.pid_heater) { + switch (screen.pid_heater) { default: return; #if ENABLED(PIDTEMPBED) case DGUS_Data::Heater::BED: @@ -485,99 +485,99 @@ void DGUSTxHandler::PIDKd(DGUS_VP &vp) { #endif } - const int32_t data = dgus_display.ToFixedPoint(value); - dgus_display.Write((uint16_t)vp.addr, dgus_display.SwapBytes(data)); + const int32_t data = dgus.toFixedPoint(value); + dgus.write((uint16_t)vp.addr, dgus.swapBytes(data)); } -void DGUSTxHandler::BuildVolume(DGUS_VP &vp) { +void DGUSTxHandler::buildVolume(DGUS_VP &vp) { char buffer[vp.size]; snprintf_P(buffer, vp.size, PSTR("%dx%dx%d"), X_BED_SIZE, Y_BED_SIZE, (Z_MAX_POS - Z_MIN_POS)); - dgus_display.WriteString((uint16_t)vp.addr, buffer, vp.size); + dgus.writeString((uint16_t)vp.addr, buffer, vp.size); } -void DGUSTxHandler::TotalPrints(DGUS_VP &vp) { +void DGUSTxHandler::totalPrints(DGUS_VP &vp) { #if ENABLED(PRINTCOUNTER) - dgus_display.Write((uint16_t)vp.addr, dgus_display.SwapBytes(print_job_timer.getStats().totalPrints)); + dgus.write((uint16_t)vp.addr, dgus.swapBytes(print_job_timer.getStats().totalPrints)); #else UNUSED(vp); #endif } -void DGUSTxHandler::FinishedPrints(DGUS_VP &vp) { +void DGUSTxHandler::finishedPrints(DGUS_VP &vp) { #if ENABLED(PRINTCOUNTER) - dgus_display.Write((uint16_t)vp.addr, dgus_display.SwapBytes(print_job_timer.getStats().finishedPrints)); + dgus.write((uint16_t)vp.addr, dgus.swapBytes(print_job_timer.getStats().finishedPrints)); #else UNUSED(vp); #endif } -void DGUSTxHandler::PrintTime(DGUS_VP &vp) { +void DGUSTxHandler::printTime(DGUS_VP &vp) { #if ENABLED(PRINTCOUNTER) char buffer[21]; ExtUI::getTotalPrintTime_str(buffer); - dgus_display.WriteString((uint16_t)vp.addr, buffer, vp.size); + dgus.writeString((uint16_t)vp.addr, buffer, vp.size); #else - dgus_display.WriteString((uint16_t)vp.addr, F("-"), vp.size); + dgus.writeString((uint16_t)vp.addr, F("-"), vp.size); #endif } -void DGUSTxHandler::LongestPrint(DGUS_VP &vp) { +void DGUSTxHandler::longestPrint(DGUS_VP &vp) { #if ENABLED(PRINTCOUNTER) char buffer[21]; ExtUI::getLongestPrint_str(buffer); - dgus_display.WriteString((uint16_t)vp.addr, buffer, vp.size); + dgus.writeString((uint16_t)vp.addr, buffer, vp.size); #else - dgus_display.WriteString((uint16_t)vp.addr, F("-"), vp.size); + dgus.writeString((uint16_t)vp.addr, F("-"), vp.size); #endif } -void DGUSTxHandler::FilamentUsed(DGUS_VP &vp) { +void DGUSTxHandler::filamentUsed(DGUS_VP &vp) { #if ENABLED(PRINTCOUNTER) char buffer[21]; ExtUI::getFilamentUsed_str(buffer); - dgus_display.WriteString((uint16_t)vp.addr, buffer, vp.size); + dgus.writeString((uint16_t)vp.addr, buffer, vp.size); #else - dgus_display.WriteString((uint16_t)vp.addr, F("-"), vp.size); + dgus.writeString((uint16_t)vp.addr, F("-"), vp.size); #endif } -void DGUSTxHandler::WaitIcons(DGUS_VP &vp) { +void DGUSTxHandler::waitIcons(DGUS_VP &vp) { uint16_t icons = 0; if (ExtUI::isPrintingPaused()) { icons |= (uint16_t)DGUS_Data::WaitIcon::ABORT; - dgus_display.EnableControl(DGUS_Screen::WAIT, + dgus.enableControl(DGUS_ScreenID::WAIT, DGUSDisplay::POPUP_WINDOW, DGUS_Control::ABORT); } else { - dgus_display.DisableControl(DGUS_Screen::WAIT, + dgus.disableControl(DGUS_ScreenID::WAIT, DGUSDisplay::POPUP_WINDOW, DGUS_Control::ABORT); } - if (dgus_screen_handler.wait_continue) { + if (screen.wait_continue) { icons |= (uint16_t)DGUS_Data::WaitIcon::CONTINUE; - dgus_display.EnableControl(DGUS_Screen::WAIT, + dgus.enableControl(DGUS_ScreenID::WAIT, DGUSDisplay::RETURN_KEY_CODE, DGUS_Control::CONTINUE); } else { - dgus_display.DisableControl(DGUS_Screen::WAIT, + dgus.disableControl(DGUS_ScreenID::WAIT, DGUSDisplay::RETURN_KEY_CODE, DGUS_Control::CONTINUE); } - dgus_display.Write((uint16_t)vp.addr, Swap16(icons)); + dgus.write((uint16_t)vp.addr, Swap16(icons)); } -void DGUSTxHandler::FanSpeed(DGUS_VP &vp) { +void DGUSTxHandler::fanSpeed(DGUS_VP &vp) { uint16_t fan_speed; switch (vp.addr) { @@ -585,31 +585,31 @@ void DGUSTxHandler::FanSpeed(DGUS_VP &vp) { case DGUS_Addr::FAN0_Speed: fan_speed = ExtUI::getTargetFan_percent(ExtUI::FAN0); break; } - dgus_display.Write((uint16_t)vp.addr, Swap16(fan_speed)); + dgus.write((uint16_t)vp.addr, Swap16(fan_speed)); } -void DGUSTxHandler::Volume(DGUS_VP &vp) { - const uint16_t volume = dgus_display.GetVolume(); +void DGUSTxHandler::volume(DGUS_VP &vp) { + const uint16_t volume = dgus.getVolume(); - dgus_display.Write((uint16_t)vp.addr, Swap16(volume)); + dgus.write((uint16_t)vp.addr, Swap16(volume)); } -void DGUSTxHandler::Brightness(DGUS_VP &vp) { - const uint16_t brightness = dgus_display.GetBrightness(); +void DGUSTxHandler::brightness(DGUS_VP &vp) { + const uint16_t brightness = dgus.getBrightness(); - dgus_display.Write((uint16_t)vp.addr, Swap16(brightness)); + dgus.write((uint16_t)vp.addr, Swap16(brightness)); } -void DGUSTxHandler::ExtraToString(DGUS_VP &vp) { +void DGUSTxHandler::extraToString(DGUS_VP &vp) { if (!vp.size || !vp.extra) return; - dgus_display.WriteString((uint16_t)vp.addr, vp.extra, vp.size, true, false, false); + dgus.writeString((uint16_t)vp.addr, vp.extra, vp.size, true, false, false); } -void DGUSTxHandler::ExtraPGMToString(DGUS_VP &vp) { +void DGUSTxHandler::extraPGMToString(DGUS_VP &vp) { if (!vp.size || !vp.extra) return; - dgus_display.WriteStringPGM((uint16_t)vp.addr, vp.extra, vp.size, true, false, false); + dgus.writeStringPGM((uint16_t)vp.addr, vp.extra, vp.size, true, false, false); } #endif // DGUS_LCD_UI_RELOADED diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.h b/Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.h index 6e4f1db5dc7e..c82f4c80dadc 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.h +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.h @@ -29,97 +29,97 @@ namespace DGUSTxHandler { #if HAS_MEDIA - void SetFileControlState(int16_t, bool); - void FileType(DGUS_VP &); - void FileName(DGUS_VP &); - void ScrollIcons(DGUS_VP &); - void SelectedFileName(DGUS_VP &); + void setFileControlState(int16_t, bool); + void fileType(DGUS_VP &); + void fileName(DGUS_VP &); + void scrollIcons(DGUS_VP &); + void selectedFileName(DGUS_VP &); #endif - void PositionZ(DGUS_VP &); - void Elapsed(DGUS_VP &); - void Percent(DGUS_VP &); - void StatusIcons(DGUS_VP &); + void zPosition(DGUS_VP &); + void elapsed(DGUS_VP &); + void percent(DGUS_VP &); + void statusIcons(DGUS_VP &); - void Flowrate(DGUS_VP &); + void flowrate(DGUS_VP &); - void TempMax(DGUS_VP &); + void tempMax(DGUS_VP &); - void StepperStatus(DGUS_VP &); + void stepperStatus(DGUS_VP &); - void StepIcons(DGUS_VP &); + void stepIcons(DGUS_VP &); - void ABLDisableIcon(DGUS_VP &); - void ABLGrid(DGUS_VP &); + void ablDisableIcon(DGUS_VP &); + void ablGrid(DGUS_VP &); - void FilamentIcons(DGUS_VP &); + void filamentIcons(DGUS_VP &); - void BLTouch(DGUS_VP &); + void blTouch(DGUS_VP &); - void PIDIcons(DGUS_VP &); - void PIDKp(DGUS_VP &); - void PIDKi(DGUS_VP &); - void PIDKd(DGUS_VP &); + void pidIcons(DGUS_VP &); + void pidKp(DGUS_VP &); + void pidKi(DGUS_VP &); + void pidKd(DGUS_VP &); - void BuildVolume(DGUS_VP &); - void TotalPrints(DGUS_VP &); - void FinishedPrints(DGUS_VP &); - void PrintTime(DGUS_VP &); - void LongestPrint(DGUS_VP &); - void FilamentUsed(DGUS_VP &); + void buildVolume(DGUS_VP &); + void totalPrints(DGUS_VP &); + void finishedPrints(DGUS_VP &); + void printTime(DGUS_VP &); + void longestPrint(DGUS_VP &); + void filamentUsed(DGUS_VP &); - void WaitIcons(DGUS_VP &); + void waitIcons(DGUS_VP &); - void FanSpeed(DGUS_VP &); + void fanSpeed(DGUS_VP &); - void Volume(DGUS_VP &); + void volume(DGUS_VP &); - void Brightness(DGUS_VP &); + void brightness(DGUS_VP &); - void ExtraToString(DGUS_VP &); - void ExtraPGMToString(DGUS_VP &); + void extraToString(DGUS_VP &); + void extraPGMToString(DGUS_VP &); template - void ExtraToInteger(DGUS_VP &vp) { + void extraToInteger(DGUS_VP &vp) { if (!vp.size || !vp.extra) return; switch (vp.size) { default: return; case 1: { const uint8_t data = uint8_t(*(T*)vp.extra); - dgus_display.Write(uint16_t(vp.addr), data); + dgus.write(uint16_t(vp.addr), data); break; } case 2: { const uint16_t data = uint16_t(*(T*)vp.extra); - dgus_display.Write(uint16_t(vp.addr), Swap16(data)); + dgus.write(uint16_t(vp.addr), Swap16(data)); break; } case 4: { const uint32_t data = uint32_t(*(T*)vp.extra); - dgus_display.Write(uint16_t(vp.addr), dgus_display.SwapBytes(data)); + dgus.write(uint16_t(vp.addr), dgus.swapBytes(data)); break; } } } template - void ExtraToFixedPoint(DGUS_VP &vp) { + void extraToFixedPoint(DGUS_VP &vp) { if (!vp.size || !vp.extra) return; switch (vp.size) { default: return; case 1: { - const uint8_t data = dgus_display.ToFixedPoint(*(T*)vp.extra); - dgus_display.Write(uint16_t(vp.addr), data); + const uint8_t data = dgus.toFixedPoint(*(T*)vp.extra); + dgus.write(uint16_t(vp.addr), data); break; } case 2: { - const uint16_t data = dgus_display.ToFixedPoint(*(T*)vp.extra); - dgus_display.Write(uint16_t(vp.addr), Swap16(data)); + const uint16_t data = dgus.toFixedPoint(*(T*)vp.extra); + dgus.write(uint16_t(vp.addr), Swap16(data)); break; } case 4: { - const uint32_t data = dgus_display.ToFixedPoint(*(T*)vp.extra); - dgus_display.Write(uint16_t(vp.addr), dgus_display.SwapBytes(data)); + const uint32_t data = dgus.toFixedPoint(*(T*)vp.extra); + dgus.write(uint16_t(vp.addr), dgus.swapBytes(data)); break; } } diff --git a/Marlin/src/lcd/extui/dgus_reloaded/config/DGUS_Screen.h b/Marlin/src/lcd/extui/dgus_reloaded/config/DGUS_ScreenID.h similarity index 97% rename from Marlin/src/lcd/extui/dgus_reloaded/config/DGUS_Screen.h rename to Marlin/src/lcd/extui/dgus_reloaded/config/DGUS_ScreenID.h index 0a738223ce36..546ebb466665 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/config/DGUS_Screen.h +++ b/Marlin/src/lcd/extui/dgus_reloaded/config/DGUS_ScreenID.h @@ -21,7 +21,7 @@ */ #pragma once -enum class DGUS_Screen : uint8_t { +enum class DGUS_ScreenID : uint8_t { BOOT = 0, HOME = 1, PRINT = 2, diff --git a/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_ScreenAddrList.cpp b/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_ScreenAddrList.cpp index 4c99ff6a0089..1a99eceeff3a 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_ScreenAddrList.cpp +++ b/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_ScreenAddrList.cpp @@ -204,37 +204,35 @@ constexpr DGUS_Addr LIST_WAIT[] PROGMEM = { (DGUS_Addr)0 }; -#define MAP_HELPER(SCREEN, LIST) \ - { .screen = SCREEN, \ - .addr_list = LIST } +#define MAP_HELPER(SCREEN, LIST) { .screenID = SCREEN, .addr_list = LIST } const struct DGUS_ScreenAddrList screen_addr_list_map[] PROGMEM = { - MAP_HELPER(DGUS_Screen::HOME, LIST_HOME), + MAP_HELPER(DGUS_ScreenID::HOME, LIST_HOME), #if HAS_MEDIA - MAP_HELPER(DGUS_Screen::PRINT, LIST_PRINT), + MAP_HELPER(DGUS_ScreenID::PRINT, LIST_PRINT), #endif - MAP_HELPER(DGUS_Screen::PRINT_STATUS, LIST_PRINT_STATUS), - MAP_HELPER(DGUS_Screen::PRINT_ADJUST, LIST_PRINT_ADJUST), - MAP_HELPER(DGUS_Screen::PRINT_FINISHED, LIST_PRINT_FINISHED), - MAP_HELPER(DGUS_Screen::TEMP_MENU, LIST_TEMP_MENU), - MAP_HELPER(DGUS_Screen::TEMP_MANUAL, LIST_TEMP_MANUAL), - MAP_HELPER(DGUS_Screen::FAN, LIST_FAN), - MAP_HELPER(DGUS_Screen::SETTINGS_MENU, LIST_SETTINGS_MENU), - MAP_HELPER(DGUS_Screen::LEVELING_OFFSET, LIST_LEVELING_OFFSET), - MAP_HELPER(DGUS_Screen::LEVELING_MANUAL, LIST_LEVELING_MANUAL), - MAP_HELPER(DGUS_Screen::LEVELING_AUTOMATIC, LIST_LEVELING_AUTOMATIC), - MAP_HELPER(DGUS_Screen::LEVELING_PROBING, LIST_LEVELING_PROBING), - MAP_HELPER(DGUS_Screen::FILAMENT, LIST_FILAMENT), - MAP_HELPER(DGUS_Screen::MOVE, LIST_MOVE), - MAP_HELPER(DGUS_Screen::GCODE, LIST_GCODE), - MAP_HELPER(DGUS_Screen::SETTINGS_MENU2, LIST_SETTINGS_MENU2), - MAP_HELPER(DGUS_Screen::PID, LIST_PID), - MAP_HELPER(DGUS_Screen::VOLUME, LIST_VOLUME), - MAP_HELPER(DGUS_Screen::BRIGHTNESS, LIST_BRIGHTNESS), - MAP_HELPER(DGUS_Screen::INFOS, LIST_INFOS), - MAP_HELPER(DGUS_Screen::WAIT, LIST_WAIT), - - MAP_HELPER((DGUS_Screen)0, nullptr) + MAP_HELPER(DGUS_ScreenID::PRINT_STATUS, LIST_PRINT_STATUS), + MAP_HELPER(DGUS_ScreenID::PRINT_ADJUST, LIST_PRINT_ADJUST), + MAP_HELPER(DGUS_ScreenID::PRINT_FINISHED, LIST_PRINT_FINISHED), + MAP_HELPER(DGUS_ScreenID::TEMP_MENU, LIST_TEMP_MENU), + MAP_HELPER(DGUS_ScreenID::TEMP_MANUAL, LIST_TEMP_MANUAL), + MAP_HELPER(DGUS_ScreenID::FAN, LIST_FAN), + MAP_HELPER(DGUS_ScreenID::SETTINGS_MENU, LIST_SETTINGS_MENU), + MAP_HELPER(DGUS_ScreenID::LEVELING_OFFSET, LIST_LEVELING_OFFSET), + MAP_HELPER(DGUS_ScreenID::LEVELING_MANUAL, LIST_LEVELING_MANUAL), + MAP_HELPER(DGUS_ScreenID::LEVELING_AUTOMATIC, LIST_LEVELING_AUTOMATIC), + MAP_HELPER(DGUS_ScreenID::LEVELING_PROBING, LIST_LEVELING_PROBING), + MAP_HELPER(DGUS_ScreenID::FILAMENT, LIST_FILAMENT), + MAP_HELPER(DGUS_ScreenID::MOVE, LIST_MOVE), + MAP_HELPER(DGUS_ScreenID::GCODE, LIST_GCODE), + MAP_HELPER(DGUS_ScreenID::SETTINGS_MENU2, LIST_SETTINGS_MENU2), + MAP_HELPER(DGUS_ScreenID::PID, LIST_PID), + MAP_HELPER(DGUS_ScreenID::VOLUME, LIST_VOLUME), + MAP_HELPER(DGUS_ScreenID::BRIGHTNESS, LIST_BRIGHTNESS), + MAP_HELPER(DGUS_ScreenID::INFOS, LIST_INFOS), + MAP_HELPER(DGUS_ScreenID::WAIT, LIST_WAIT), + + MAP_HELPER((DGUS_ScreenID)0, nullptr) }; #endif // DGUS_LCD_UI_RELOADED diff --git a/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_ScreenAddrList.h b/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_ScreenAddrList.h index 1e481ef3cce6..dea39ed145ad 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_ScreenAddrList.h +++ b/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_ScreenAddrList.h @@ -21,12 +21,12 @@ */ #pragma once -#include "../config/DGUS_Screen.h" +#include "../config/DGUS_ScreenID.h" #include "../config/DGUS_Addr.h" struct DGUS_ScreenAddrList { - DGUS_Screen screen; - const DGUS_Addr *addr_list; + DGUS_ScreenID screenID; + const DGUS_Addr *addr_list; }; extern const struct DGUS_ScreenAddrList screen_addr_list_map[]; diff --git a/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_ScreenSetup.cpp b/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_ScreenSetup.cpp index e3ba393af25b..e01f6ab3a6bb 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_ScreenSetup.cpp +++ b/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_ScreenSetup.cpp @@ -30,28 +30,26 @@ #include "../../ui_api.h" -#define SETUP_HELPER(SCREEN, SETUP) \ - { .screen = SCREEN, \ - .setup_fn = SETUP } +#define SETUP_HELPER(SCREEN, SETUP) { .screenID = SCREEN, .setup_fn = SETUP } const struct DGUS_ScreenSetup screen_setup_list[] PROGMEM = { #if HAS_MEDIA - SETUP_HELPER(DGUS_Screen::PRINT, &DGUSSetupHandler::Print), + SETUP_HELPER(DGUS_ScreenID::PRINT, &DGUSSetupHandler::Print), #endif - SETUP_HELPER(DGUS_Screen::PRINT_STATUS, &DGUSSetupHandler::PrintStatus), - SETUP_HELPER(DGUS_Screen::PRINT_ADJUST, &DGUSSetupHandler::PrintAdjust), - SETUP_HELPER(DGUS_Screen::LEVELING_MENU, &DGUSSetupHandler::LevelingMenu), - SETUP_HELPER(DGUS_Screen::LEVELING_OFFSET, &DGUSSetupHandler::LevelingOffset), - SETUP_HELPER(DGUS_Screen::LEVELING_MANUAL, &DGUSSetupHandler::LevelingManual), - SETUP_HELPER(DGUS_Screen::LEVELING_AUTOMATIC, &DGUSSetupHandler::LevelingAutomatic), - SETUP_HELPER(DGUS_Screen::LEVELING_PROBING, &DGUSSetupHandler::LevelingProbing), - SETUP_HELPER(DGUS_Screen::FILAMENT, &DGUSSetupHandler::Filament), - SETUP_HELPER(DGUS_Screen::MOVE, &DGUSSetupHandler::Move), - SETUP_HELPER(DGUS_Screen::GCODE, &DGUSSetupHandler::Gcode), - SETUP_HELPER(DGUS_Screen::PID, &DGUSSetupHandler::PID), - SETUP_HELPER(DGUS_Screen::INFOS, &DGUSSetupHandler::Infos), - - SETUP_HELPER((DGUS_Screen)0, nullptr) + SETUP_HELPER(DGUS_ScreenID::PRINT_STATUS, &DGUSSetupHandler::PrintStatus), + SETUP_HELPER(DGUS_ScreenID::PRINT_ADJUST, &DGUSSetupHandler::PrintAdjust), + SETUP_HELPER(DGUS_ScreenID::LEVELING_MENU, &DGUSSetupHandler::LevelingMenu), + SETUP_HELPER(DGUS_ScreenID::LEVELING_OFFSET, &DGUSSetupHandler::LevelingOffset), + SETUP_HELPER(DGUS_ScreenID::LEVELING_MANUAL, &DGUSSetupHandler::LevelingManual), + SETUP_HELPER(DGUS_ScreenID::LEVELING_AUTOMATIC, &DGUSSetupHandler::LevelingAutomatic), + SETUP_HELPER(DGUS_ScreenID::LEVELING_PROBING, &DGUSSetupHandler::LevelingProbing), + SETUP_HELPER(DGUS_ScreenID::FILAMENT, &DGUSSetupHandler::Filament), + SETUP_HELPER(DGUS_ScreenID::MOVE, &DGUSSetupHandler::Move), + SETUP_HELPER(DGUS_ScreenID::GCODE, &DGUSSetupHandler::Gcode), + SETUP_HELPER(DGUS_ScreenID::PID, &DGUSSetupHandler::PID), + SETUP_HELPER(DGUS_ScreenID::INFOS, &DGUSSetupHandler::Infos), + + SETUP_HELPER((DGUS_ScreenID)0, nullptr) }; #endif // DGUS_LCD_UI_RELOADED diff --git a/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_ScreenSetup.h b/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_ScreenSetup.h index 93df5ad90ae6..e740997ad446 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_ScreenSetup.h +++ b/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_ScreenSetup.h @@ -21,10 +21,10 @@ */ #pragma once -#include "../config/DGUS_Screen.h" +#include "../config/DGUS_ScreenID.h" struct DGUS_ScreenSetup { - DGUS_Screen screen; + DGUS_ScreenID screenID; bool (*setup_fn)(void); }; diff --git a/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_VPList.cpp b/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_VPList.cpp index 69f792c45d1b..172cf98fe6f6 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_VPList.cpp +++ b/Marlin/src/lcd/extui/dgus_reloaded/definition/DGUS_VPList.cpp @@ -75,248 +75,248 @@ const struct DGUS_VP vp_list[] PROGMEM = { // READ-ONLY VARIABLES - VP_HELPER_RX(DGUS_Addr::SCREENCHANGE, &DGUSRxHandler::ScreenChange), - VP_HELPER_RX(DGUS_Addr::SCREENCHANGE_SD, &DGUSRxHandler::ScreenChange), - VP_HELPER_RX(DGUS_Addr::SCREENCHANGE_Idle, &DGUSRxHandler::ScreenChange), - VP_HELPER_RX(DGUS_Addr::SCREENCHANGE_Printing, &DGUSRxHandler::ScreenChange), + VP_HELPER_RX(DGUS_Addr::SCREENCHANGE, &DGUSRxHandler::screenChange), + VP_HELPER_RX(DGUS_Addr::SCREENCHANGE_SD, &DGUSRxHandler::screenChange), + VP_HELPER_RX(DGUS_Addr::SCREENCHANGE_Idle, &DGUSRxHandler::screenChange), + VP_HELPER_RX(DGUS_Addr::SCREENCHANGE_Printing, &DGUSRxHandler::screenChange), #if HAS_MEDIA VP_HELPER_RX(DGUS_Addr::SD_SelectFile, &DGUSRxHandler::selectFile), - VP_HELPER_RX(DGUS_Addr::SD_Scroll, &DGUSRxHandler::Scroll), - VP_HELPER_RX_NODATA(DGUS_Addr::SD_Print, &DGUSRxHandler::PrintFile), + VP_HELPER_RX(DGUS_Addr::SD_Scroll, &DGUSRxHandler::scroll), + VP_HELPER_RX_NODATA(DGUS_Addr::SD_Print, &DGUSRxHandler::printFile), #endif - VP_HELPER_RX(DGUS_Addr::STATUS_Abort, &DGUSRxHandler::PrintAbort), - VP_HELPER_RX(DGUS_Addr::STATUS_Pause, &DGUSRxHandler::PrintPause), - VP_HELPER_RX(DGUS_Addr::STATUS_Resume, &DGUSRxHandler::PrintResume), + VP_HELPER_RX(DGUS_Addr::STATUS_Abort, &DGUSRxHandler::printAbort), + VP_HELPER_RX(DGUS_Addr::STATUS_Pause, &DGUSRxHandler::printPause), + VP_HELPER_RX(DGUS_Addr::STATUS_Resume, &DGUSRxHandler::printResume), - VP_HELPER_RX(DGUS_Addr::ADJUST_SetFeedrate, &DGUSRxHandler::Feedrate), - VP_HELPER_RX(DGUS_Addr::ADJUST_SetFlowrate_CUR, &DGUSRxHandler::Flowrate), + VP_HELPER_RX(DGUS_Addr::ADJUST_SetFeedrate, &DGUSRxHandler::feedrate), + VP_HELPER_RX(DGUS_Addr::ADJUST_SetFlowrate_CUR, &DGUSRxHandler::flowrate), #if HAS_MULTI_EXTRUDER - VP_HELPER_RX(DGUS_Addr::ADJUST_SetFlowrate_E0, &DGUSRxHandler::Flowrate), - VP_HELPER_RX(DGUS_Addr::ADJUST_SetFlowrate_E1, &DGUSRxHandler::Flowrate), + VP_HELPER_RX(DGUS_Addr::ADJUST_SetFlowrate_E0, &DGUSRxHandler::flowrate), + VP_HELPER_RX(DGUS_Addr::ADJUST_SetFlowrate_E1, &DGUSRxHandler::flowrate), #endif - VP_HELPER_RX(DGUS_Addr::ADJUST_SetBabystep, &DGUSRxHandler::BabystepSet), - VP_HELPER_RX(DGUS_Addr::ADJUST_Babystep, &DGUSRxHandler::Babystep), + VP_HELPER_RX(DGUS_Addr::ADJUST_SetBabystep, &DGUSRxHandler::babystepSet), + VP_HELPER_RX(DGUS_Addr::ADJUST_Babystep, &DGUSRxHandler::babystep), - VP_HELPER_RX(DGUS_Addr::TEMP_Preset, &DGUSRxHandler::TempPreset), - VP_HELPER_RX(DGUS_Addr::TEMP_SetTarget_Bed, &DGUSRxHandler::TempTarget), - VP_HELPER_RX(DGUS_Addr::TEMP_SetTarget_H0, &DGUSRxHandler::TempTarget), + VP_HELPER_RX(DGUS_Addr::TEMP_Preset, &DGUSRxHandler::tempPreset), + VP_HELPER_RX(DGUS_Addr::TEMP_SetTarget_Bed, &DGUSRxHandler::tempTarget), + VP_HELPER_RX(DGUS_Addr::TEMP_SetTarget_H0, &DGUSRxHandler::tempTarget), #if HAS_MULTI_HOTEND - VP_HELPER_RX(DGUS_Addr::TEMP_SetTarget_H1, &DGUSRxHandler::TempTarget), + VP_HELPER_RX(DGUS_Addr::TEMP_SetTarget_H1, &DGUSRxHandler::tempTarget), #endif - VP_HELPER_RX(DGUS_Addr::TEMP_Cool, &DGUSRxHandler::TempCool), + VP_HELPER_RX(DGUS_Addr::TEMP_Cool, &DGUSRxHandler::tempCool), - VP_HELPER_RX(DGUS_Addr::STEPPER_Control, &DGUSRxHandler::Steppers), + VP_HELPER_RX(DGUS_Addr::STEPPER_Control, &DGUSRxHandler::steppers), - VP_HELPER_RX(DGUS_Addr::LEVEL_OFFSET_Set, &DGUSRxHandler::ZOffset), - VP_HELPER_RX(DGUS_Addr::LEVEL_OFFSET_Step, &DGUSRxHandler::ZOffsetStep), - VP_HELPER_RX(DGUS_Addr::LEVEL_OFFSET_SetStep, &DGUSRxHandler::ZOffsetSetStep), + VP_HELPER_RX(DGUS_Addr::LEVEL_OFFSET_Set, &DGUSRxHandler::zOffset), + VP_HELPER_RX(DGUS_Addr::LEVEL_OFFSET_Step, &DGUSRxHandler::zOffsetStep), + VP_HELPER_RX(DGUS_Addr::LEVEL_OFFSET_SetStep, &DGUSRxHandler::zOffsetSetStep), - VP_HELPER_RX(DGUS_Addr::LEVEL_MANUAL_Point, &DGUSRxHandler::MoveToPoint), + VP_HELPER_RX(DGUS_Addr::LEVEL_MANUAL_Point, &DGUSRxHandler::moveToPoint), - VP_HELPER_RX_NODATA(DGUS_Addr::LEVEL_AUTO_Probe, &DGUSRxHandler::Probe), - VP_HELPER_RX_NODATA(DGUS_Addr::LEVEL_AUTO_Disable, &DGUSRxHandler::DisableABL), + VP_HELPER_RX_NODATA(DGUS_Addr::LEVEL_AUTO_Probe, &DGUSRxHandler::probe), + VP_HELPER_RX_NODATA(DGUS_Addr::LEVEL_AUTO_Disable, &DGUSRxHandler::disableABL), - VP_HELPER_RX(DGUS_Addr::FILAMENT_Select, &DGUSRxHandler::FilamentSelect), - VP_HELPER_RX(DGUS_Addr::FILAMENT_SetLength, &DGUSRxHandler::FilamentLength), - VP_HELPER_RX(DGUS_Addr::FILAMENT_Move, &DGUSRxHandler::FilamentMove), + VP_HELPER_RX(DGUS_Addr::FILAMENT_Select, &DGUSRxHandler::filamentSelect), + VP_HELPER_RX(DGUS_Addr::FILAMENT_SetLength, &DGUSRxHandler::filamentLength), + VP_HELPER_RX(DGUS_Addr::FILAMENT_Move, &DGUSRxHandler::filamentMove), - VP_HELPER_RX(DGUS_Addr::MOVE_Home, &DGUSRxHandler::Home), - VP_HELPER_RX(DGUS_Addr::MOVE_SetX, &DGUSRxHandler::Move), - VP_HELPER_RX(DGUS_Addr::MOVE_SetY, &DGUSRxHandler::Move), - VP_HELPER_RX(DGUS_Addr::MOVE_SetZ, &DGUSRxHandler::Move), - VP_HELPER_RX(DGUS_Addr::MOVE_Step, &DGUSRxHandler::MoveStep), - VP_HELPER_RX(DGUS_Addr::MOVE_SetStep, &DGUSRxHandler::MoveSetStep), + VP_HELPER_RX(DGUS_Addr::MOVE_Home, &DGUSRxHandler::home), + VP_HELPER_RX(DGUS_Addr::MOVE_SetX, &DGUSRxHandler::move), + VP_HELPER_RX(DGUS_Addr::MOVE_SetY, &DGUSRxHandler::move), + VP_HELPER_RX(DGUS_Addr::MOVE_SetZ, &DGUSRxHandler::move), + VP_HELPER_RX(DGUS_Addr::MOVE_Step, &DGUSRxHandler::moveStep), + VP_HELPER_RX(DGUS_Addr::MOVE_SetStep, &DGUSRxHandler::moveSetStep), - VP_HELPER_RX_NODATA(DGUS_Addr::GCODE_Clear, &DGUSRxHandler::GcodeClear), - VP_HELPER_RX_NODATA(DGUS_Addr::GCODE_Execute, &DGUSRxHandler::GcodeExecute), + VP_HELPER_RX_NODATA(DGUS_Addr::GCODE_Clear, &DGUSRxHandler::gcodeClear), + VP_HELPER_RX_NODATA(DGUS_Addr::GCODE_Execute, &DGUSRxHandler::gcodeExecute), - VP_HELPER_RX(DGUS_Addr::EEPROM_Reset, &DGUSRxHandler::ResetEEPROM), + VP_HELPER_RX(DGUS_Addr::EEPROM_Reset, &DGUSRxHandler::resetEEPROM), - VP_HELPER_RX(DGUS_Addr::SETTINGS2_Extra, &DGUSRxHandler::SettingsExtra), + VP_HELPER_RX(DGUS_Addr::SETTINGS2_Extra, &DGUSRxHandler::settingsExtra), - VP_HELPER_RX(DGUS_Addr::PID_Select, &DGUSRxHandler::PIDSelect), - VP_HELPER_RX(DGUS_Addr::PID_SetTemp, &DGUSRxHandler::PIDSetTemp), - VP_HELPER_RX_NODATA(DGUS_Addr::PID_Run, &DGUSRxHandler::PIDRun), + VP_HELPER_RX(DGUS_Addr::PID_Select, &DGUSRxHandler::pidSelect), + VP_HELPER_RX(DGUS_Addr::PID_SetTemp, &DGUSRxHandler::pidSetTemp), + VP_HELPER_RX_NODATA(DGUS_Addr::PID_Run, &DGUSRxHandler::pidRun), #if ENABLED(POWER_LOSS_RECOVERY) - VP_HELPER_RX(DGUS_Addr::POWERLOSS_Abort, &DGUSRxHandler::PowerLossAbort), - VP_HELPER_RX(DGUS_Addr::POWERLOSS_Resume, &DGUSRxHandler::PowerLossResume), + VP_HELPER_RX(DGUS_Addr::POWERLOSS_Abort, &DGUSRxHandler::powerLossAbort), + VP_HELPER_RX(DGUS_Addr::POWERLOSS_Resume, &DGUSRxHandler::powerLossResume), #endif - VP_HELPER_RX(DGUS_Addr::WAIT_Abort, &DGUSRxHandler::WaitAbort), - VP_HELPER_RX_NODATA(DGUS_Addr::WAIT_Continue, &DGUSRxHandler::WaitContinue), + VP_HELPER_RX(DGUS_Addr::WAIT_Abort, &DGUSRxHandler::waitAbort), + VP_HELPER_RX_NODATA(DGUS_Addr::WAIT_Continue, &DGUSRxHandler::waitContinue), // WRITE-ONLY VARIABLES #if HAS_MEDIA - VP_HELPER_TX(DGUS_Addr::SD_Type, &DGUSTxHandler::FileType), + VP_HELPER_TX(DGUS_Addr::SD_Type, &DGUSTxHandler::fileType), VP_HELPER_TX_SIZE(DGUS_Addr::SD_FileName0, DGUS_FILENAME_LEN, - &DGUSTxHandler::FileName), + &DGUSTxHandler::fileName), VP_HELPER_TX_SIZE(DGUS_Addr::SD_FileName1, DGUS_FILENAME_LEN, - &DGUSTxHandler::FileName), + &DGUSTxHandler::fileName), VP_HELPER_TX_SIZE(DGUS_Addr::SD_FileName2, DGUS_FILENAME_LEN, - &DGUSTxHandler::FileName), + &DGUSTxHandler::fileName), VP_HELPER_TX_SIZE(DGUS_Addr::SD_FileName3, DGUS_FILENAME_LEN, - &DGUSTxHandler::FileName), + &DGUSTxHandler::fileName), VP_HELPER_TX_SIZE(DGUS_Addr::SD_FileName4, DGUS_FILENAME_LEN, - &DGUSTxHandler::FileName), - VP_HELPER_TX(DGUS_Addr::SD_ScrollIcons, &DGUSTxHandler::ScrollIcons), + &DGUSTxHandler::fileName), + VP_HELPER_TX(DGUS_Addr::SD_ScrollIcons, &DGUSTxHandler::scrollIcons), VP_HELPER_TX_SIZE(DGUS_Addr::SD_SelectedFileName, DGUS_FILENAME_LEN, - &DGUSTxHandler::SelectedFileName), + &DGUSTxHandler::selectedFileName), #endif VP_HELPER_TX_AUTO(DGUS_Addr::STATUS_PositionZ, nullptr, - &DGUSTxHandler::PositionZ), + &DGUSTxHandler::zPosition), VP_HELPER(DGUS_Addr::STATUS_Elapsed, DGUS_ELAPSED_LEN, VPFLAG_AUTOUPLOAD, nullptr, nullptr, - &DGUSTxHandler::Elapsed), + &DGUSTxHandler::elapsed), VP_HELPER_TX_AUTO(DGUS_Addr::STATUS_Percent, nullptr, - &DGUSTxHandler::Percent), - VP_HELPER_TX(DGUS_Addr::STATUS_Icons, &DGUSTxHandler::StatusIcons), + &DGUSTxHandler::percent), + VP_HELPER_TX(DGUS_Addr::STATUS_Icons, &DGUSTxHandler::statusIcons), VP_HELPER_TX_AUTO(DGUS_Addr::ADJUST_Feedrate, &feedrate_percentage, - &DGUSTxHandler::ExtraToInteger), + &DGUSTxHandler::extraToInteger), VP_HELPER_TX_AUTO(DGUS_Addr::ADJUST_Flowrate_CUR, nullptr, - &DGUSTxHandler::Flowrate), + &DGUSTxHandler::flowrate), #if HAS_MULTI_EXTRUDER VP_HELPER_TX_AUTO(DGUS_Addr::ADJUST_Flowrate_E0, nullptr, - &DGUSTxHandler::Flowrate), + &DGUSTxHandler::flowrate), VP_HELPER_TX_AUTO(DGUS_Addr::ADJUST_Flowrate_E1, nullptr, - &DGUSTxHandler::Flowrate), + &DGUSTxHandler::flowrate), #endif VP_HELPER_TX_AUTO(DGUS_Addr::TEMP_Current_Bed, &thermalManager.temp_bed.celsius, - (&DGUSTxHandler::ExtraToFixedPoint)), + (&DGUSTxHandler::extraToFixedPoint)), VP_HELPER_TX_AUTO(DGUS_Addr::TEMP_Target_Bed, &thermalManager.temp_bed.target, - &DGUSTxHandler::ExtraToInteger), - VP_HELPER_TX(DGUS_Addr::TEMP_Max_Bed, &DGUSTxHandler::TempMax), + &DGUSTxHandler::extraToInteger), + VP_HELPER_TX(DGUS_Addr::TEMP_Max_Bed, &DGUSTxHandler::tempMax), VP_HELPER_TX_AUTO(DGUS_Addr::TEMP_Current_H0, &thermalManager.temp_hotend[ExtUI::heater_t::H0].celsius, - (&DGUSTxHandler::ExtraToFixedPoint)), + (&DGUSTxHandler::extraToFixedPoint)), VP_HELPER_TX_AUTO(DGUS_Addr::TEMP_Target_H0, &thermalManager.temp_hotend[ExtUI::heater_t::H0].target, - &DGUSTxHandler::ExtraToInteger), - VP_HELPER_TX(DGUS_Addr::TEMP_Max_H0, &DGUSTxHandler::TempMax), + &DGUSTxHandler::extraToInteger), + VP_HELPER_TX(DGUS_Addr::TEMP_Max_H0, &DGUSTxHandler::tempMax), #if HAS_MULTI_HOTEND VP_HELPER_TX_AUTO(DGUS_Addr::TEMP_Current_H1, &thermalManager.temp_hotend[ExtUI::heater_t::H1].celsius, - (&DGUSTxHandler::ExtraToFixedPoint)), + (&DGUSTxHandler::extraToFixedPoint)), VP_HELPER_TX_AUTO(DGUS_Addr::TEMP_Target_H1, &thermalManager.temp_hotend[ExtUI::heater_t::H1].target, - &DGUSTxHandler::ExtraToInteger), - VP_HELPER_TX(DGUS_Addr::TEMP_Max_H1, &DGUSTxHandler::TempMax), + &DGUSTxHandler::extraToInteger), + VP_HELPER_TX(DGUS_Addr::TEMP_Max_H1, &DGUSTxHandler::tempMax), #endif VP_HELPER_TX_AUTO(DGUS_Addr::STEPPER_Status, nullptr, - &DGUSTxHandler::StepperStatus), + &DGUSTxHandler::stepperStatus), VP_HELPER_TX_AUTO(DGUS_Addr::LEVEL_OFFSET_Current, &probe.offset.z, - (&DGUSTxHandler::ExtraToFixedPoint)), + (&DGUSTxHandler::extraToFixedPoint)), VP_HELPER_TX_EXTRA(DGUS_Addr::LEVEL_OFFSET_StepIcons, &DGUSScreenHandler::offset_steps, - &DGUSTxHandler::StepIcons), + &DGUSTxHandler::stepIcons), VP_HELPER_TX_AUTO(DGUS_Addr::LEVEL_AUTO_DisableIcon, nullptr, - &DGUSTxHandler::ABLDisableIcon), - VP_HELPER_TX(DGUS_Addr::LEVEL_AUTO_Grid, &DGUSTxHandler::ABLGrid), + &DGUSTxHandler::ablDisableIcon), + VP_HELPER_TX(DGUS_Addr::LEVEL_AUTO_Grid, &DGUSTxHandler::ablGrid), VP_HELPER_TX_EXTRA(DGUS_Addr::LEVEL_PROBING_Icons1, &DGUSScreenHandler::probing_icons[0], - &DGUSTxHandler::ExtraToInteger), + &DGUSTxHandler::extraToInteger), VP_HELPER_TX_EXTRA(DGUS_Addr::LEVEL_PROBING_Icons2, &DGUSScreenHandler::probing_icons[1], - &DGUSTxHandler::ExtraToInteger), + &DGUSTxHandler::extraToInteger), - VP_HELPER_TX(DGUS_Addr::FILAMENT_ExtruderIcons, &DGUSTxHandler::FilamentIcons), + VP_HELPER_TX(DGUS_Addr::FILAMENT_ExtruderIcons, &DGUSTxHandler::filamentIcons), VP_HELPER_TX_EXTRA(DGUS_Addr::FILAMENT_Length, &DGUSScreenHandler::filament_length, - &DGUSTxHandler::ExtraToInteger), + &DGUSTxHandler::extraToInteger), VP_HELPER_TX_AUTO(DGUS_Addr::MOVE_CurrentX, ¤t_position.x, - (&DGUSTxHandler::ExtraToFixedPoint)), + (&DGUSTxHandler::extraToFixedPoint)), VP_HELPER_TX_AUTO(DGUS_Addr::MOVE_CurrentY, ¤t_position.y, - (&DGUSTxHandler::ExtraToFixedPoint)), + (&DGUSTxHandler::extraToFixedPoint)), VP_HELPER_TX_AUTO(DGUS_Addr::MOVE_CurrentZ, ¤t_position.z, - (&DGUSTxHandler::ExtraToFixedPoint)), + (&DGUSTxHandler::extraToFixedPoint)), VP_HELPER_TX_EXTRA(DGUS_Addr::MOVE_StepIcons, &DGUSScreenHandler::move_steps, - &DGUSTxHandler::StepIcons), + &DGUSTxHandler::stepIcons), - VP_HELPER_TX(DGUS_Addr::SETTINGS2_BLTouch, &DGUSTxHandler::BLTouch), + VP_HELPER_TX(DGUS_Addr::SETTINGS2_BLTouch, &DGUSTxHandler::blTouch), - VP_HELPER_TX(DGUS_Addr::PID_HeaterIcons, &DGUSTxHandler::PIDIcons), + VP_HELPER_TX(DGUS_Addr::PID_HeaterIcons, &DGUSTxHandler::pidIcons), VP_HELPER_TX_EXTRA(DGUS_Addr::PID_Temp, &DGUSScreenHandler::pid_temp, - &DGUSTxHandler::ExtraToInteger), + &DGUSTxHandler::extraToInteger), VP_HELPER_DWORD(DGUS_Addr::PID_Kp, VPFLAG_AUTOUPLOAD, nullptr, nullptr, - &DGUSTxHandler::PIDKp), + &DGUSTxHandler::pidKp), VP_HELPER_DWORD(DGUS_Addr::PID_Ki, VPFLAG_AUTOUPLOAD, nullptr, nullptr, - &DGUSTxHandler::PIDKi), + &DGUSTxHandler::pidKi), VP_HELPER_DWORD(DGUS_Addr::PID_Kd, VPFLAG_AUTOUPLOAD, nullptr, nullptr, - &DGUSTxHandler::PIDKd), + &DGUSTxHandler::pidKd), VP_HELPER(DGUS_Addr::INFOS_Machine, DGUS_MACHINE_LEN, VPFLAG_NONE, (void*)DGUS_MACHINENAME, nullptr, - &DGUSTxHandler::ExtraPGMToString), + &DGUSTxHandler::extraPGMToString), VP_HELPER_TX_SIZE(DGUS_Addr::INFOS_BuildVolume, DGUS_BUILDVOLUME_LEN, - &DGUSTxHandler::BuildVolume), + &DGUSTxHandler::buildVolume), VP_HELPER(DGUS_Addr::INFOS_Version, DGUS_VERSION_LEN, VPFLAG_NONE, (void*)DGUS_MARLINVERSION, nullptr, - &DGUSTxHandler::ExtraPGMToString), - VP_HELPER_TX(DGUS_Addr::INFOS_TotalPrints, &DGUSTxHandler::TotalPrints), - VP_HELPER_TX(DGUS_Addr::INFOS_FinishedPrints, &DGUSTxHandler::FinishedPrints), + &DGUSTxHandler::extraPGMToString), + VP_HELPER_TX(DGUS_Addr::INFOS_TotalPrints, &DGUSTxHandler::totalPrints), + VP_HELPER_TX(DGUS_Addr::INFOS_FinishedPrints, &DGUSTxHandler::finishedPrints), VP_HELPER_TX_SIZE(DGUS_Addr::INFOS_PrintTime, DGUS_PRINTTIME_LEN, - &DGUSTxHandler::PrintTime), + &DGUSTxHandler::printTime), VP_HELPER_TX_SIZE(DGUS_Addr::INFOS_LongestPrint, DGUS_LONGESTPRINT_LEN, - &DGUSTxHandler::LongestPrint), + &DGUSTxHandler::longestPrint), VP_HELPER_TX_SIZE(DGUS_Addr::INFOS_FilamentUsed, DGUS_FILAMENTUSED_LEN, - &DGUSTxHandler::FilamentUsed), + &DGUSTxHandler::filamentUsed), - VP_HELPER_TX(DGUS_Addr::WAIT_Icons, &DGUSTxHandler::WaitIcons), + VP_HELPER_TX(DGUS_Addr::WAIT_Icons, &DGUSTxHandler::waitIcons), // READ-WRITE VARIABLES @@ -324,41 +324,41 @@ const struct DGUS_VP vp_list[] PROGMEM = { 2, VPFLAG_AUTOUPLOAD, nullptr, - &DGUSRxHandler::FanSpeed, - &DGUSTxHandler::FanSpeed), + &DGUSRxHandler::fanSpeed, + &DGUSTxHandler::fanSpeed), VP_HELPER(DGUS_Addr::GCODE_Data, DGUS_GCODE_LEN, VPFLAG_RXSTRING, (void*)DGUSScreenHandler::gcode, - &DGUSRxHandler::StringToExtra, - &DGUSTxHandler::ExtraToString), + &DGUSRxHandler::stringToExtra, + &DGUSTxHandler::extraToString), VP_HELPER(DGUS_Addr::PID_Cycles, 2, VPFLAG_NONE, &DGUSScreenHandler::pid_cycles, - &DGUSRxHandler::IntegerToExtra, - &DGUSTxHandler::ExtraToInteger), + &DGUSRxHandler::integerToExtra, + &DGUSTxHandler::extraToInteger), VP_HELPER(DGUS_Addr::VOLUME_Level, 2, VPFLAG_NONE, nullptr, - &DGUSRxHandler::Volume, - &DGUSTxHandler::Volume), + &DGUSRxHandler::volume, + &DGUSTxHandler::volume), VP_HELPER(DGUS_Addr::BRIGHTNESS_Level, 2, VPFLAG_NONE, nullptr, - &DGUSRxHandler::Brightness, - &DGUSTxHandler::Brightness), + &DGUSRxHandler::brightness, + &DGUSTxHandler::brightness), // SPECIAL CASES - VP_HELPER_TX(DGUS_Addr::STATUS_Percent_Complete, &DGUSTxHandler::Percent), - VP_HELPER_RX_NODATA(DGUS_Addr::INFOS_Debug, &DGUSRxHandler::Debug), + VP_HELPER_TX(DGUS_Addr::STATUS_Percent_Complete, &DGUSTxHandler::percent), + VP_HELPER_RX_NODATA(DGUS_Addr::INFOS_Debug, &DGUSRxHandler::debug), VP_HELPER((DGUS_Addr)0, 0, VPFLAG_NONE, nullptr, nullptr, nullptr) diff --git a/Marlin/src/lcd/extui/dgus_reloaded/dgus_reloaded_extui.cpp b/Marlin/src/lcd/extui/dgus_reloaded/dgus_reloaded_extui.cpp index 73dead1b56f6..e9e3940a0805 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/dgus_reloaded_extui.cpp +++ b/Marlin/src/lcd/extui/dgus_reloaded/dgus_reloaded_extui.cpp @@ -33,7 +33,7 @@ namespace ExtUI { - void onStartup() { dgus_screen_handler.Init(); } + void onStartup() { screen.init(); } void onIdle() { static bool processing = false; @@ -41,45 +41,45 @@ namespace ExtUI { // Prevent recursion if (!processing) { processing = true; - dgus_screen_handler.Loop(); + screen.loop(); processing = false; } } void onPrinterKilled(FSTR_P const error, FSTR_P const component) { - dgus_screen_handler.printerKilled(error, component); + screen.printerKilled(error, component); } - void onMediaInserted() { TERN_(HAS_MEDIA, dgus_screen_handler.SDCardInserted()); } - void onMediaError() { TERN_(HAS_MEDIA, dgus_screen_handler.SDCardError()); } - void onMediaRemoved() { TERN_(HAS_MEDIA, dgus_screen_handler.SDCardRemoved()); } + void onMediaInserted() { TERN_(HAS_MEDIA, screen.sDCardInserted()); } + void onMediaError() { TERN_(HAS_MEDIA, screen.sdCardError()); } + void onMediaRemoved() { TERN_(HAS_MEDIA, screen.sdCardRemoved()); } void onPlayTone(const uint16_t frequency, const uint16_t duration) { - dgus_screen_handler.PlayTone(frequency, duration); + screen.playTone(frequency, duration); } void onPrintTimerStarted() { - dgus_screen_handler.PrintTimerStarted(); + screen.printTimerStarted(); } void onPrintTimerPaused() { - dgus_screen_handler.PrintTimerPaused(); + screen.printTimerPaused(); } void onPrintTimerStopped() { - dgus_screen_handler.PrintTimerStopped(); + screen.printTimerStopped(); } void onFilamentRunout(const extruder_t extruder) { - dgus_screen_handler.filamentRunout(extruder); + screen.filamentRunout(extruder); } void onUserConfirmRequired(const char * const msg) { - dgus_screen_handler.UserConfirmRequired(msg); + screen.userConfirmRequired(msg); } void onStatusChanged(const char * const msg) { - dgus_screen_handler.SetStatusMessage(msg); + screen.setStatusMessage(msg); } void onHomingStart() {} @@ -87,38 +87,40 @@ namespace ExtUI { void onPrintDone() {} void onFactoryReset() { - dgus_screen_handler.SettingsReset(); + screen.settingsReset(); } void onStoreSettings(char *buff) { - dgus_screen_handler.StoreSettings(buff); + screen.storeSettings(buff); } void onLoadSettings(const char *buff) { - dgus_screen_handler.LoadSettings(buff); + screen.loadSettings(buff); } void onPostprocessSettings() {} void onSettingsStored(const bool success) { - dgus_screen_handler.ConfigurationStoreWritten(success); + screen.configurationStoreWritten(success); } void onSettingsLoaded(const bool success) { - dgus_screen_handler.ConfigurationStoreRead(success); + screen.configurationStoreRead(success); } - #if HAS_MESH + #if HAS_LEVELING void onLevelingStart() {} void onLevelingDone() {} + #endif + #if HAS_MESH void onMeshUpdate(const int8_t xpos, const int8_t ypos, const_float_t zval) { - dgus_screen_handler.MeshUpdate(xpos, ypos); + screen.meshUpdate(xpos, ypos); } void onMeshUpdate(const int8_t xpos, const int8_t ypos, const probe_state_t state) { if (state == G29_POINT_FINISH) - dgus_screen_handler.MeshUpdate(xpos, ypos); + screen.meshUpdate(xpos, ypos); } #endif @@ -131,14 +133,14 @@ namespace ExtUI { } void onPowerLossResume() { // Called on resume from power-loss - dgus_screen_handler.PowerLossResume(); + screen.powerLossResume(); } #endif #if HAS_PID_HEATING void onPidTuning(const result_t rst) { // Called for temperature PID tuning result - dgus_screen_handler.PidTuning(rst); + screen.pidTuning(rst); } #endif diff --git a/Marlin/src/lcd/extui/example/example.cpp b/Marlin/src/lcd/extui/example/example.cpp index 83b7a0a3cabc..e78e4b967987 100644 --- a/Marlin/src/lcd/extui/example/example.cpp +++ b/Marlin/src/lcd/extui/example/example.cpp @@ -21,7 +21,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if BOTH(EXTUI_EXAMPLE, EXTENSIBLE_UI) +#if ALL(EXTUI_EXAMPLE, EXTENSIBLE_UI) #include "../ui_api.h" @@ -98,10 +98,12 @@ namespace ExtUI { // whether successful or not. } - #if HAS_MESH + #if HAS_LEVELING void onLevelingStart() {} void onLevelingDone() {} + #endif + #if HAS_MESH void onMeshUpdate(const int8_t xpos, const int8_t ypos, const_float_t zval) { // Called when any mesh points are updated } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.cpp index be18c0348388..fa31ce155332 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.cpp @@ -25,7 +25,7 @@ #if ENABLED(COCOA_LEVELING_MENU) -#if BOTH(HAS_BED_PROBE, BLTOUCH) +#if ALL(HAS_BED_PROBE, BLTOUCH) #include "../../../../feature/bltouch.h" #endif diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/main_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/main_menu.cpp index ee299a7f64d6..2f231278f2d8 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/main_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/main_menu.cpp @@ -57,7 +57,7 @@ void MainMenu::onRedraw(draw_mode_t what) { .font(Theme::font_medium) .tag( 2).button(MOVE_XYZ_POS, GET_TEXT_F(MSG_XYZ_MOVE)) .tag( 3).button(TEMPERATURE_POS, GET_TEXT_F(MSG_TEMPERATURE)) - .enabled(BOTH(HAS_LEVELING, HAS_BED_PROBE)) + .enabled(ALL(HAS_LEVELING, HAS_BED_PROBE)) .tag( 4).button(ZPROBE_ZOFFSET_POS, GET_TEXT_F(MSG_ZPROBE_ZOFFSET)) .tag( 5).button(MOVE_E_POS, GET_TEXT_F(MSG_E_MOVE)) .tag( 6).button(SPEED_POS, GET_TEXT_F(MSG_PRINT_SPEED)) @@ -79,7 +79,7 @@ bool MainMenu::onTouchEnd(uint8_t tag) { case 1: SaveSettingsDialogBox::promptToSaveSettings(); break; case 2: GOTO_SCREEN(MoveXYZScreen); break; case 3: GOTO_SCREEN(TemperatureScreen); break; - #if BOTH(HAS_LEVELING, HAS_BED_PROBE) + #if ALL(HAS_LEVELING, HAS_BED_PROBE) case 4: GOTO_SCREEN(ZOffsetScreen); break; #endif case 5: GOTO_SCREEN(MoveEScreen); break; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_extui.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_extui.cpp index 86f470ee1915..dc49a77ff8a3 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_extui.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_extui.cpp @@ -117,9 +117,12 @@ namespace ExtUI { ConfirmUserRequestAlertBox::hide(); } - #if HAS_LEVELING && HAS_MESH + #if HAS_LEVELING void onLevelingStart() {} void onLevelingDone() {} + #endif + + #if HAS_MESH void onMeshUpdate(const int8_t x, const int8_t y, const_float_t val) { BedMeshViewScreen::onMeshUpdate(x, y, val); } void onMeshUpdate(const int8_t x, const int8_t y, const ExtUI::probe_state_t state) { BedMeshViewScreen::onMeshUpdate(x, y, state); } #endif diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp index 662753a1547c..a796c8edcf5f 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/commands.cpp @@ -1208,7 +1208,7 @@ void CLCD::default_display_orientation() { + ENABLED(TOUCH_UI_INVERTED) * 1 ); cmd.execute(); - #elif EITHER(TOUCH_UI_PORTRAIT, TOUCH_UI_MIRRORED) + #elif ANY(TOUCH_UI_PORTRAIT, TOUCH_UI_MIRRORED) #error "PORTRAIT or MIRRORED orientation not supported on the FT800." #elif ENABLED(TOUCH_UI_INVERTED) mem_write_32(REG::ROTATE, 1); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h index 6b2dc9eb4498..a9f77a518ba0 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h @@ -305,14 +305,11 @@ #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. - #define IF_ENABLED TERN_ #define IF_DISABLED(O,A) _TERN(_ENA_1(O),,A) #define ANY(V...) !DISABLED(V) - #define NONE(V...) DISABLED(V) - #define ALL(V...) ENABLED(V) - #define BOTH(V1,V2) ALL(V1,V2) - #define EITHER(V1,V2) ANY(V1,V2) + #define NONE DISABLED + #define ALL ENABLED // Remove compiler warning on an unused variable #ifndef UNUSED diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/cyrillic_char_set.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/cyrillic_char_set.cpp index 1c193ade4be1..2faa1c72e688 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/cyrillic_char_set.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/cyrillic_char_set.cpp @@ -58,11 +58,11 @@ cyrillic_fm.stride = 20; cyrillic_fm.width = 40; cyrillic_fm.height = 49; - LOOP_L_N(i, 127) + for (uint8_t i = 0; i < 127; ++i) cyrillic_fm.char_widths[i] = 0; // For cyrillic characters, copy the character widths from the widths tables - LOOP_L_N(i, NUM_ELEMENTS(cyrillic_font_widths)) { + for (uint8_t i = 0; i < NUM_ELEMENTS(cyrillic_font_widths); ++i) { cyrillic_fm.char_widths[i] = cyrillic_font_widths[i]; } CLCD::mem_write_bulk(addr, &cyrillic_fm, 148); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_size_t.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_size_t.cpp index 0e251f7bb1c7..b229154e82a4 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_size_t.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/font_size_t.cpp @@ -21,7 +21,7 @@ #include "../ftdi_extended.h" -#if BOTH(FTDI_EXTENDED, TOUCH_UI_USE_UTF8) +#if ALL(FTDI_EXTENDED, TOUCH_UI_USE_UTF8) namespace FTDI { // Returns the height of a standard FTDI romfont diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/standard_char_set.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/standard_char_set.cpp index d12bf9711907..5171ee508aff 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/standard_char_set.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/standard_char_set.cpp @@ -21,7 +21,7 @@ #include "../ftdi_extended.h" -#if BOTH(FTDI_EXTENDED, TOUCH_UI_USE_UTF8) +#if ALL(FTDI_EXTENDED, TOUCH_UI_USE_UTF8) constexpr static uint8_t std_font = 31; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp index 6f189155f5de..d7f4d31bdc12 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp @@ -21,7 +21,7 @@ #include "../ftdi_extended.h" -#if BOTH(FTDI_EXTENDED, TOUCH_UI_USE_UTF8) +#if ALL(FTDI_EXTENDED, TOUCH_UI_USE_UTF8) using namespace FTDI; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set.cpp index 4fb2f8fdbf24..02a39cd01c87 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/western_char_set.cpp @@ -342,11 +342,11 @@ alt_fm.stride = 19; alt_fm.width = 38; alt_fm.height = 49; - LOOP_L_N(i, 127) + for (uint8_t i = 0; i < 127; ++i) alt_fm.char_widths[i] = 0; // For special characters, copy the character widths from the char tables - LOOP_L_N(i, NUM_ELEMENTS(char_recipe)) { + for (uint8_t i = 0; i < NUM_ELEMENTS(char_recipe); ++i) { uint8_t std_char, alt_char, alt_data; get_char_data(i, std_char, alt_char, alt_data); if (std_char == 0) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.cpp index 43e5c333651a..698f0d47b794 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.cpp @@ -76,7 +76,7 @@ void AboutScreen::onRedraw(draw_mode_t) { #endif , OPT_CENTER, font_xlarge ); - #if BOTH(TOUCH_UI_DEVELOPER_MENU, FTDI_DEVELOPER_MENU) + #if ALL(TOUCH_UI_DEVELOPER_MENU, FTDI_DEVELOPER_MENU) cmd.tag(3); #endif draw_text_box(cmd, FW_VERS_POS, @@ -91,7 +91,7 @@ void AboutScreen::onRedraw(draw_mode_t) { draw_text_box(cmd, LICENSE_POS, GET_TEXT_F(MSG_LICENSE), OPT_CENTER, font_tiny); cmd.font(font_medium); - #if BOTH(PRINTCOUNTER, FTDI_STATISTICS_SCREEN) + #if ALL(PRINTCOUNTER, FTDI_STATISTICS_SCREEN) cmd.colors(normal_btn) .tag(2).button(STATS_POS, GET_TEXT_F(MSG_INFO_STATS_MENU)); #endif @@ -102,10 +102,10 @@ void AboutScreen::onRedraw(draw_mode_t) { bool AboutScreen::onTouchEnd(uint8_t tag) { switch (tag) { case 1: GOTO_PREVIOUS(); break; - #if BOTH(PRINTCOUNTER, FTDI_STATISTICS_SCREEN) + #if ALL(PRINTCOUNTER, FTDI_STATISTICS_SCREEN) case 2: GOTO_SCREEN(StatisticsScreen); break; #endif - #if BOTH(TOUCH_UI_DEVELOPER_MENU, FTDI_DEVELOPER_MENU) + #if ALL(TOUCH_UI_DEVELOPER_MENU, FTDI_DEVELOPER_MENU) case 3: GOTO_SCREEN(DeveloperMenu); break; #endif default: return false; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/advanced_settings_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/advanced_settings_menu.cpp index 8753b44e709b..4745ff99dc55 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/advanced_settings_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/advanced_settings_menu.cpp @@ -37,7 +37,7 @@ void AdvancedSettingsMenu::onRedraw(draw_mode_t what) { } #if ENABLED(TOUCH_UI_PORTRAIT) - #if EITHER(HAS_MULTI_HOTEND, SENSORLESS_HOMING) + #if ANY(HAS_MULTI_HOTEND, SENSORLESS_HOMING) #define GRID_ROWS 9 #else #define GRID_ROWS 8 @@ -58,7 +58,7 @@ void AdvancedSettingsMenu::onRedraw(draw_mode_t what) { #define BACKLASH_POS BTN_POS(2,7), BTN_SIZE(1,1) #define OFFSETS_POS BTN_POS(1,8), BTN_SIZE(1,1) #define TMC_HOMING_THRS_POS BTN_POS(2,8), BTN_SIZE(1,1) - #if EITHER(HAS_MULTI_HOTEND, SENSORLESS_HOMING) + #if ANY(HAS_MULTI_HOTEND, SENSORLESS_HOMING) #define BACK_POS BTN_POS(1,9), BTN_SIZE(2,1) #else #define BACK_POS BTN_POS(1,8), BTN_SIZE(2,1) @@ -99,7 +99,7 @@ void AdvancedSettingsMenu::onRedraw(draw_mode_t what) { .tag(14).button(TMC_HOMING_THRS_POS, GET_TEXT_F(MSG_TMC_HOMING_THRS)) .enabled(ENABLED(HAS_MULTI_HOTEND)) .tag(4) .button(OFFSETS_POS, GET_TEXT_F(MSG_OFFSETS_MENU)) - .enabled(EITHER(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR)) + .enabled(ANY(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR)) .tag(11).button(FILAMENT_POS, GET_TEXT_F(MSG_FILAMENT)) .tag(12).button(ENDSTOPS_POS, GET_TEXT_F(MSG_LCD_ENDSTOPS)) .tag(15).button(DISPLAY_POS, GET_TEXT_F(MSG_DISPLAY_MENU)) @@ -133,7 +133,7 @@ bool AdvancedSettingsMenu::onTouchEnd(uint8_t tag) { #endif case 9: GOTO_SCREEN(InterfaceSettingsScreen); LockScreen::check_passcode(); break; case 10: GOTO_SCREEN(RestoreFailsafeDialogBox); LockScreen::check_passcode(); break; - #if EITHER(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR) + #if ANY(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR) case 11: GOTO_SCREEN(FilamentMenu); break; #endif case 12: GOTO_SCREEN(EndstopStatesScreen); break; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_edit_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_edit_screen.cpp index 37eb29a99d11..ab6d8a89024d 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_edit_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_edit_screen.cpp @@ -95,7 +95,7 @@ void BedMeshEditScreen::setHighlightedValue(float value) { } void BedMeshEditScreen::moveToHighlightedValue() { - if (ExtUI::getMeshValid()) { + if (ExtUI::getLevelingIsValid()) { ExtUI::setLevelingActive(true); ExtUI::setSoftEndstopState(false); ExtUI::moveToMeshPoint(mydata.highlight, gaugeThickness + mydata.zAdjustment); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_view_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_view_screen.cpp index 7b4195ff5ce3..86eab54d85b1 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_view_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_view_screen.cpp @@ -125,7 +125,7 @@ void BedMeshViewScreen::onMeshUpdate(const int8_t x, const int8_t y, const ExtUI mydata.count = 0; break; case ExtUI::G29_FINISH: - if (mydata.count == GRID_MAX_POINTS && ExtUI::getMeshValid()) + if (mydata.count == GRID_MAX_POINTS && ExtUI::getLevelingIsValid()) mydata.message = GET_TEXT_F(MSG_BED_MAPPING_DONE); else mydata.message = GET_TEXT_F(MSG_BED_MAPPING_INCOMPLETE); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/endstop_state_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/endstop_state_screen.cpp index eae83d070d48..1d81649444e2 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/endstop_state_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/endstop_state_screen.cpp @@ -89,7 +89,7 @@ void EndstopStatesScreen::onRedraw(draw_mode_t) { #else PIN_DISABLED(1, 4, GET_TEXT_F(MSG_RUNOUT_1), FIL_RUNOUT) #endif - #if BOTH(HAS_MULTI_EXTRUDER, FILAMENT_RUNOUT_SENSOR) && PIN_EXISTS(FIL_RUNOUT2) + #if ALL(HAS_MULTI_EXTRUDER, FILAMENT_RUNOUT_SENSOR) && PIN_EXISTS(FIL_RUNOUT2) PIN_ENABLED (3, 4, GET_TEXT_F(MSG_RUNOUT_2), FIL_RUNOUT2, FIL_RUNOUT2_STATE) #else PIN_DISABLED(3, 4, GET_TEXT_F(MSG_RUNOUT_2), FIL_RUNOUT2) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.cpp index 2fb9d18498c0..47540b0f5519 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/leveling_menu.cpp @@ -25,7 +25,7 @@ #ifdef FTDI_LEVELING_MENU -#if BOTH(HAS_BED_PROBE,BLTOUCH) +#if ALL(HAS_BED_PROBE,BLTOUCH) #include "../../../../feature/bltouch.h" #endif @@ -81,7 +81,7 @@ void LevelingMenu::onRedraw(draw_mode_t what) { .text(BLTOUCH_TITLE_POS, GET_TEXT_F(MSG_BLTOUCH)) #endif .font(font_medium).colors(normal_btn) - .enabled(EITHER(Z_STEPPER_AUTO_ALIGN,MECHANICAL_GANTRY_CALIBRATION)) + .enabled(ANY(Z_STEPPER_AUTO_ALIGN,MECHANICAL_GANTRY_CALIBRATION)) .tag(2).button(LEVEL_AXIS_POS, GET_TEXT_F(MSG_LEVEL_X_AXIS)) .enabled(ENABLED(HAS_BED_PROBE)) .tag(3).button(PROBE_BED_POS, GET_TEXT_F(MSG_PROBE_BED)) @@ -103,7 +103,7 @@ void LevelingMenu::onRedraw(draw_mode_t what) { bool LevelingMenu::onTouchEnd(uint8_t tag) { switch (tag) { case 1: GOTO_PREVIOUS(); break; - #if EITHER(Z_STEPPER_AUTO_ALIGN,MECHANICAL_GANTRY_CALIBRATION) + #if ANY(Z_STEPPER_AUTO_ALIGN,MECHANICAL_GANTRY_CALIBRATION) case 2: SpinnerDialogBox::enqueueAndWait(F("G34")); break; #endif #if HAS_BED_PROBE diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/move_axis_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/move_axis_screen.cpp index c08935f3bcda..95fe023cdaf6 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/move_axis_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/move_axis_screen.cpp @@ -37,7 +37,7 @@ void BaseMoveAxisScreen::onEntry() { // ourselves. The relative distances are reset to zero whenever this // screen is entered. - LOOP_L_N(i, ExtUI::extruderCount) { + for (uint8_t i = 0; i < ExtUI::extruderCount; ++i) { mydata.e_rel[i] = 0; } BaseNumericAdjustmentScreen::onEntry(); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/screens.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/screens.h index e2df29cb833d..c200931eec51 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/screens.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/screens.h @@ -74,7 +74,7 @@ enum { #if ENABLED(CASE_LIGHT_ENABLE) CASE_LIGHT_SCREEN_CACHE, #endif - #if EITHER(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR) + #if ANY(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR) FILAMENT_MENU_CACHE, #endif #if ENABLED(LIN_ADVANCE) @@ -192,7 +192,7 @@ enum { #include "case_light_screen.h" #endif -#if EITHER(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR) +#if ANY(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR) #include "filament_menu.h" #endif diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/tune_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/tune_menu.cpp index 0370c4417478..259f6d5b89ef 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/tune_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/tune_menu.cpp @@ -74,11 +74,11 @@ void TuneMenu::onRedraw(draw_mode_t what) { .tag(2).button(TEMPERATURE_POS, GET_TEXT_F(MSG_TEMPERATURE)) .enabled(!sdOrHostPrinting || sdOrHostPaused) .tag(3).button(FIL_CHANGE_POS, GET_TEXT_F(MSG_FILAMENTCHANGE)) - .enabled(EITHER(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR)) + .enabled(ANY(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR)) .tag(9).button(FILAMENT_POS, GET_TEXT_F(MSG_FILAMENT)) #if ENABLED(BABYSTEPPING) && HAS_MULTI_HOTEND .tag(4).button(NUDGE_NOZ_POS, GET_TEXT_F(MSG_NUDGE_NOZZLE)) - #elif BOTH(HAS_LEVELING, HAS_BED_PROBE) + #elif ALL(HAS_LEVELING, HAS_BED_PROBE) .tag(4).button(NUDGE_NOZ_POS, GET_TEXT_F(MSG_ZPROBE_ZOFFSET)) #endif .tag(5).button(SPEED_POS, GET_TEXT_F(MSG_PRINT_SPEED)) @@ -105,7 +105,7 @@ bool TuneMenu::onTouchEnd(uint8_t tag) { case 4: #if ENABLED(BABYSTEPPING) && HAS_MULTI_HOTEND GOTO_SCREEN(NudgeNozzleScreen); - #elif BOTH(HAS_LEVELING, HAS_BED_PROBE) + #elif ALL(HAS_LEVELING, HAS_BED_PROBE) GOTO_SCREEN(ZOffsetScreen); #endif break; @@ -117,7 +117,7 @@ bool TuneMenu::onTouchEnd(uint8_t tag) { current_screen.forget(); PUSH_SCREEN(StatusScreen); break; - #if EITHER(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR) + #if ANY(LIN_ADVANCE, FILAMENT_RUNOUT_SENSOR) case 9: GOTO_SCREEN(FilamentMenu); break; #endif #if ENABLED(CASE_LIGHT_ENABLE) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/colors.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/colors.h index 70c2be4ec23f..0e145e39f208 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/colors.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/colors.h @@ -37,7 +37,7 @@ namespace Theme { #else // Use linear accent colors - #if EITHER(TOUCH_UI_ROYAL_THEME, TOUCH_UI_FROZEN_THEME) + #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; @@ -88,7 +88,7 @@ namespace Theme { constexpr uint32_t bed_mesh_lines_rgb = 0xFFFFFF; constexpr uint32_t bed_mesh_shadow_rgb = 0x444444; - #elif EITHER(TOUCH_UI_COCOA_THEME, TOUCH_UI_FROZEN_THEME) + #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; diff --git a/Marlin/src/lcd/extui/ia_creality/ia_creality_extui.cpp b/Marlin/src/lcd/extui/ia_creality/ia_creality_extui.cpp index 4bfdfc6ec3c9..2d6c2aa96e68 100644 --- a/Marlin/src/lcd/extui/ia_creality/ia_creality_extui.cpp +++ b/Marlin/src/lcd/extui/ia_creality/ia_creality_extui.cpp @@ -311,7 +311,7 @@ void onSettingsStored(const bool success) { void onSettingsLoaded(const bool success) { #if HAS_MESH - if (ExtUI::getMeshValid()) { + if (ExtUI::getLevelingIsValid()) { uint8_t abl_probe_index = 0; for (uint8_t outer = 0; outer < GRID_MAX_POINTS_Y; outer++) for (uint8_t inner = 0; inner < GRID_MAX_POINTS_X; inner++) { @@ -371,7 +371,7 @@ void onLevelingStart() {} void onLevelingDone() { #if HAS_MESH - if (ExtUI::getMeshValid()) { + if (ExtUI::getLevelingIsValid()) { uint8_t abl_probe_index = 0; for (uint8_t outer = 0; outer < GRID_MAX_POINTS_Y; outer++) for (uint8_t inner = 0; inner < GRID_MAX_POINTS_X; inner++) { diff --git a/Marlin/src/lcd/extui/ia_creality/ia_creality_rts.cpp b/Marlin/src/lcd/extui/ia_creality/ia_creality_rts.cpp index 37ba539ff102..3eac438bb1b7 100644 --- a/Marlin/src/lcd/extui/ia_creality/ia_creality_rts.cpp +++ b/Marlin/src/lcd/extui/ia_creality/ia_creality_rts.cpp @@ -1043,7 +1043,7 @@ void RTS::handleData() { #if HAS_MESH sendData(getLevelingActive() ? 3 : 2, AutoLevelIcon); - if (ExtUI::getMeshValid()) { + if (ExtUI::getLevelingIsValid()) { uint8_t abl_probe_index = 0; for (uint8_t outer = 0; outer < GRID_MAX_POINTS_Y; outer++) for (uint8_t inner = 0; inner < GRID_MAX_POINTS_X; inner++) { diff --git a/Marlin/src/lcd/extui/malyan/malyan.cpp b/Marlin/src/lcd/extui/malyan/malyan.cpp index 1c051f4504cd..d1c2387682ff 100644 --- a/Marlin/src/lcd/extui/malyan/malyan.cpp +++ b/Marlin/src/lcd/extui/malyan/malyan.cpp @@ -79,7 +79,7 @@ void write_to_lcd(FSTR_P const fmsg) { char encoded_message[MAX_CURLY_COMMAND]; uint8_t message_length = _MIN(strlen_P(pmsg), sizeof(encoded_message)); - LOOP_L_N(i, message_length) + for (uint8_t i = 0; i < message_length; ++i) encoded_message[i] = pgm_read_byte(&pmsg[i]) | 0x80; LCD_SERIAL.Print::write(encoded_message, message_length); @@ -89,7 +89,7 @@ void write_to_lcd(const char * const cmsg) { char encoded_message[MAX_CURLY_COMMAND]; const uint8_t message_length = _MIN(strlen(cmsg), sizeof(encoded_message)); - LOOP_L_N(i, message_length) + for (uint8_t i = 0; i < message_length; ++i) encoded_message[i] = cmsg[i] | 0x80; LCD_SERIAL.Print::write(encoded_message, message_length); diff --git a/Marlin/src/lcd/extui/malyan/malyan_extui.cpp b/Marlin/src/lcd/extui/malyan/malyan_extui.cpp index 042062b7c9b7..f82f1f06a7de 100644 --- a/Marlin/src/lcd/extui/malyan/malyan_extui.cpp +++ b/Marlin/src/lcd/extui/malyan/malyan_extui.cpp @@ -150,11 +150,14 @@ namespace ExtUI { void onSettingsStored(const bool) {} void onSettingsLoaded(const bool) {} - #if HAS_MESH + #if HAS_LEVELING void onLevelingStart() {} void onLevelingDone() {} - void onMeshUpdate(const int8_t xpos, const int8_t ypos, const_float_t zval) {} - void onMeshUpdate(const int8_t xpos, const int8_t ypos, const ExtUI::probe_state_t state) {} + #endif + + #if HAS_MESH + void onMeshUpdate(const int8_t, const int8_t, const_float_t) {} + void onMeshUpdate(const int8_t, const int8_t, const ExtUI::probe_state_t) {} #endif #if ENABLED(POWER_LOSS_RECOVERY) diff --git a/Marlin/src/lcd/extui/mks_ui/draw_auto_level_offset_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_auto_level_offset_settings.cpp index fd14585e7028..5a5d457b080b 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_auto_level_offset_settings.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_auto_level_offset_settings.cpp @@ -22,7 +22,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if BOTH(HAS_TFT_LVGL_UI, HAS_BED_PROBE) +#if ALL(HAS_TFT_LVGL_UI, HAS_BED_PROBE) #include "draw_ui.h" #include diff --git a/Marlin/src/lcd/extui/mks_ui/draw_cloud_bind.cpp b/Marlin/src/lcd/extui/mks_ui/draw_cloud_bind.cpp index 1dae0ebe2251..0798db1cc9f4 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_cloud_bind.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_cloud_bind.cpp @@ -22,7 +22,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if BOTH(HAS_TFT_LVGL_UI, MKS_WIFI_MODULE) +#if ALL(HAS_TFT_LVGL_UI, MKS_WIFI_MODULE) #include "lv_conf.h" #include "draw_ui.h" diff --git a/Marlin/src/lcd/extui/mks_ui/draw_jerk_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_jerk_settings.cpp index a070cae15f4e..5b22103e8f2d 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_jerk_settings.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_jerk_settings.cpp @@ -22,7 +22,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if BOTH(HAS_TFT_LVGL_UI, HAS_CLASSIC_JERK) +#if ALL(HAS_TFT_LVGL_UI, HAS_CLASSIC_JERK) #include "draw_ui.h" #include diff --git a/Marlin/src/lcd/extui/mks_ui/draw_media_select.cpp b/Marlin/src/lcd/extui/mks_ui/draw_media_select.cpp index 81c82dc02dfa..085a008acde9 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_media_select.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_media_select.cpp @@ -21,7 +21,7 @@ */ #include "../../../inc/MarlinConfigPre.h" -#if BOTH(HAS_TFT_LVGL_UI, MULTI_VOLUME) +#if ALL(HAS_TFT_LVGL_UI, MULTI_VOLUME) #include "draw_ui.h" #include diff --git a/Marlin/src/lcd/extui/mks_ui/draw_pause_message.cpp b/Marlin/src/lcd/extui/mks_ui/draw_pause_message.cpp index e5f6a5963a6b..b753a578012b 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_pause_message.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_pause_message.cpp @@ -22,7 +22,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if BOTH(HAS_TFT_LVGL_UI, ADVANCED_PAUSE_FEATURE) +#if ALL(HAS_TFT_LVGL_UI, ADVANCED_PAUSE_FEATURE) #include "draw_ui.h" #include diff --git a/Marlin/src/lcd/extui/mks_ui/draw_tmc_current_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_tmc_current_settings.cpp index 9ec8f1501a0b..b243c88705a3 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_tmc_current_settings.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_tmc_current_settings.cpp @@ -22,7 +22,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if BOTH(HAS_TFT_LVGL_UI, HAS_TRINAMIC_CONFIG) +#if ALL(HAS_TFT_LVGL_UI, HAS_TRINAMIC_CONFIG) #include "draw_ui.h" #include diff --git a/Marlin/src/lcd/extui/mks_ui/draw_tmc_step_mode_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_tmc_step_mode_settings.cpp index 990cdda7e63b..d09c823b5979 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_tmc_step_mode_settings.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_tmc_step_mode_settings.cpp @@ -22,7 +22,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if BOTH(HAS_TFT_LVGL_UI, HAS_STEALTHCHOP) +#if ALL(HAS_TFT_LVGL_UI, HAS_STEALTHCHOP) #include "draw_ui.h" #include diff --git a/Marlin/src/lcd/extui/mks_ui/draw_touch_calibration.cpp b/Marlin/src/lcd/extui/mks_ui/draw_touch_calibration.cpp index a9a25db11822..74902a30ddc8 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_touch_calibration.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_touch_calibration.cpp @@ -22,7 +22,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if BOTH(HAS_TFT_LVGL_UI, TOUCH_SCREEN_CALIBRATION) +#if ALL(HAS_TFT_LVGL_UI, TOUCH_SCREEN_CALIBRATION) #include "draw_ui.h" #include "draw_touch_calibration.h" diff --git a/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp b/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp index 102109a1363e..708ad77fca8c 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp @@ -1377,7 +1377,7 @@ void LV_TASK_HANDLER() { if (TERN1(USE_SPI_DMA_TC, !get_lcd_dma_lock())) lv_task_handler(); - #if BOTH(MKS_TEST, HAS_MEDIA) + #if ALL(MKS_TEST, HAS_MEDIA) if (mks_test_flag == 0x1E) mks_hardware_test(); #endif diff --git a/Marlin/src/lcd/extui/mks_ui/draw_z_offset_wizard.cpp b/Marlin/src/lcd/extui/mks_ui/draw_z_offset_wizard.cpp index 69e547a68ccb..9d16c9dff261 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_z_offset_wizard.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_z_offset_wizard.cpp @@ -22,7 +22,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if BOTH(HAS_TFT_LVGL_UI, PROBE_OFFSET_WIZARD) +#if ALL(HAS_TFT_LVGL_UI, PROBE_OFFSET_WIZARD) #include "draw_ui.h" #include diff --git a/Marlin/src/lcd/extui/mks_ui/irq_overrid.cpp b/Marlin/src/lcd/extui/mks_ui/irq_overrid.cpp index aca1db0039ba..b2615ac24b24 100644 --- a/Marlin/src/lcd/extui/mks_ui/irq_overrid.cpp +++ b/Marlin/src/lcd/extui/mks_ui/irq_overrid.cpp @@ -23,7 +23,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if BOTH(HAS_TFT_LVGL_UI, MKS_WIFI_MODULE) +#if ALL(HAS_TFT_LVGL_UI, MKS_WIFI_MODULE) #include "tft_lvgl_configuration.h" diff --git a/Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp b/Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp index 657629049673..53f31b1c4042 100644 --- a/Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp +++ b/Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp @@ -681,7 +681,7 @@ void disp_assets_update_progress(FSTR_P const fmsg) { #endif } -#if BOTH(MKS_TEST, HAS_MEDIA) +#if ALL(MKS_TEST, HAS_MEDIA) uint8_t mks_test_flag = 0; const char *MKSTestPath = "MKS_TEST"; void mks_test_get() { diff --git a/Marlin/src/lcd/extui/mks_ui/mks_hardware.h b/Marlin/src/lcd/extui/mks_ui/mks_hardware.h index 6a2574e3b0ce..f73f4e645910 100644 --- a/Marlin/src/lcd/extui/mks_ui/mks_hardware.h +++ b/Marlin/src/lcd/extui/mks_ui/mks_hardware.h @@ -26,7 +26,7 @@ #include // Functions for MKS_TEST -#if BOTH(MKS_TEST, HAS_MEDIA) +#if ALL(MKS_TEST, HAS_MEDIA) void mks_hardware_test(); void mks_test_get(); void mks_gpio_test(); diff --git a/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp b/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp index 6e39c9a36e8f..7c0ec802c306 100644 --- a/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp +++ b/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp @@ -379,7 +379,7 @@ uint32_t Pic_Info_Write(uint8_t *P_name, uint32_t P_size) { static void dosName2LongName(const char dosName[11], char *longName) { uint8_t j = 0; - LOOP_L_N(i, 11) { + for (uint8_t i = 0; i < 11; ++i) { if (i == 8) longName[j++] = '.'; if (dosName[i] == '\0' || dosName[i] == ' ') continue; longName[j++] = dosName[i]; diff --git a/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp b/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp index 71f4166ca89e..5dfb02bfaca4 100644 --- a/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp +++ b/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp @@ -51,7 +51,7 @@ XPT2046 touch; #include "../../../module/servo.h" #endif -#if EITHER(PROBE_TARE, HAS_Z_SERVO_PROBE) +#if ANY(PROBE_TARE, HAS_Z_SERVO_PROBE) #include "../../../module/probe.h" #endif @@ -249,7 +249,7 @@ void tft_lvgl_init() { if (ready) lv_draw_ready_print(); - #if BOTH(MKS_TEST, HAS_MEDIA) + #if ALL(MKS_TEST, HAS_MEDIA) if (mks_test_flag == 0x1E) mks_gpio_test(); #endif } diff --git a/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32.cpp b/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32.cpp index 9d7f5e20325f..cb5b7f0b68c8 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32.cpp +++ b/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32.cpp @@ -25,7 +25,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if BOTH(HAS_TFT_LVGL_UI, MKS_WIFI_MODULE) +#if ALL(HAS_TFT_LVGL_UI, MKS_WIFI_MODULE) #include "tft_lvgl_configuration.h" diff --git a/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32F1.cpp b/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32F1.cpp index 654fca6cb334..92fd139dfa5d 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32F1.cpp +++ b/Marlin/src/lcd/extui/mks_ui/wifiSerial_STM32F1.cpp @@ -23,7 +23,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if BOTH(HAS_TFT_LVGL_UI, MKS_WIFI_MODULE) +#if ALL(HAS_TFT_LVGL_UI, MKS_WIFI_MODULE) #include "tft_lvgl_configuration.h" diff --git a/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp b/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp index bf399f70aad4..f3967a3ec38a 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp +++ b/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp @@ -22,7 +22,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if BOTH(HAS_TFT_LVGL_UI, MKS_WIFI_MODULE) +#if ALL(HAS_TFT_LVGL_UI, MKS_WIFI_MODULE) #include "draw_ui.h" #include "wifi_module.h" diff --git a/Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp b/Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp index 398d35fdc3f3..2d4d19e7a23e 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp +++ b/Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp @@ -22,7 +22,7 @@ #include "../../../inc/MarlinConfigPre.h" -#if BOTH(HAS_TFT_LVGL_UI, MKS_WIFI_MODULE) +#if ALL(HAS_TFT_LVGL_UI, MKS_WIFI_MODULE) #include "draw_ui.h" #include "wifi_module.h" @@ -101,15 +101,17 @@ const char *resultMessages[] = { "slip data" }; -// A note on baud rates. -// The ESP8266 supports 921600, 460800, 230400, 115200, 74880 and some lower baud rates. -// 921600b is not reliable because even though it sometimes succeeds in connecting, we get a bad response during uploading after a few blocks. -// Probably our UART ISR cannot receive bytes fast enough, perhaps because of the latency of the system tick ISR. -// 460800b doesn't always manage to connect, but if it does then uploading appears to be reliable. -// 230400b always manages to connect. +/** + * Baud Rate Notes: + * The ESP8266 supports 921600, 460800, 230400, 115200, 74880 and some lower baud rates. + * 921600b is not reliable because even though it sometimes succeeds in connecting, we get a bad response during uploading after a few blocks. + * Probably our UART ISR cannot receive bytes fast enough, perhaps because of the latency of the system tick ISR. + * 460800b doesn't always manage to connect, but if it does then uploading appears to be reliable. + * 230400b always manages to connect. + */ static const uint32_t uploadBaudRates[] = { 460800, 230400, 115200, 74880 }; -signed char IsReady() { +signed char isReady() { return esp_upload.state == upload_idle; } @@ -170,15 +172,17 @@ void putData(uint32_t val, unsigned byteCnt, uint8_t *buf, int ofst) { } } -// Read a byte optionally performing SLIP decoding. The return values are: -// -// 2 - an escaped byte was read successfully -// 1 - a non-escaped byte was read successfully -// 0 - no data was available -// -1 - the value 0xC0 was encountered (shouldn't happen) -// -2 - a SLIP escape byte was found but the following byte wasn't available -// -3 - a SLIP escape byte was followed by an invalid byte -int ReadByte(uint8_t *data, signed char slipDecode) { +/** + * Read a byte optionally performing SLIP decoding. The return values are: + * + * 2 - an escaped byte was read successfully + * 1 - a non-escaped byte was read successfully + * 0 - no data was available + * -1 - the value 0xC0 was encountered (shouldn't happen) + * -2 - a SLIP escape byte was found but the following byte wasn't available + * -3 - a SLIP escape byte was followed by an invalid byte + */ +int readByte(uint8_t *data, signed char slipDecode) { if (uploadPort_available() == 0) return 0; // At least one byte is available @@ -206,31 +210,33 @@ void _writePacketRaw(const uint8_t *buf, size_t len) { } // Write a byte to the serial port optionally SLIP encoding. Return the number of bytes actually written. -void WriteByteRaw(uint8_t b) { +void writeByteRaw(uint8_t b) { uploadPort_write((const uint8_t *)&b, 1); } // Write a byte to the serial port optionally SLIP encoding. Return the number of bytes actually written. -void WriteByteSlip(const uint8_t b) { +void writeByteSlip(const uint8_t b) { if (b == 0xC0) { - WriteByteRaw(0xDB); - WriteByteRaw(0xDC); + writeByteRaw(0xDB); + writeByteRaw(0xDC); } else if (b == 0xDB) { - WriteByteRaw(0xDB); - WriteByteRaw(0xDD); + writeByteRaw(0xDB); + writeByteRaw(0xDD); } else uploadPort_write((const uint8_t *)&b, 1); } -// Wait for a data packet to be returned. If the body of the packet is -// non-zero length, return an allocated buffer indirectly containing the -// data and return the data length. Note that if the pointer for returning -// the data buffer is nullptr, the response is expected to be two bytes of zero. -// -// If an error occurs, return a negative value. Otherwise, return the number -// of bytes in the response (or zero if the response was not the standard "two bytes of zero"). +/** + * Wait for a data packet to be returned. If the body of the packet is + * non-zero length, return an allocated buffer indirectly containing the + * data and return the data length. Note that if the pointer for returning + * the data buffer is nullptr, the response is expected to be two bytes of zero. + * + * If an error occurs, return a negative value. Otherwise, return the number + * of bytes in the response (or zero if the response was not the standard "two bytes of zero"). + */ EspUploadResult readPacket(uint8_t op, uint32_t *valp, size_t *bodyLen, uint32_t msTimeout) { typedef enum { begin = 0, @@ -292,7 +298,7 @@ EspUploadResult readPacket(uint8_t op, uint32_t *valp, size_t *bodyLen, uint32_t case body: { // reading the response body int rslt; // retrieve a byte with SLIP decoding - rslt = ReadByte(&c, 1); + rslt = readByte(&c, 1); if (rslt != 1 && rslt != 2) { // some error occurred stat = (rslt == 0 || rslt == -2) ? slipData : slipFrame; @@ -370,19 +376,19 @@ void _writePacket(const uint8_t *data, size_t len) { // 0xC0 and 0xDB replaced by the two-byte sequences {0xDB, 0xDC} and {0xDB, 0xDD} respectively. void writePacket(const uint8_t *hdr, size_t hdrLen, const uint8_t *data, size_t dataLen) { - WriteByteRaw(0xC0); // send the packet start character + writeByteRaw(0xC0); // send the packet start character _writePacket(hdr, hdrLen); // send the header _writePacket(data, dataLen); // send the data block - WriteByteRaw(0xC0); // send the packet end character + writeByteRaw(0xC0); // send the packet end character } // Send a packet to the serial port while performing SLIP framing. The packet data comprises a header and an optional data block. // This is like writePacket except that it does a fast block write for both the header and the main data with no SLIP encoding. Used to send sync commands. void writePacketRaw(const uint8_t *hdr, size_t hdrLen, const uint8_t *data, size_t dataLen) { - WriteByteRaw(0xC0); // send the packet start character + writeByteRaw(0xC0); // send the packet start character _writePacketRaw(hdr, hdrLen); // send the header _writePacketRaw(data, dataLen); // send the data block in raw mode - WriteByteRaw(0xC0); // send the packet end character + writeByteRaw(0xC0); // send the packet end character } // Send a command to the attached device together with the supplied data, if any. @@ -418,7 +424,7 @@ EspUploadResult doCommand(uint8_t op, const uint8_t *data, size_t dataLen, uint3 // Send a synchronising packet to the serial port in an attempt to induce // the ESP8266 to auto-baud lock on the baud rate. -EspUploadResult Sync(uint16_t timeout) { +EspUploadResult sync(uint16_t timeout) { uint8_t buf[36]; EspUploadResult stat; int i; @@ -553,7 +559,7 @@ void upload_spin() { case connecting: if ((getWifiTickDiff(esp_upload.lastAttemptTime, getWifiTick()) >= connectAttemptInterval) && (getWifiTickDiff(esp_upload.lastResetTime, getWifiTick()) >= 500)) { - EspUploadResult res = Sync(5000); + EspUploadResult res = sync(5000); esp_upload.lastAttemptTime = getWifiTick(); if (res == success) esp_upload.state = erasing; @@ -622,7 +628,7 @@ void upload_spin() { } // Try to upload the given file at the given address -void SendUpdateFile(const char *file, uint32_t address) { +void sendUpdateFile(const char *file, uint32_t address) { const char * const fname = card.diveToFile(false, update_curDir, ESP_FIRMWARE_FILE); if (!update_file.open(update_curDir, fname, O_READ)) return; @@ -640,7 +646,7 @@ void SendUpdateFile(const char *file, uint32_t address) { static const uint32_t FirmwareAddress = 0x00000000, WebFilesAddress = 0x00100000; -void ResetWiFiForUpload(int begin_or_end) { +void resetWiFiForUpload(int begin_or_end) { //#if 0 uint32_t start = getWifiTick(); @@ -660,12 +666,12 @@ void ResetWiFiForUpload(int begin_or_end) { int32_t wifi_upload(int type) { esp_upload.retriesPerBaudRate = 9; - ResetWiFiForUpload(0); + resetWiFiForUpload(0); switch (type) { - case 0: SendUpdateFile(ESP_FIRMWARE_FILE, FirmwareAddress); break; - case 1: SendUpdateFile(ESP_WEB_FIRMWARE_FILE, FirmwareAddress); break; - case 2: SendUpdateFile(ESP_WEB_FILE, WebFilesAddress); break; + case 0: sendUpdateFile(ESP_FIRMWARE_FILE, FirmwareAddress); break; + case 1: sendUpdateFile(ESP_WEB_FIRMWARE_FILE, FirmwareAddress); break; + case 2: sendUpdateFile(ESP_WEB_FILE, WebFilesAddress); break; default: return -1; } @@ -674,7 +680,7 @@ int32_t wifi_upload(int type) { hal.watchdog_refresh(); } - ResetWiFiForUpload(1); + resetWiFiForUpload(1); return esp_upload.uploadResult == success ? 0 : -1; } diff --git a/Marlin/src/lcd/extui/nextion/nextion_extui.cpp b/Marlin/src/lcd/extui/nextion/nextion_extui.cpp index da3e344a35aa..b1e1997a3ac6 100644 --- a/Marlin/src/lcd/extui/nextion/nextion_extui.cpp +++ b/Marlin/src/lcd/extui/nextion/nextion_extui.cpp @@ -89,10 +89,12 @@ namespace ExtUI { // whether successful or not. } - #if HAS_MESH + #if HAS_LEVELING void onLevelingStart() {} void onLevelingDone() {} + #endif + #if HAS_MESH void onMeshUpdate(const int8_t xpos, const int8_t ypos, const float zval) { // Called when any mesh points are updated } diff --git a/Marlin/src/lcd/extui/nextion/nextion_tft.cpp b/Marlin/src/lcd/extui/nextion/nextion_tft.cpp index 15c384808f89..e5e3a74be2c5 100644 --- a/Marlin/src/lcd/extui/nextion/nextion_tft.cpp +++ b/Marlin/src/lcd/extui/nextion/nextion_tft.cpp @@ -294,7 +294,7 @@ void NextionTFT::panelInfo(uint8_t req) { break; case 26: // TMC Hybrid Threshold Speed - #if 0 && BOTH(HAS_TRINAMIC_CONFIG, HYBRID_THRESHOLD) + #if 0 && ALL(HAS_TRINAMIC_CONFIG, HYBRID_THRESHOLD) #define SEND_TRINAMIC_THRS(A, B) SEND_VALasTXT(A, getAxisPWMthrs(B)) #else #define SEND_TRINAMIC_THRS(A, B) SEND_NA(A) @@ -463,7 +463,7 @@ void NextionTFT::panelInfo(uint8_t req) { #else #define SEND_PID_INFO_0(A, B) SEND_NA(A) #endif - #if BOTH(PIDTEMP, HAS_MULTI_EXTRUDER) + #if ALL(PIDTEMP, HAS_MULTI_EXTRUDER) #define SEND_PID_INFO_1(A, B) SEND_VALasTXT(A, getPID_K##B(E1)) #else #define SEND_PID_INFO_1(A, B) SEND_NA(A) diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index fb77be94afb0..7f216107289a 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -919,7 +919,7 @@ namespace ExtUI { bool getLevelingActive() { return planner.leveling_active; } void setLevelingActive(const bool state) { set_bed_leveling_enabled(state); } - bool getMeshValid() { return leveling_is_valid(); } + bool getLevelingIsValid() { return leveling_is_valid(); } #if HAS_MESH @@ -933,7 +933,7 @@ namespace ExtUI { } void moveToMeshPoint(const xy_uint8_t &pos, const_float_t z) { - #if EITHER(MESH_BED_LEVELING, AUTO_BED_LEVELING_UBL) + #if ANY(MESH_BED_LEVELING, AUTO_BED_LEVELING_UBL) REMEMBER(fr, feedrate_mm_s); const float x_target = MESH_MIN_X + pos.x * (MESH_X_DIST), y_target = MESH_MIN_Y + pos.y * (MESH_Y_DIST); diff --git a/Marlin/src/lcd/extui/ui_api.h b/Marlin/src/lcd/extui/ui_api.h index 209635ea0944..125c85ffa275 100644 --- a/Marlin/src/lcd/extui/ui_api.h +++ b/Marlin/src/lcd/extui/ui_api.h @@ -172,14 +172,14 @@ namespace ExtUI { #if HAS_LEVELING bool getLevelingActive(); void setLevelingActive(const bool); - bool getMeshValid(); + bool getLevelingIsValid(); + void onLevelingStart(); + void onLevelingDone(); #if HAS_MESH bed_mesh_t& getMeshArray(); float getMeshPoint(const xy_uint8_t &pos); void setMeshPoint(const xy_uint8_t &pos, const_float_t zval); void moveToMeshPoint(const xy_uint8_t &pos, const_float_t z); - void onLevelingStart(); - void onLevelingDone(); void onMeshUpdate(const int8_t xpos, const int8_t ypos, const_float_t zval); inline void onMeshUpdate(const xy_int8_t &pos, const_float_t zval) { onMeshUpdate(pos.x, pos.y, zval); } diff --git a/Marlin/src/lcd/language/language_de.h b/Marlin/src/lcd/language/language_de.h index 2e75c2668b90..3f17ca1453bb 100644 --- a/Marlin/src/lcd/language/language_de.h +++ b/Marlin/src/lcd/language/language_de.h @@ -54,8 +54,6 @@ namespace Language_de { LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Software-Endstopp"); LSTR MSG_MAIN_MENU = _UxGT("HauptmenΓΌ"); LSTR MSG_ADVANCED_SETTINGS = _UxGT("Erw. Einstellungen"); - LSTR MSG_TOOLBAR_SETUP = _UxGT("Toolbar Einstellung"); - LSTR MSG_OPTION_DISABLED = _UxGT("Option Deaktiviert"); LSTR MSG_CONFIGURATION = _UxGT("Konfiguration"); LSTR MSG_RUN_AUTO_FILES = _UxGT("Autostart"); LSTR MSG_DISABLE_STEPPERS = _UxGT("Motoren deaktivieren"); // M84 :: Max length 19 characters diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index f74e24e93a1c..1876b26038d8 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -69,8 +69,6 @@ namespace Language_en { LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Soft Endstops"); LSTR MSG_MAIN_MENU = _UxGT("Main Menu"); LSTR MSG_ADVANCED_SETTINGS = _UxGT("Advanced Settings"); - LSTR MSG_TOOLBAR_SETUP = _UxGT("Toolbar Setup"); - LSTR MSG_OPTION_DISABLED = _UxGT("Option Disabled"); LSTR MSG_CONFIGURATION = _UxGT("Configuration"); LSTR MSG_RUN_AUTO_FILES = _UxGT("Run Auto Files"); LSTR MSG_DISABLE_STEPPERS = _UxGT("Disable Steppers"); diff --git a/Marlin/src/lcd/language/language_it.h b/Marlin/src/lcd/language/language_it.h index a6b48b0d0a1b..d9a9340762df 100644 --- a/Marlin/src/lcd/language/language_it.h +++ b/Marlin/src/lcd/language/language_it.h @@ -64,8 +64,6 @@ namespace Language_it { LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Finecorsa Soft"); LSTR MSG_MAIN_MENU = _UxGT("Menu principale"); LSTR MSG_ADVANCED_SETTINGS = _UxGT("Impostaz. avanzate"); - LSTR MSG_TOOLBAR_SETUP = _UxGT("Cnf barra strumenti"); - LSTR MSG_OPTION_DISABLED = _UxGT("Opzione disab."); LSTR MSG_CONFIGURATION = _UxGT("Configurazione"); LSTR MSG_RUN_AUTO_FILES = _UxGT("Esegui files auto"); LSTR MSG_DISABLE_STEPPERS = _UxGT("Disabilita Motori"); @@ -778,7 +776,7 @@ namespace Language_it { // #if LCD_HEIGHT >= 4 LSTR MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_3_LINE("Premi per", "riprendere", "la stampa")); - LSTR MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parcheggiando...")); + LSTR MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Sto parcheggiando...")); LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_3_LINE("Attendere avvio", "del cambio", "di filamento")); LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Inserisci il", "filamento e premi", "per continuare")); LSTR MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_2_LINE("Premi per", "riscaldare ugello")); diff --git a/Marlin/src/lcd/language/language_ru.h b/Marlin/src/lcd/language/language_ru.h index 25f62173f350..a8db7852ccf3 100644 --- a/Marlin/src/lcd/language/language_ru.h +++ b/Marlin/src/lcd/language/language_ru.h @@ -91,42 +91,49 @@ namespace Language_ru { LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("БмСщСния ΠΏΡ€ΠΈΠΌΠ΅Π½Π΅Π½Ρ‹"); LSTR MSG_SELECT_ORIGIN = _UxGT("Π’Ρ‹Π±Π΅Ρ€ΠΈΡ‚Π΅ ноль"); #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 - LSTR MSG_LAST_VALUE_SP = _UxGT("ПослСднСС Π·Π½Π°Ρ‡. "); + LSTR MSG_LAST_VALUE_SP = _UxGT("ПослСднСС Π·Π½Π°Ρ‡Π΅Π½ΠΈΠ΅ "); #else LSTR MSG_LAST_VALUE_SP = _UxGT("ПослСд. Π·Π½Π°Ρ‡. "); #endif #if HAS_PREHEAT - LSTR MSG_PREHEAT_1 = _UxGT("ΠŸΡ€Π΅Π΄Π½Π°Π³Ρ€Π΅Π² ") PREHEAT_1_LABEL; - LSTR MSG_PREHEAT_1_H = _UxGT("ΠΠ°Π³Ρ€Π΅Ρ‚ΡŒ ~ ") PREHEAT_1_LABEL; - LSTR MSG_PREHEAT_1_END = _UxGT("ΠΠ°Π³Ρ€Π΅Ρ‚ΡŒ сопло ") PREHEAT_1_LABEL; - LSTR MSG_PREHEAT_1_END_E = _UxGT("ΠΠ°Π³Ρ€Π΅Ρ‚ΡŒ сопло ~") PREHEAT_1_LABEL; - LSTR MSG_PREHEAT_1_ALL = _UxGT("ΠΠ°Π³Ρ€Π΅Ρ‚ΡŒ всё ") PREHEAT_1_LABEL; - LSTR MSG_PREHEAT_1_BEDONLY = _UxGT("ΠΠ°Π³Ρ€Π΅Ρ‚ΡŒ стол ") PREHEAT_1_LABEL; - LSTR MSG_PREHEAT_1_SETTINGS = _UxGT("ΠŸΡ€Π°Π²ΠΊΠ° ΠΏΡ€Π΅Π΄Π½. ") PREHEAT_1_LABEL; - - LSTR MSG_PREHEAT_M = _UxGT("ΠŸΡ€Π΅Π΄Π½Π°Π³Ρ€Π΅Π² $"); + LSTR MSG_PREHEAT_1 = _UxGT("НагрСв ") PREHEAT_1_LABEL; + LSTR MSG_PREHEAT_1_H = _UxGT("ΠΠ°Π³Ρ€Π΅Ρ‚ΡŒ ~ ") PREHEAT_1_LABEL " ~"; + LSTR MSG_PREHEAT_1_END = _UxGT("ΠΠ°Π³Ρ€Π΅Ρ‚ΡŒ сопло ") PREHEAT_1_LABEL _UxGT(" сопло"); + LSTR MSG_PREHEAT_1_END_E = _UxGT("ΠΠ°Π³Ρ€Π΅Ρ‚ΡŒ сопло ~") PREHEAT_1_LABEL _UxGT(" сопло ~");; + LSTR MSG_PREHEAT_1_ALL = _UxGT("ΠΠ°Π³Ρ€Π΅Ρ‚ΡŒ всё ") PREHEAT_1_LABEL _UxGT(" всё"); + LSTR MSG_PREHEAT_1_BEDONLY = _UxGT("ΠΠ°Π³Ρ€Π΅Ρ‚ΡŒ стол ") PREHEAT_1_LABEL _UxGT(" стол"); + LSTR MSG_PREHEAT_1_SETTINGS = _UxGT("ΠŸΡ€Π°Π²ΠΊΠ° ΠΏΡ€Π΅Π΄Π½. ") PREHEAT_1_LABEL _UxGT(" наст."); + #ifdef PREHEAT_2_LABEL + LSTR MSG_PREHEAT_2 = _UxGT("НагрСв ") PREHEAT_2_LABEL; + LSTR MSG_PREHEAT_2_SETTINGS = _UxGT("НагрСв ") PREHEAT_2_LABEL _UxGT(" настр."); + #endif + #ifdef PREHEAT_3_LABEL + LSTR MSG_PREHEAT_3 = _UxGT("НагрСв ") PREHEAT_3_LABEL; + LSTR MSG_PREHEAT_3_SETTINGS = _UxGT("НагрСв ") PREHEAT_3_LABEL _UxGT(" настр."); + #endif + LSTR MSG_PREHEAT_M = _UxGT("НагрСв $"); LSTR MSG_PREHEAT_M_H = _UxGT("ΠΠ°Π³Ρ€Π΅Ρ‚ΡŒ ~ $"); LSTR MSG_PREHEAT_M_END = _UxGT("ΠΠ°Π³Ρ€Π΅Ρ‚ΡŒ сопло $"); LSTR MSG_PREHEAT_M_END_E = _UxGT("ΠΠ°Π³Ρ€Π΅Ρ‚ΡŒ сопло ~ $"); LSTR MSG_PREHEAT_M_ALL = _UxGT("ΠΠ°Π³Ρ€Π΅Ρ‚ΡŒ всё $"); LSTR MSG_PREHEAT_M_BEDONLY = _UxGT("ΠΠ°Π³Ρ€Π΅Ρ‚ΡŒ стол $"); - LSTR MSG_PREHEAT_M_SETTINGS = _UxGT("ΠŸΡ€Π°Π²ΠΊΠ° ΠΏΡ€Π΅Π΄Π½Π°Π³. $"); + LSTR MSG_PREHEAT_M_SETTINGS = _UxGT("Настр.Π½Π°Π³Ρ€Π΅Π²Π° $"); #endif LSTR MSG_PREHEAT_CUSTOM = _UxGT("НагрСв Π‘Π²ΠΎΠΉ"); LSTR MSG_COOLDOWN = _UxGT("ΠžΡ…Π»Π°ΠΆΠ΄Π΅Π½ΠΈΠ΅"); LSTR MSG_CUTTER_FREQUENCY = _UxGT("Частота"); LSTR MSG_LASER_MENU = _UxGT("Π£ΠΏΡ€Π°Π²Π»Π΅Π½ΠΈΠ΅ Π»Π°Π·Π΅Ρ€ΠΎΠΌ"); #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 - LSTR MSG_SPINDLE_MENU = _UxGT("Π£ΠΏΡ€Π°Π²Π»Π΅Π½ΠΈΠ΅ шпиндСлСм"); + LSTR MSG_SPINDLE_MENU = _UxGT("Π£ΠΏΡ€Π°Π²Π»Π΅Π½.шпиндСлСм"); LSTR MSG_LASER_TOGGLE = _UxGT("ΠŸΠ΅Ρ€Π΅ΠΊΠ»ΡŽΡ‡ΠΈΡ‚ΡŒ Π»Π°Π·Π΅Ρ€"); - LSTR MSG_SPINDLE_TOGGLE = _UxGT("ΠŸΠ΅Ρ€Π΅ΠΊΠ»ΡŽΡ‡.шпиндСль"); + LSTR MSG_SPINDLE_TOGGLE = _UxGT("ΠŸΠ΅Ρ€Π΅ΠΊΠ»ΡŽΡ‡. шпиндСль"); LSTR MSG_SPINDLE_POWER = _UxGT("ΠœΠΎΡ‰Π½ΠΎΡΡ‚ΡŒ шпиндСля"); LSTR MSG_LASER_POWER = _UxGT("ΠœΠΎΡ‰Π½ΠΎΡΡ‚ΡŒ Π»Π°Π·Π΅Ρ€Π°"); LSTR MSG_LASER_PULSE_MS = _UxGT("ВСстовый ΠΈΠΌΠΏΡƒΠ»ΡŒΡ мс"); LSTR MSG_LASER_EVAC_TOGGLE = _UxGT("ΠŸΠ΅Ρ€Π΅ΠΊΠ»ΡŽΡ‡ΠΈΡ‚ΡŒ ΠΎΠ±Π΄ΡƒΠ²"); LSTR MSG_SPINDLE_EVAC_TOGGLE = _UxGT("ΠŸΠ΅Ρ€Π΅ΠΊΠ»ΡŽΡ‡ΠΈΡ‚ΡŒ Π²Π°ΠΊΡƒΡƒΠΌ"); #else - LSTR MSG_SPINDLE_MENU = _UxGT("Π£ΠΏΡ€Π°Π²Π»Π΅Π½ΠΈΠ΅ шпинд."); + LSTR MSG_SPINDLE_MENU = _UxGT("Π£ΠΏΡ€Π°Π²Π». шпинд."); LSTR MSG_LASER_TOGGLE = _UxGT("ΠŸΠ΅Ρ€Π΅ΠΊΠ»ΡŽΡ‡.Π»Π°Π·Π΅Ρ€"); LSTR MSG_SPINDLE_TOGGLE = _UxGT("ΠŸΠ΅Ρ€Π΅ΠΊΠ»ΡŽΡ‡.шпинд"); LSTR MSG_SPINDLE_POWER = _UxGT("ΠœΠΎΡ‰Π½.шпиндСля"); @@ -339,6 +346,11 @@ namespace Language_ru { LSTR MSG_MOVE_1MM = _UxGT("Π”Π²ΠΈΠΆΠ΅Π½ΠΈΠ΅ 1ΠΌΠΌ"); LSTR MSG_MOVE_10MM = _UxGT("Π”Π²ΠΈΠΆΠ΅Π½ΠΈΠ΅ 10ΠΌΠΌ"); LSTR MSG_MOVE_100MM = _UxGT("Π”Π²ΠΈΠΆΠ΅Π½ΠΈΠ΅ 100mm"); + LSTR MSG_MOVE_0001IN = _UxGT("Π”Π²ΠΈΠΆΠ΅Π½ΠΈΠ΅ 0.001in"); + LSTR MSG_MOVE_001IN = _UxGT("Π”Π²ΠΈΠΆΠ΅Π½ΠΈΠ΅ 0.01in"); + LSTR MSG_MOVE_01IN = _UxGT("Π”Π²ΠΈΠΆΠ΅Π½ΠΈΠ΅ 0.1in"); + LSTR MSG_MOVE_05IN = _UxGT("Π”Π²ΠΈΠΆΠ΅Π½ΠΈΠ΅ 0.5in"); + LSTR MSG_MOVE_1IN = _UxGT("Π”Π²ΠΈΠΆΠ΅Π½ΠΈΠ΅ 1.0in"); LSTR MSG_SPEED = _UxGT("Π‘ΠΊΠΎΡ€ΠΎΡΡ‚ΡŒ"); LSTR MSG_MESH_Z_OFFSET = _UxGT("Z стола"); LSTR MSG_NOZZLE = _UxGT("Π‘ΠΎΠΏΠ»ΠΎ, ") LCD_STR_DEGREE _UxGT("C"); @@ -454,10 +466,11 @@ namespace Language_ru { LSTR MSG_ERR_EEPROM_CRC = _UxGT("Π‘Π±ΠΎΠΉ EEPROM: CRC"); LSTR MSG_ERR_EEPROM_SIZE = _UxGT("Π‘Π±ΠΎΠΉ EEPROM: Ρ€Π°Π·ΠΌΠ΅Ρ€"); LSTR MSG_ERR_EEPROM_VERSION = _UxGT("Π‘Π±ΠΎΠΉ EEPROM: вСрсия"); + LSTR MSG_ERR_EEPROM_CORRUPT = _UxGT("Π‘Π±ΠΎΠΉ EEPROM: Π΄Π°Π½Π½Ρ‹Π΅"); LSTR MSG_SETTINGS_STORED = _UxGT("ΠŸΠ°Ρ€Π°ΠΌΠ΅Ρ‚Ρ€Ρ‹ сохранСны"); LSTR MSG_MEDIA_UPDATE = _UxGT("ОбновлСниС ΠΏΡ€ΠΎΡˆΠΈΠ²ΠΊΠΈ"); LSTR MSG_RESET_PRINTER = _UxGT("Бброс ΠΏΡ€ΠΈΠ½Ρ‚Π΅Ρ€Π°"); - LSTR MSG_REFRESH = LCD_STR_REFRESH _UxGT(" ΠžΠ±Π½ΠΎΠ²ΠΈΡ‚ΡŒ"); + LSTR MSG_REFRESH = LCD_STR_REFRESH _UxGT(" ΠžΠ±Π½ΠΎΠ²ΠΈΡ‚ΡŒ"); LSTR MSG_INFO_SCREEN = _UxGT("Π“Π»Π°Π²Π½Ρ‹ΠΉ экран"); LSTR MSG_PREPARE = _UxGT("ΠŸΠΎΠ΄Π³ΠΎΡ‚ΠΎΠ²ΠΈΡ‚ΡŒ"); LSTR MSG_TUNE = _UxGT("ΠΠ°ΡΡ‚Ρ€ΠΎΠΈΡ‚ΡŒ"); @@ -777,93 +790,261 @@ namespace Language_ru { LSTR MSG_BAD_PAGE_SPEED = _UxGT("ΠŸΠ»ΠΎΡ…Π°Ρ скор.стран."); #endif - LSTR MSG_EDIT_PASSWORD = _UxGT("Π Π΅Π΄Π°ΠΊΡ‚ΠΈΡ€ΠΎΠ²Π°Ρ‚ΡŒ ΠΏΠ°Ρ€ΠΎΠ»ΡŒ"); - LSTR MSG_LOGIN_REQUIRED = _UxGT("НуТСн Π»ΠΎΠ³ΠΈΠ½"); - LSTR MSG_PASSWORD_SETTINGS = _UxGT("Настройки пароля"); - LSTR MSG_ENTER_DIGIT = _UxGT("Π’Π²Π΅Π΄ΠΈΡ‚Π΅ Ρ†ΠΈΡ„Ρ€Ρƒ"); - LSTR MSG_CHANGE_PASSWORD = _UxGT("Π‘ΠΌΠ΅Π½ΠΈΡ‚Π΅ ΠΏΠ°Ρ€ΠΎΠ»ΡŒ"); - LSTR MSG_REMOVE_PASSWORD = _UxGT("Π£Π΄Π°Π»ΠΈΡ‚ΡŒ ΠΏΠ°Ρ€ΠΎΠ»ΡŒ"); - LSTR MSG_PASSWORD_SET = _UxGT("ΠŸΠ°Ρ€ΠΎΠ»ΡŒ это "); - LSTR MSG_START_OVER = _UxGT("Π‘Ρ‚Π°Ρ€Ρ‚ Ρ‡Π΅Ρ€Π΅Π·"); + LSTR MSG_EDIT_PASSWORD = _UxGT("Π Π΅Π΄Π°ΠΊΡ‚ΠΈΡ€ΠΎΠ²Π°Ρ‚ΡŒ ΠΏΠ°Ρ€ΠΎΠ»ΡŒ"); + LSTR MSG_LOGIN_REQUIRED = _UxGT("НуТСн Π»ΠΎΠ³ΠΈΠ½"); + LSTR MSG_PASSWORD_SETTINGS = _UxGT("Настройки пароля"); + LSTR MSG_ENTER_DIGIT = _UxGT("Π’Π²Π΅Π΄ΠΈΡ‚Π΅ Ρ†ΠΈΡ„Ρ€Ρƒ"); + LSTR MSG_CHANGE_PASSWORD = _UxGT("Π‘ΠΌΠ΅Π½ΠΈΡ‚Π΅ ΠΏΠ°Ρ€ΠΎΠ»ΡŒ"); + LSTR MSG_REMOVE_PASSWORD = _UxGT("Π£Π΄Π°Π»ΠΈΡ‚ΡŒ ΠΏΠ°Ρ€ΠΎΠ»ΡŒ"); + LSTR MSG_PASSWORD_SET = _UxGT("ΠŸΠ°Ρ€ΠΎΠ»ΡŒ это "); + LSTR MSG_START_OVER = _UxGT("Π‘Ρ‚Π°Ρ€Ρ‚ Ρ‡Π΅Ρ€Π΅Π·"); #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 - LSTR MSG_REMINDER_SAVE_SETTINGS = _UxGT("НС Π·Π°Π±ΡƒΠ΄ΡŒ ΡΠΎΡ…Ρ€Π°Π½ΠΈΡ‚ΡŒ!"); + LSTR MSG_REMINDER_SAVE_SETTINGS = _UxGT("НС Π·Π°Π±ΡƒΠ΄ΡŒ ΡΠΎΡ…Ρ€Π°Π½ΠΈΡ‚ΡŒ!"); #else - LSTR MSG_REMINDER_SAVE_SETTINGS = _UxGT("НС Π·Π°Π±ΡƒΠ΄ΡŒ ΡΠΎΡ…Ρ€Π°Π½ΠΈΡ‚ΡŒ"); + LSTR MSG_REMINDER_SAVE_SETTINGS = _UxGT("НС Π·Π°Π±ΡƒΠ΄ΡŒ ΡΠΎΡ…Ρ€Π°Π½ΠΈΡ‚ΡŒ"); #endif - LSTR MSG_PASSWORD_REMOVED = _UxGT("ΠŸΠ°Ρ€ΠΎΠ»ΡŒ ΡƒΠ΄Π°Π»Ρ‘Π½"); + LSTR MSG_PASSWORD_REMOVED = _UxGT("ΠŸΠ°Ρ€ΠΎΠ»ΡŒ ΡƒΠ΄Π°Π»Ρ‘Π½"); // // Filament Change screens show up to 3 lines on a 4-line display // ...or up to 2 lines on a 3-line display // - LSTR MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("ΠŸΠ°Ρ€ΠΊΠΎΠ²ΠΊΠ°...")); + LSTR MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("ΠŸΠ°Ρ€ΠΊΠΎΠ²ΠΊΠ°...")); #if LCD_HEIGHT >= 4 - LSTR MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_3_LINE("НаТмитС ΠΊΠ½ΠΎΠΏΠΊΡƒ", "для продолТСния", "ΠΏΠ΅Ρ‡Π°Ρ‚ΠΈ")); - LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_2_LINE("ΠžΠΆΠΈΠ΄Π°ΠΉΡ‚Π΅ Π½Π°Ρ‡Π°Π»Π°", "смСны Ρ„ΠΈΠ»Π°ΠΌΠ΅Π½Ρ‚Π°")); - LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Π’ΡΡ‚Π°Π²ΡŒΡ‚Π΅ Ρ„ΠΈΠ»Π°ΠΌΠ΅Π½Ρ‚", "ΠΈ Π½Π°ΠΆΠΌΠΈΡ‚Π΅ ΠΊΠ½ΠΎΠΏΠΊΡƒ", "для продолТСния")); - LSTR MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_3_LINE("НаТмитС ΠΊΠ½ΠΎΠΏΠΊΡƒ", "для Π½Π°Π³Ρ€Π΅Π²Π°", "сопла...")); - LSTR MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_2_LINE("НагрСв сопла", "Π–Π΄ΠΈΡ‚Π΅...")); - LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_3_LINE("ΠžΠΆΠΈΠ΄Π°ΠΉΡ‚Π΅", "Π²Ρ‹Π³Ρ€ΡƒΠ·ΠΊΠΈ", "Ρ„ΠΈΠ»Π°ΠΌΠ΅Π½Ρ‚Π°")); - LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_3_LINE("ΠžΠΆΠΈΠ΄Π°ΠΉΡ‚Π΅", "Π·Π°Π³Ρ€ΡƒΠ·ΠΊΠΈ", "Ρ„ΠΈΠ»Π°ΠΌΠ΅Π½Ρ‚Π°")); - LSTR MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_3_LINE("ΠžΠΆΠΈΠ΄Π°ΠΉΡ‚Π΅", "экструзии", "Ρ„ΠΈΠ»Π°ΠΌΠ΅Π½Ρ‚Π°")); - LSTR MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_3_LINE("НаТмитС ΠΊΠ½ΠΎΠΏΠΊΡƒ", "для Π·Π°Π²Π΅Ρ€ΡˆΠ΅Π½ΠΈΡ", "прочистки Ρ„ΠΈΠ»Π°ΠΌΠ΅Π½Ρ‚Π°")); - LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_3_LINE("ΠžΠΆΠΈΠ΄Π°ΠΉΡ‚Π΅", "возобновлСния", "ΠΏΠ΅Ρ‡Π°Ρ‚ΠΈ")); - #else - LSTR MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("ΠŸΡ€ΠΎΠ΄ΠΎΠ»ΠΆΠΈΡ‚ΡŒ ΠΏΠ΅Ρ‡Π°Ρ‚ΡŒ")); - LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("ΠžΠΆΠΈΠ΄Π°ΠΉΡ‚Π΅...")); - LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Π’ΡΡ‚Π°Π²ΡŒ ΠΈ Π½Π°ΠΆΠΌΠΈ")); - LSTR MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("ΠΠ°Π³Ρ€Π΅Ρ‚ΡŒ сопло")); - LSTR MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("НагрСв...")); - LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("Π’Ρ‹Π³Ρ€ΡƒΠ·ΠΊΠ°...")); - LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("Π—Π°Π³Ρ€ΡƒΠ·ΠΊΠ°...")); - LSTR MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_1_LINE("ΠŸΡ€ΠΎΡ‡ΠΈΡΡ‚ΠΊΠ°...")); - LSTR MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("Π—Π°Π²Π΅Ρ€ΡˆΠΈΡ‚ΡŒ прочистку")); - LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Π’ΠΎΠ·ΠΎΠ±Π½ΠΎΠ²Π»Π΅Π½ΠΈΠ΅...")); - #endif - - LSTR MSG_TMC_DRIVERS = _UxGT("Π”Ρ€Π°ΠΉΠ²Π΅Ρ€Π° TMC"); - LSTR MSG_TMC_CURRENT = _UxGT("Π’ΠΎΠΊ Π΄Π²ΠΈΠ³Π°Ρ‚Π΅Π»Π΅ΠΉ"); - LSTR MSG_TMC_HYBRID_THRS = _UxGT("Π“ΠΈΠ±Ρ€ΠΈΠ΄Π½Ρ‹ΠΉ Ρ€Π΅ΠΆΠΈΠΌ"); - LSTR MSG_TMC_HOMING_THRS = _UxGT("Π§ΡƒΠ²ΡΡ‚Π²ΠΈΡ‚Π΅Π»ΡŒΠ½ΠΎΡΡ‚ΡŒ"); - LSTR MSG_TMC_STEPPING_MODE = _UxGT("Π Π΅ΠΆΠΈΠΌ Π΄Ρ€Π°ΠΉΠ²Π΅Ρ€Π°"); - LSTR MSG_TMC_STEALTH_ENABLED = _UxGT("Π’ΠΈΡ…ΠΈΠΉ Ρ€Π΅ΠΆΠΈΠΌ Π²ΠΊΠ»"); - - LSTR MSG_SERVICE_RESET = _UxGT("Бброс"); - LSTR MSG_SERVICE_IN = _UxGT(" Π²:"); - LSTR MSG_BACKLASH = _UxGT("Π›ΡŽΡ„Ρ‚"); - LSTR MSG_BACKLASH_CORRECTION = _UxGT("Π˜ΡΠΏΡ€Π°Π²Π»Π΅Π½ΠΈΠ΅"); - LSTR MSG_BACKLASH_SMOOTHING = _UxGT("Π‘Π³Π»Π°ΠΆΠΈΠ²Π°Π½ΠΈΠ΅"); - - LSTR MSG_LEVEL_X_AXIS = _UxGT("Π’Ρ‹Ρ€ΠΎΠ²Π½ΡΡ‚ΡŒ ось X"); - LSTR MSG_AUTO_CALIBRATE = _UxGT("Автокалибровка"); - LSTR MSG_HEATER_TIMEOUT = _UxGT("Π’Π°ΠΉΠΌΠ°ΡƒΡ‚ Π½Π°Π³Ρ€Π΅Π²Π°"); - LSTR MSG_REHEAT = _UxGT("Π’ΠΎΠ·ΠΎΠ±Π½ΠΎΠ²ΠΈΡ‚ΡŒ Π½Π°Π³Ρ€Π΅Π²"); - LSTR MSG_REHEATING = _UxGT("НагрСв..."); - - LSTR MSG_PROBE_WIZARD = _UxGT("ΠœΠ°ΡΡ‚Π΅Ρ€ Z-Π·ΠΎΠ½Π΄Π°"); - #if LCD_WIDTH > 21 || HAS_DWIN_E3V2 - LSTR MSG_PROBE_WIZARD_PROBING = _UxGT("Π—ΠΎΠ½Π΄ΠΈΡ€ΠΎΠ². ΠΊΠΎΠ½Ρ‚Ρ€. Ρ‚ΠΎΡ‡ΠΊΠΈ Z"); - LSTR MSG_PROBE_WIZARD_MOVING = _UxGT("Π”Π²ΠΈΠΆΠ΅Π½ΠΈΠ΅ ΠΊ Ρ‚ΠΎΡ‡ΠΊΠ΅ Π·ΠΎΠ½Π΄ΠΈΡ€ΠΎΠ²."); - #else - LSTR MSG_PROBE_WIZARD_PROBING = _UxGT("Π—ΠΎΠ½Π΄ΠΈΡ€.ΠΊΠΎΠ½Ρ‚Ρ€.Ρ‚ΠΎΡ‡ΠΊΠΈ Z"); - LSTR MSG_PROBE_WIZARD_MOVING = _UxGT("Π”Π²ΠΈΠΆ. ΠΊ Ρ‚ΠΎΡ‡ΠΊΠ΅ Π·ΠΎΠ½Π΄ΠΈΡ€."); - #endif - - LSTR MSG_SOUND = _UxGT("Π—Π²ΡƒΠΊ"); - - LSTR MSG_TOP_LEFT = _UxGT("Π’Π΅Ρ€Ρ…Π½ΠΈΠΉ Π»Π΅Π²Ρ‹ΠΉ"); - LSTR MSG_BOTTOM_LEFT = _UxGT("НиТний Π»Π΅Π²Ρ‹ΠΉ"); - LSTR MSG_TOP_RIGHT = _UxGT("Π’Π΅Ρ€Ρ…Π½ΠΈΠΉ ΠΏΡ€Π°Π²Ρ‹ΠΉ"); - LSTR MSG_BOTTOM_RIGHT = _UxGT("НиТний ΠΏΡ€Π°Π²Ρ‹ΠΉ"); - LSTR MSG_CALIBRATION_COMPLETED = _UxGT("ΠšΠ°Π»ΠΈΠ±Ρ€ΠΎΠ²ΠΊΠ° ΡƒΡΠΏΠ΅ΡˆΠ½Π°"); - LSTR MSG_CALIBRATION_FAILED = _UxGT("Ошибка ΠΊΠ°Π»ΠΈΠ±Ρ€ΠΎΠ²ΠΊΠΈ"); - - LSTR MSG_DRIVER_BACKWARD = _UxGT(" Π΄Ρ€Π°ΠΉΠ²Π΅Ρ€ Π½Π°ΠΎΠ±ΠΎΡ€ΠΎΡ‚"); - - LSTR MSG_SD_CARD = _UxGT("SD ΠšΠ°Ρ€Ρ‚Π°"); - LSTR MSG_USB_DISK = _UxGT("USB Диск"); - - LSTR MSG_SHORT_DAY = _UxGT("Π΄"); // One character only - LSTR MSG_SHORT_HOUR = _UxGT("Ρ‡"); // One character only - LSTR MSG_SHORT_MINUTE = _UxGT("ΠΌ"); // One character only + LSTR MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_3_LINE("НаТмитС ΠΊΠ½ΠΎΠΏΠΊΡƒ", "для продолТСния", "ΠΏΠ΅Ρ‡Π°Ρ‚ΠΈ")); + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_2_LINE("ΠžΠΆΠΈΠ΄Π°ΠΉΡ‚Π΅ Π½Π°Ρ‡Π°Π»Π°", "смСны Ρ„ΠΈΠ»Π°ΠΌΠ΅Π½Ρ‚Π°")); + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_3_LINE("Π’ΡΡ‚Π°Π²ΡŒΡ‚Π΅ Ρ„ΠΈΠ»Π°ΠΌΠ΅Π½Ρ‚", "ΠΈ Π½Π°ΠΆΠΌΠΈΡ‚Π΅ ΠΊΠ½ΠΎΠΏΠΊΡƒ", "для продолТСния")); + LSTR MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_3_LINE("НаТмитС ΠΊΠ½ΠΎΠΏΠΊΡƒ", "для Π½Π°Π³Ρ€Π΅Π²Π°", "сопла...")); + LSTR MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_2_LINE("НагрСв сопла", "Π–Π΄ΠΈΡ‚Π΅...")); + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_3_LINE("ΠžΠΆΠΈΠ΄Π°ΠΉΡ‚Π΅", "Π²Ρ‹Π³Ρ€ΡƒΠ·ΠΊΠΈ", "Ρ„ΠΈΠ»Π°ΠΌΠ΅Π½Ρ‚Π°")); + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_3_LINE("ΠžΠΆΠΈΠ΄Π°ΠΉΡ‚Π΅", "Π·Π°Π³Ρ€ΡƒΠ·ΠΊΠΈ", "Ρ„ΠΈΠ»Π°ΠΌΠ΅Π½Ρ‚Π°")); + LSTR MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_3_LINE("ΠžΠΆΠΈΠ΄Π°ΠΉΡ‚Π΅", "экструзии", "Ρ„ΠΈΠ»Π°ΠΌΠ΅Π½Ρ‚Π°")); + LSTR MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_3_LINE("НаТмитС ΠΊΠ½ΠΎΠΏΠΊΡƒ", "для Π·Π°Π²Π΅Ρ€ΡˆΠ΅Π½ΠΈΡ", "прочистки Ρ„ΠΈΠ»Π°ΠΌΠ΅Π½Ρ‚Π°")); + LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_3_LINE("ΠžΠΆΠΈΠ΄Π°ΠΉΡ‚Π΅", "возобновлСния", "ΠΏΠ΅Ρ‡Π°Ρ‚ΠΈ")); + #else + LSTR MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("ΠŸΡ€ΠΎΠ΄ΠΎΠ»ΠΆΠΈΡ‚ΡŒ ΠΏΠ΅Ρ‡Π°Ρ‚ΡŒ")); + LSTR MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_1_LINE("ΠžΠΆΠΈΠ΄Π°ΠΉΡ‚Π΅...")); + LSTR MSG_FILAMENT_CHANGE_INSERT = _UxGT(MSG_1_LINE("Π’ΡΡ‚Π°Π²ΡŒ ΠΈ Π½Π°ΠΆΠΌΠΈ")); + LSTR MSG_FILAMENT_CHANGE_HEAT = _UxGT(MSG_1_LINE("ΠΠ°Π³Ρ€Π΅Ρ‚ΡŒ сопло")); + LSTR MSG_FILAMENT_CHANGE_HEATING = _UxGT(MSG_1_LINE("НагрСв...")); + LSTR MSG_FILAMENT_CHANGE_UNLOAD = _UxGT(MSG_1_LINE("Π’Ρ‹Π³Ρ€ΡƒΠ·ΠΊΠ°...")); + LSTR MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_1_LINE("Π—Π°Π³Ρ€ΡƒΠ·ΠΊΠ°...")); + LSTR MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_1_LINE("ΠŸΡ€ΠΎΡ‡ΠΈΡΡ‚ΠΊΠ°...")); + LSTR MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("Π—Π°Π²Π΅Ρ€ΡˆΠΈΡ‚ΡŒ прочистку")); + LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Π’ΠΎΠ·ΠΎΠ±Π½ΠΎΠ²Π»Π΅Π½ΠΈΠ΅...")); + #endif + + LSTR MSG_TMC_DRIVERS = _UxGT("Π”Ρ€Π°ΠΉΠ²Π΅Ρ€Π° TMC"); + LSTR MSG_TMC_CURRENT = _UxGT("Π’ΠΎΠΊ Π΄Π²ΠΈΠ³Π°Ρ‚Π΅Π»Π΅ΠΉ"); + LSTR MSG_TMC_HYBRID_THRS = _UxGT("Π“ΠΈΠ±Ρ€ΠΈΠ΄Π½Ρ‹ΠΉ Ρ€Π΅ΠΆΠΈΠΌ"); + LSTR MSG_TMC_HOMING_THRS = _UxGT("Π§ΡƒΠ²ΡΡ‚Π²ΠΈΡ‚Π΅Π»ΡŒΠ½ΠΎΡΡ‚ΡŒ"); + LSTR MSG_TMC_STEPPING_MODE = _UxGT("Π Π΅ΠΆΠΈΠΌ Π΄Ρ€Π°ΠΉΠ²Π΅Ρ€Π°"); + LSTR MSG_TMC_STEALTH_ENABLED = _UxGT("Π’ΠΈΡ…ΠΈΠΉ Ρ€Π΅ΠΆΠΈΠΌ Π²ΠΊΠ»"); + + LSTR MSG_SERVICE_RESET = _UxGT("Бброс"); + LSTR MSG_SERVICE_IN = _UxGT(" Π²:"); + LSTR MSG_BACKLASH = _UxGT("Π›ΡŽΡ„Ρ‚"); + LSTR MSG_BACKLASH_CORRECTION = _UxGT("Π˜ΡΠΏΡ€Π°Π²Π»Π΅Π½ΠΈΠ΅"); + LSTR MSG_BACKLASH_SMOOTHING = _UxGT("Π‘Π³Π»Π°ΠΆΠΈΠ²Π°Π½ΠΈΠ΅"); + + LSTR MSG_LEVEL_X_AXIS = _UxGT("Π’Ρ‹Ρ€ΠΎΠ²Π½ΡΡ‚ΡŒ ось X"); + LSTR MSG_AUTO_CALIBRATE = _UxGT("Автокалибровка"); + LSTR MSG_HEATER_TIMEOUT = _UxGT("Π’Π°ΠΉΠΌΠ°ΡƒΡ‚ Π½Π°Π³Ρ€Π΅Π²Π°"); + LSTR MSG_REHEAT = _UxGT("Π’ΠΎΠ·ΠΎΠ±Π½ΠΎΠ²ΠΈΡ‚ΡŒ Π½Π°Π³Ρ€Π΅Π²"); + LSTR MSG_REHEATING = _UxGT("НагрСв..."); + + LSTR MSG_PROBE_WIZARD = _UxGT("ΠœΠ°ΡΡ‚Π΅Ρ€ Z-Π·ΠΎΠ½Π΄Π°"); + #if LCD_WIDTH > 20 || HAS_DWIN_E3V2 + LSTR MSG_PROBE_WIZARD_PROBING = _UxGT("Π—ΠΎΠ½Π΄ΠΈΡ€ΠΎΠ². ΠΊΠΎΠ½Ρ‚Ρ€. Ρ‚ΠΎΡ‡ΠΊΠΈ Z"); + LSTR MSG_PROBE_WIZARD_MOVING = _UxGT("Π”Π²ΠΈΠΆΠ΅Π½ΠΈΠ΅ ΠΊ Ρ‚ΠΎΡ‡ΠΊΠ΅ Π·ΠΎΠ½Π΄ΠΈΡ€ΠΎΠ²."); + #else + LSTR MSG_PROBE_WIZARD_PROBING = _UxGT("Π—ΠΎΠ½Π΄ΠΈΡ€.ΠΊΠΎΠ½Ρ‚Ρ€.Ρ‚ΠΎΡ‡ΠΊΠΈ Z"); + LSTR MSG_PROBE_WIZARD_MOVING = _UxGT("Π”Π²ΠΈΠΆ.ΠΊ Ρ‚ΠΎΡ‡ΠΊΠ΅ Π·ΠΎΠ½Π΄ΠΈΡ€."); + #endif + + LSTR MSG_SOUND = _UxGT("Π—Π²ΡƒΠΊ"); + + LSTR MSG_TOP_LEFT = _UxGT("Π’Π΅Ρ€Ρ…Π½ΠΈΠΉ Π»Π΅Π²Ρ‹ΠΉ"); + LSTR MSG_BOTTOM_LEFT = _UxGT("НиТний Π»Π΅Π²Ρ‹ΠΉ"); + LSTR MSG_TOP_RIGHT = _UxGT("Π’Π΅Ρ€Ρ…Π½ΠΈΠΉ ΠΏΡ€Π°Π²Ρ‹ΠΉ"); + LSTR MSG_BOTTOM_RIGHT = _UxGT("НиТний ΠΏΡ€Π°Π²Ρ‹ΠΉ"); + LSTR MSG_CALIBRATION_COMPLETED = _UxGT("ΠšΠ°Π»ΠΈΠ±Ρ€ΠΎΠ²ΠΊΠ° ΡƒΡΠΏΠ΅ΡˆΠ½Π°"); + LSTR MSG_CALIBRATION_FAILED = _UxGT("Ошибка ΠΊΠ°Π»ΠΈΠ±Ρ€ΠΎΠ²ΠΊΠΈ"); + + LSTR MSG_DRIVER_BACKWARD = _UxGT(" Π΄Ρ€Π°ΠΉΠ²Π΅Ρ€ Π½Π°ΠΎΠ±ΠΎΡ€ΠΎΡ‚"); + + LSTR MSG_SD_CARD = _UxGT("SD ΠšΠ°Ρ€Ρ‚Π°"); + LSTR MSG_USB_DISK = _UxGT("USB Диск"); + + LSTR MSG_SHORT_DAY = _UxGT("Π΄"); // One character only + LSTR MSG_SHORT_HOUR = _UxGT("Ρ‡"); // One character only + LSTR MSG_SHORT_MINUTE = _UxGT("ΠΌ"); // One character only + + LSTR MSG_HIGH = _UxGT("Π’Π«Π‘ΠžΠšΠ˜Π™"); + LSTR MSG_LOW = _UxGT("ΠΠ˜Π—ΠšΠ˜Π™"); + LSTR MSG_ERROR = _UxGT("Ошибка"); + LSTR MSG_ENDSTOP_TEST = _UxGT("ВСст ΠΊΠΎΠ½Ρ†Π΅Π²ΠΈΠΊΠΎΠ²"); + LSTR MSG_Z_PROBE = _UxGT("Z-Π·ΠΎΠ½Π΄"); + LSTR MSG_HOMING = _UxGT("ΠŸΠ°Ρ€ΠΊΠΎΠ²ΠΊΠ°"); + LSTR MSG_Z_AFTER_HOME = _UxGT("Z послС ΠΏΠ°Ρ€ΠΊΠΎΠ²ΠΊΠΈ"); + LSTR MSG_FILAMENT_SET = _UxGT("Настройки Ρ„ΠΈΠ»Π°ΠΌΠ΅Π½Ρ‚Π°"); + #if LCD_WIDTH > 20 || HAS_DWIN_E3V2 + LSTR MSG_FILAMENT_MAN = _UxGT("Π£ΠΏΡ€Π°Π²Π»Π΅Π½ΠΈΠ΅ Ρ„ΠΈΠ»Π°ΠΌΠ΅Π½Ρ‚ΠΎΠΌ"); + #else + LSTR MSG_FILAMENT_MAN = _UxGT("Π£ΠΏΡ€Π°Π²Π».Ρ„ΠΈΠ»Π°ΠΌΠ΅Π½Ρ‚ΠΎΠΌ"); + #endif + LSTR MSG_MANUAL_LEVELING = _UxGT("Π ΡƒΡ‡Π½ΠΎΠ΅ Π²Ρ‹Ρ€Π°Π²Π½ΠΈΠ²Π°Π½ΠΈΠ΅"); + LSTR MSG_LEVBED_FL = _UxGT("ΠŸΠ΅Ρ€Π΅Π΄Π½ΠΈΠΉ Π»Π΅Π²Ρ‹ΠΉ"); + LSTR MSG_LEVBED_FR = _UxGT("ΠŸΠ΅Ρ€Π΅Π΄Π½ΠΈΠΉ ΠΏΡ€Π°Π²Ρ‹ΠΉ"); + LSTR MSG_LEVBED_C = _UxGT("Π¦Π΅Π½Ρ‚Ρ€"); + LSTR MSG_LEVBED_BL = _UxGT("Π—Π°Π΄Π½ΠΈΠΉ Π»Π΅Π²Ρ‹ΠΉ"); + LSTR MSG_LEVBED_BR = _UxGT("Π—Π°Π΄Π½ΠΈΠΉ ΠΏΡ€Π°Π²Ρ‹ΠΉ"); + LSTR MSG_MANUAL_MESH = _UxGT("Π‘Π΅Ρ‚ΠΊΠ° Π²Ρ€ΡƒΡ‡Π½ΡƒΡŽ"); + LSTR MSG_AUTO_MESH = _UxGT("Π‘Π΅Ρ‚ΠΊΠ° автоматичСски"); + LSTR MSG_ERR_M428_TOO_FAR = _UxGT("Ошибка: слишком Π΄Π°Π»Π΅ΠΊΠΎ!"); + LSTR MSG_TRAMMING_WIZARD = _UxGT("ΠŸΠΎΠΌΠΎΡ‰Π½ΠΈΠΊ Π²Ρ‹Ρ€Π°Π²Π½ΠΈΠ²."); + LSTR MSG_PREHEAT_HOTEND = _UxGT("ΠΠ°Π³Ρ€Π΅Ρ‚ΡŒ сопло"); + LSTR MSG_BED_TRAMMING_MANUAL = _UxGT("Π ΡƒΡ‡Π½ΠΎΠ΅ Π²Ρ‹Ρ€Π°Π²Π½ΠΈΠ²."); + LSTR MSG_MESH_VIEWER = _UxGT("ΠŸΡ€ΠΎΡΠΌΠΎΡ‚Ρ€ сСтки"); + LSTR MSG_MESH_VIEW = _UxGT("Π‘ΠΌΠΎΡ‚Ρ€Π΅Ρ‚ΡŒ сСтку"); + LSTR MSG_NO_VALID_MESH = _UxGT("НСт Π³ΠΎΠ΄Π½ΠΎΠΉ сСтки"); + LSTR MSG_ACTIVATE_MESH = _UxGT("Π’ΠΊΠ»ΡŽΡ‡ΠΈΡ‚ΡŒ сСтку"); + LSTR MSG_MESH_INSET = _UxGT("ΠžΡ‚ΡΡ‚ΡƒΠΏΡ‹ сСтки"); + LSTR MSG_MESH_MIN_X = _UxGT("Π‘Π΅Ρ‚ΠΊΠ° X ΠΌΠΈΠ½ΠΈΠΌΡƒΠΌ"); + LSTR MSG_MESH_MAX_X = _UxGT("Π‘Π΅Ρ‚ΠΊΠ° X максимум"); + LSTR MSG_MESH_MIN_Y = _UxGT("Π‘Π΅Ρ‚ΠΊΠ° Y ΠΌΠΈΠ½ΠΈΠΌΡƒΠΌ"); + LSTR MSG_MESH_MAX_Y = _UxGT("Π‘Π΅Ρ‚ΠΊΠ° Y максимум"); + LSTR MSG_MESH_AMAX = _UxGT("Максимальная Π·ΠΎΠ½Π°"); + LSTR MSG_MESH_CENTER = _UxGT("Π¦Π΅Π½Ρ‚Ρ€ΠΈΡ€ΠΎΠ²Π°Ρ‚ΡŒ Π·ΠΎΠ½Ρƒ"); + LSTR MSG_MESH_CANCEL = _UxGT("Π‘Π΅Ρ‚ΠΊΠ° ΠΎΡ‚ΠΌΠ΅Π½Π΅Π½Π°"); + LSTR MSG_UBL_TILT_MESH = _UxGT("ΠΠ°ΠΊΠΎΠ»Π½ΠΈΡ‚ΡŒ сСтку"); + LSTR MSG_UBL_TILTING_GRID = _UxGT("Π’Π΅Π»ΠΈΡ‡ΠΈΠ½Π° Π½Π°ΠΊΠ»ΠΎΠ½Π°"); + LSTR MSG_UBL_MESH_TILTED = _UxGT("Π‘Π΅Ρ‚ΠΊΠ° Π½Π°ΠΊΠ»ΠΎΠ½Π΅Π½Π°"); + LSTR MSG_UBL_MESH_FILLED = _UxGT("ΠŸΠΎΠΏΡƒΡ‰Π΅Π½Π½Ρ‹Π΅ Ρ‚ΠΎΡ‡ΠΊΠΈ Π·Π°ΠΏΠΎΠ»Π½Π΅Π½Ρ‹"); + LSTR MSG_UBL_MESH_INVALID = _UxGT("НСгодная сСтка"); + LSTR MSG_UBL_INVALID_SLOT = _UxGT("Π‘ΠΏΠ΅Ρ€Π²Π° Π²Ρ‹Π±Π΅Ρ€ΠΈΡ‚Π΅ слот сСтки"); + LSTR MSG_MESH_ACTIVE = _UxGT("Π‘Π΅Ρ‚ΠΊΠ° %i Π°ΠΊΡ‚ΠΈΠ²Π½Π°"); + LSTR MSG_MOVE_50MM = _UxGT("Π”Π²ΠΈΠ³Π°Ρ‚ΡŒ 50mm"); + LSTR MSG_LIVE_MOVE = _UxGT("Π–ΠΈΠ²ΠΎΠ΅ ΠΏΠ΅Ρ€Π΅ΠΌΠ΅Ρ‰Π΅Π½ΠΈΠ΅"); + LSTR MSG_CUTTER = _UxGT("Π Π΅Π·Π°ΠΊ"); + LSTR MSG_PID_CYCLE = _UxGT("Π¦ΠΈΠΊΠ»Ρ‹ PID"); + LSTR MSG_PID_AUTOTUNE_FAILED = _UxGT("Автонастройка PID Π½Π΅ ΡƒΠ΄Π°Π»Π°ΡΡŒ!"); + LSTR MSG_BAD_HEATER_ID = _UxGT("НСвСрный экструдСр."); + LSTR MSG_TEMP_TOO_HIGH = _UxGT("Блишком высокая Ρ‚Π΅ΠΌΠΏΠ΅Ρ€Π°Ρ‚ΡƒΡ€Π°."); + LSTR MSG_TIMEOUT = _UxGT("Π’Π°ΠΉΠΌΠ°ΡƒΡ‚."); + LSTR MSG_MPC_MEASURING_AMBIENT = _UxGT("ВСст ΠΏΠΎΡ‚Π΅Ρ€ΠΈ Ρ‚Π΅ΠΏΠ»Π°"); + LSTR MSG_MPC_HEATING_PAST_200 = _UxGT("НагрСв Π²Ρ‹ΡˆΠ΅ >200C"); + LSTR MSG_MPC_COOLING_TO_AMBIENT = _UxGT("ΠžΡ…Π»Π°ΠΆΠ΄Π΅Π½ΠΈΠ΅ Π΄ΠΎ ΠΎΠΊΡ€ΡƒΠΆΠ°ΡŽΡ‰Π΅ΠΉ"); + LSTR MSG_MPC_AUTOTUNE = _UxGT("Автонастройка MPC"); + LSTR MSG_MPC_EDIT = _UxGT("Π˜Π·ΠΌΠ΅Π½ΠΈΡ‚ΡŒ * MPC"); + LSTR MSG_MPC_POWER = _UxGT("ΠœΠΎΡ‰Π½ΠΎΡΡ‚ΡŒ нагрСватСля"); + LSTR MSG_MPC_POWER_E = _UxGT("ΠœΠΎΡ‰Π½ΠΎΡΡ‚ΡŒ *"); + LSTR MSG_MPC_BLOCK_HEAT_CAPACITY = _UxGT("Π’Π΅ΠΏΠ»ΠΎΡ‘ΠΌΠΊΠΎΡΡ‚ΡŒ"); + LSTR MSG_MPC_BLOCK_HEAT_CAPACITY_E = _UxGT("Π’Π΅ΠΏΠ»ΠΎΡ‘ΠΌΠΊ. *"); + LSTR MSG_SENSOR_RESPONSIVENESS = _UxGT("ΠžΡ‚ΠΊΠ»ΠΈΠΊ Π΄Π°Ρ‚Ρ‡ΠΈΠΊΠ°"); + LSTR MSG_SENSOR_RESPONSIVENESS_E = _UxGT("ΠžΡ‚ΠΊΠ»ΠΈΠΊ Π΄Π°Ρ‚Ρ‡. *"); + LSTR MSG_MPC_AMBIENT_XFER_COEFF = _UxGT("ΠšΠΎΡΡ„Ρ„.окруТСния"); + LSTR MSG_MPC_AMBIENT_XFER_COEFF_E = _UxGT("ΠšΠΎΡΡ„Ρ„.ΠΎΠΊΡ€ΡƒΠΆ *"); + LSTR MSG_MPC_AMBIENT_XFER_COEFF_FAN = _UxGT("ΠšΠΎΡΡ„Ρ„.ΠΊΡƒΠ»Π΅Ρ€Π°"); + LSTR MSG_MPC_AMBIENT_XFER_COEFF_FAN_E = _UxGT("ΠšΠΎΡΡ„Ρ„.ΠΊΡƒΠ»Π΅Ρ€ *"); + LSTR MSG_INPUT_SHAPING = _UxGT("Input Shaping"); + LSTR MSG_SHAPING_ENABLE = _UxGT("Π’ΠΊΠ»ΡŽΡ‡ΠΈΡ‚ΡŒ шСйпинг @"); + LSTR MSG_SHAPING_DISABLE = _UxGT("Π’Ρ‹ΠΊΠ»ΡŽΡ‡ΠΈΡ‚ΡŒ шСйпинг @"); + LSTR MSG_SHAPING_FREQ = _UxGT("@ частота"); + LSTR MSG_SHAPING_ZETA = _UxGT("@ ΠΏΠΎΠ΄Π°Π²Π»Π΅Π½ΠΈΠ΅"); + LSTR MSG_FILAMENT_EN = _UxGT("Π€ΠΈΠ»Π°ΠΌΠ΅Π½Ρ‚ *"); + LSTR MSG_SEGMENTS_PER_SECOND = _UxGT("Π‘Π΅Π³ΠΌΠ΅Π½Ρ‚ΠΎΠ²/сСк"); + LSTR MSG_DRAW_MIN_X = _UxGT("Π ΠΈΡΠΎΠ²Π°Ρ‚ΡŒ ΠΌΠΈΠ½ X"); + LSTR MSG_DRAW_MAX_X = _UxGT("Π ΠΈΡΠΎΠ²Π°Ρ‚ΡŒ макс X"); + LSTR MSG_DRAW_MIN_Y = _UxGT("Π ΠΈΡΠΎΠ²Π°Ρ‚ΡŒ ΠΌΠΈΠ½ Y"); + LSTR MSG_DRAW_MAX_Y = _UxGT("Π ΠΈΡΠΎΠ²Π°Ρ‚ΡŒ макс Y"); + LSTR MSG_MAX_BELT_LEN = _UxGT("Макс.Π΄Π»ΠΈΠ½Π° рСмня"); + LSTR MSG_LINEAR_ADVANCE = _UxGT("Linear Advance"); + LSTR MSG_BRIGHTNESS = _UxGT("Π―Ρ€ΠΊΠΎΡΡ‚ΡŒ LCD"); + LSTR MSG_SCREEN_TIMEOUT = _UxGT("Π’Π°ΠΉΠΌΠ°ΡƒΡ‚ LCD (ΠΌ)"); + LSTR MSG_BRIGHTNESS_OFF = _UxGT("Π’Ρ‹ΠΊΠ».подсвСтку"); + LSTR MSG_INFO_MACHINENAME = _UxGT("НазваниС ΠΌΠ°ΡˆΠΈΠ½Ρ‹"); + LSTR MSG_INFO_SIZE = _UxGT("Π Π°Π·ΠΌΠ΅Ρ€"); + LSTR MSG_INFO_FWVERSION = _UxGT("ВСрсия ΠΏΡ€ΠΎΡˆΠΈΠ²ΠΊΠΈ"); + LSTR MSG_INFO_BUILD = _UxGT("Π”Π°Ρ‚Π° сборки"); + LSTR MSG_BUTTON_CONFIRM = _UxGT("ΠŸΠΎΠ΄Ρ‚Π²Π΅Ρ€Π΄ΠΈΡ‚ΡŒ"); + LSTR MSG_BUTTON_CONTINUE = _UxGT("ΠŸΡ€ΠΎΠ΄ΠΎΠ»ΠΆΠΈΡ‚ΡŒ"); + LSTR MSG_BUTTON_INFO = _UxGT("Π˜Π½Ρ„ΠΎ"); + LSTR MSG_BUTTON_LEVEL = _UxGT("Π’Ρ‹Ρ€ΠΎΠ²Π½ΡΡ‚ΡŒ"); + LSTR MSG_BUTTON_PAUSE = _UxGT("ΠŸΠ°ΡƒΠ·Π°"); + LSTR MSG_BUTTON_RESUME = _UxGT("ΠŸΡ€ΠΎΠ΄ΠΎΠ»ΠΆΠΈΡ‚ΡŒ"); + LSTR MSG_BUTTON_ADVANCED = _UxGT("Π Π°ΡΡˆΠΈΡ€Π°Π½Π½Ρ‹Π΅"); + LSTR MSG_BUTTON_SAVE = _UxGT("Π‘ΠΎΡ…Ρ€Π°Π½ΠΈΡ‚ΡŒ"); + LSTR MSG_BUTTON_PURGE = _UxGT("ΠŸΡ€ΠΎΡ‡ΠΈΡΡ‚ΠΈΡ‚ΡŒ"); + LSTR MSG_PAUSING = _UxGT("ΠŸΠ°ΡƒΠ·Π°..."); + LSTR MSG_ADVANCED_PAUSE = _UxGT("Π Π°ΡΡˆΠΈΡ€Π΅Π½Π½Π°Ρ ΠΏΠ°ΡƒΠ·Π°"); + LSTR MSG_CONTINUE_PRINT_JOB = _UxGT("ΠŸΡ€ΠΎΠ΄ΠΎΠ»ΠΆΠΈΡ‚ΡŒ ΠΏΠ΅Ρ‡Π°Ρ‚ΡŒ"); + LSTR MSG_TURN_OFF = _UxGT("Π’Ρ‹ΠΊΠ»ΡŽΡ‡ΠΈΡ‚ΡŒ ΠΏΡ€ΠΈΠ½Ρ‚Π΅Ρ€"); + LSTR MSG_END_LOOPS = _UxGT("Π—Π°Π²Π΅Ρ€ΡˆΠΈΡ‚ΡŒ ΠΏΠ΅Ρ‚Π»ΡŽ"); + LSTR MSG_STOPPING = _UxGT("ΠžΡΡ‚Π°Π½ΠΎΠ²ΠΊΠ°..."); + LSTR MSG_REMAINING_TIME = _UxGT("ΠžΡΡ‚Π°Π»ΠΎΡΡŒ"); + LSTR MSG_PRINTER_KILLED = _UxGT("ΠŸΡ€ΠΈΠ½Ρ‚Π΅Ρ€ ΡƒΠ±ΠΈΡ‚!"); + LSTR MSG_FWRETRACT = _UxGT("ΠžΡ‚ΠΊΠ°Ρ‚ ΠΏΡ€ΠΈΠ½Ρ‚Π΅Ρ€Π°"); + LSTR MSG_SINGLENOZZLE_WIPE_RETRACT = _UxGT("Π’Ρ‹Ρ‚ΠΈΡ€Π°Π½ΠΈΠ΅ ΠΏΡ€ΠΈ ΠΎΡ‚ΠΊΠ°Ρ‚Π΅"); + LSTR MSG_PARK_FAILED = _UxGT("НС ΡƒΠ΄Π°Π»ΠΎΡΡŒ Π·Π°ΠΏΠ°Ρ€ΠΊΠΎΠ²Π°Ρ‚ΡŒ"); + LSTR MSG_FILAMENTUNLOAD = _UxGT("Π’Ρ‹Π³Ρ€ΡƒΠ·ΠΈΡ‚ΡŒ Ρ„ΠΈΠ»Π°ΠΌΠ΅Π½Ρ‚"); + LSTR MSG_ATTACH_USB_MEDIA = _UxGT("ΠœΠΎΠ½Ρ‚ΠΈΡ€ΠΎΠ²Π°Ρ‚ΡŒ USB"); + LSTR MSG_BLTOUCH_SPEED_MODE = _UxGT("Высокая ΡΠΊΠΎΡ€ΠΎΡΡ‚ΡŒ"); + LSTR MSG_MANUAL_PENUP = _UxGT("ΠŸΠΎΠ΄Π½ΡΡ‚ΡŒ ΠΏΠ΅Ρ€ΠΎ"); + LSTR MSG_MANUAL_PENDOWN = _UxGT("ΠžΠΏΡƒΡΡ‚ΠΈΡ‚ΡŒ ΠΏΠ΅Ρ€ΠΎ"); + LSTR MSG_ZPROBE_SETTINGS = _UxGT("Наторойки Π·ΠΎΠ½Π΄Π°"); + LSTR MSG_ZPROBE_MARGIN = _UxGT("ΠžΡ‚ΡΡ‚ΡƒΠΏΡ‹ Π·ΠΎΠ½Π΄Π°"); + LSTR MSG_Z_FEED_RATE = _UxGT("Π‘ΠΊΠΎΡ€ΠΎΡΡ‚ΡŒ Z"); + LSTR MSG_ENABLE_HS_MODE = _UxGT("Π’ΠΊΠ»ΡŽΡ‡ΠΈΡ‚ΡŒ Ρ€Π΅ΠΆΠΈΠΌ Π’Π‘"); + LSTR MSG_TEMP_MALFUNCTION = _UxGT("Π‘Π‘ΠžΠ™ Π’Π•ΠœΠŸΠ•Π ΠΠ’Π£Π Π«"); + LSTR MSG_PLEASE_WAIT = _UxGT("ΠžΠΆΠΈΠ΄Π°ΠΉΡ‚Π΅..."); + LSTR MSG_PREHEATING = _UxGT("ΠΠ°Π³Ρ€Π΅Π²Π°ΡŽ..."); + LSTR MSG_DELTA_CALIBRATION_IN_PROGRESS = _UxGT("Π”Π΅Π»Π°ΡŽ Π΄Π΅Π»ΡŒΡ‚Π°-ΠΊΠ°Π»ΠΈΠ±Ρ€ΠΎΠ²ΠΊΡƒ"); + LSTR MSG_RESET_STATS = _UxGT("Π‘Π±Ρ€ΠΎΡΠΈΡ‚ΡŒ статистику ΠΏΠ΅Ρ‡Π°Ρ‚ΠΈ?"); + LSTR MSG_FAN_SPEED_FAULT = _UxGT("Π‘Π±ΠΎΠΉ скорости ΠΊΡƒΠ»Π΅Ρ€Π°"); + LSTR MSG_COLORS_GET = _UxGT("ΠŸΠΎΠ»ΡƒΡ‡ΠΈΡ‚ΡŒ Ρ†Π²Π΅Ρ‚"); + LSTR MSG_COLORS_SELECT = _UxGT("Π’Ρ‹Π±Ρ€Π°Ρ‚ΡŒ Ρ†Π²Π΅Ρ‚Π°"); + LSTR MSG_COLORS_APPLIED = _UxGT("Π¦Π²Π΅Ρ‚Π° ΠΏΡ€ΠΈΠΌΠ΅Π½Π΅Π½Ρ‹"); + LSTR MSG_COLORS_RED = _UxGT("ΠšΡ€Π°ΡΠ½Ρ‹ΠΉ"); + LSTR MSG_COLORS_GREEN = _UxGT("Π—Π΅Π»Ρ‘Π½Ρ‹ΠΉ"); + LSTR MSG_COLORS_BLUE = _UxGT("Π‘ΠΈΠ½ΠΈΠΉ"); + LSTR MSG_COLORS_WHITE = _UxGT("Π‘Π΅Π»Ρ‹ΠΉ"); + LSTR MSG_UI_LANGUAGE = _UxGT("UI Language"); + LSTR MSG_SOUND_ENABLE = _UxGT("Π’ΠΊΠ»ΡŽΡ‡ΠΈΡ‚ΡŒ Π·Π²ΡƒΠΊ"); + LSTR MSG_LOCKSCREEN = _UxGT("Π‘Π»ΠΎΠΊΠΈΡ€ΠΎΠ²Π°Ρ‚ΡŒ экран"); + LSTR MSG_LOCKSCREEN_LOCKED = _UxGT("ΠŸΡ€ΠΈΠ½Ρ‚Π΅Ρ€ Π·Π°Π±Π»ΠΎΠΊΠΈΡ€ΠΎΠ²Π°Π½,"); + LSTR MSG_LOCKSCREEN_UNLOCK = _UxGT("ΠšΡ€ΡƒΡ‚ΠΈΡ‚ΡŒ для Ρ€Π°Π·Π±Π»ΠΎΠΊΠΈΡ€ΠΎΠ²ΠΊΠΈ."); + LSTR MSG_PLEASE_WAIT_REBOOT = _UxGT("Π–Π΄ΠΈΡ‚Π΅ ΠΏΠ΅Ρ€Π΅Π·Π°Π³Ρ€ΡƒΠ·ΠΊΠΈ."); + LSTR MSG_MEDIA_NOT_INSERTED = _UxGT("НСт носитСля."); + LSTR MSG_PLEASE_PREHEAT = _UxGT("НагрСйтС сопло."); + LSTR MSG_INFO_PRINT_COUNT_RESET = _UxGT("Π‘Π±Ρ€ΠΎΡΠΈΡ‚ΡŒ счСтчик"); + LSTR MSG_FILAMENT_CHANGE_PURGE_CONTINUE = _UxGT("ΠŸΡ€ΠΎΡ‡ΠΈΡΡ‚ΠΈΡ‚ΡŒ ΠΈΠ»ΠΈ ΠΏΡ€ΠΎΠ΄ΠΎΠ»ΠΆΠΈΡ‚ΡŒ?"); + LSTR MSG_RUNOUT_ENABLE = _UxGT("Π’ΠΊΠ»ΡŽΡ‡ΠΈΡ‚ΡŒ Π΄Π°Ρ‚Ρ‡.Ρ„ΠΈΠ»Π°ΠΌΠ΅Π½Ρ‚Π°"); + LSTR MSG_RUNOUT_ACTIVE = _UxGT("Π”Π°Ρ‚Ρ‡.Ρ„ΠΈΠ»Π°ΠΌ. Π°ΠΊΡ‚ΠΈΠ²Π΅Π½"); + LSTR MSG_INVERT_EXTRUDER = _UxGT("Π˜Π½Π²Π΅Ρ€Ρ‚ΠΈΡ€ΠΎΠ²Π°Ρ‚ΡŒ экструдСр"); + LSTR MSG_EXTRUDER_MIN_TEMP = _UxGT("Миню Ρ‚Π΅ΠΌΠΏ. экструдСра."); + LSTR MSG_FANCHECK = _UxGT("ΠŸΡ€ΠΎΠ².Ρ‚Π°Ρ…ΠΎΠΌΠ΅Ρ‚Ρ€Π° ΠΊΡƒΠ»Π΅Ρ€Π°"); + LSTR MSG_MMU2_REMOVE_AND_CLICK = _UxGT("Π£Π±Π΅Ρ€ΠΈΡ‚Π΅ ΠΈ ΠΊΠ»ΠΈΠΊΠ½ΠΈΡ‚Π΅..."); + LSTR MSG_REHEATDONE = _UxGT("НагрСто"); + LSTR MSG_XATC = _UxGT("ΠŸΠΎΠΌΠΎΡ‰Π½ΠΈΠΊ пСрСкоса X"); + LSTR MSG_XATC_DONE = _UxGT("ΠŸΠ΅Ρ€Π΅ΠΊΠΎΡ Π₯ настроСн!"); + LSTR MSG_XATC_UPDATE_Z_OFFSET = _UxGT("НовоС смСщСниС Z-Π·ΠΎΠ½Π΄Π° "); + LSTR MSG_HOST_SHUTDOWN = _UxGT("Π’Ρ‹ΠΊΠ»ΡŽΡ‡ΠΈΡ‚ΡŒ хост"); + + // did not translate as there is no local terms/slang yet + LSTR MSG_FIXED_TIME_MOTION = _UxGT("Fixed-Time Motion"); + LSTR MSG_FTM_MODE = _UxGT("Motion Mode:"); + LSTR MSG_FTM_ZV = _UxGT("ZV"); + LSTR MSG_FTM_ZVD = _UxGT("ZVD"); + LSTR MSG_FTM_EI = _UxGT("EI"); + LSTR MSG_FTM_2HEI = _UxGT("2HEI"); + LSTR MSG_FTM_3HEI = _UxGT("3HEI"); + LSTR MSG_FTM_MZV = _UxGT("MZV"); + //LSTR MSG_FTM_ULENDO_FBS = _UxGT("Ulendo Π€BΠ‘"); + //LSTR MSG_FTM_DISCTF = _UxGT("DISCTF"); + LSTR MSG_FTM_DYN_MODE = _UxGT("DF Mode:"); + LSTR MSG_FTM_Z_BASED = _UxGT("Z-based"); + LSTR MSG_FTM_MASS_BASED = _UxGT("Mass-based"); + LSTR MSG_FTM_BASE_FREQ_N = _UxGT("@ Base Freq."); + LSTR MSG_FTM_DFREQ_K_N = _UxGT("@ Dyn. Freq."); } diff --git a/Marlin/src/lcd/language/language_sk.h b/Marlin/src/lcd/language/language_sk.h index c7b2cef0d10c..cea40d2406aa 100644 --- a/Marlin/src/lcd/language/language_sk.h +++ b/Marlin/src/lcd/language/language_sk.h @@ -67,8 +67,6 @@ namespace Language_sk { LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Soft. endstopy"); LSTR MSG_MAIN_MENU = _UxGT("HlavnΓ‘ ponuka"); LSTR MSG_ADVANCED_SETTINGS = _UxGT("PokročilΓ© nastav."); - LSTR MSG_TOOLBAR_SETUP = _UxGT("Panel nΓ‘strojov"); - LSTR MSG_OPTION_DISABLED = _UxGT("MoΕΎnosΕ₯ vypnutΓ‘"); LSTR MSG_CONFIGURATION = _UxGT("KonfigurΓ‘cia"); LSTR MSG_RUN_AUTO_FILES = _UxGT("Auto-Ε‘tart"); LSTR MSG_DISABLE_STEPPERS = _UxGT("UvolniΕ₯ motory"); diff --git a/Marlin/src/lcd/language/language_tr.h b/Marlin/src/lcd/language/language_tr.h index 5be21c9c565f..63c41854477b 100644 --- a/Marlin/src/lcd/language/language_tr.h +++ b/Marlin/src/lcd/language/language_tr.h @@ -57,8 +57,6 @@ namespace Language_tr { LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("YazΔ±lΔ±msal Endstops"); LSTR MSG_MAIN_MENU = _UxGT("Ana"); LSTR MSG_ADVANCED_SETTINGS = _UxGT("Gelişmiş Ayarlar"); - LSTR MSG_TOOLBAR_SETUP = _UxGT("AraΓ§ Γ‡ubuğu Kurulumu"); - LSTR MSG_OPTION_DISABLED = _UxGT("SeΓ§enek Devre Dışı"); LSTR MSG_CONFIGURATION = _UxGT("YapΔ±landΔ±rma"); LSTR MSG_RUN_AUTO_FILES = _UxGT("Oto. Başlat"); LSTR MSG_DISABLE_STEPPERS = _UxGT("MotorlarΔ± Durdur"); diff --git a/Marlin/src/lcd/language/language_vi.h b/Marlin/src/lcd/language/language_vi.h index 2ce22961ca73..69b58f71f01d 100644 --- a/Marlin/src/lcd/language/language_vi.h +++ b/Marlin/src/lcd/language/language_vi.h @@ -438,5 +438,4 @@ namespace Language_vi { LSTR MSG_SHORT_DAY = _UxGT("n"); // d - ngΓ y - One character only LSTR MSG_SHORT_HOUR = _UxGT("g"); // h - giờ - One character only LSTR MSG_SHORT_MINUTE = _UxGT("p"); // m - phΓΊt - One character only - LSTR MSG_SHORT_MINUTE = _UxGT("p"); // M - phΓΊt - One character only } diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 1c4bbe5fa93b..8d27ee8f7e26 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -24,7 +24,7 @@ #include "../MarlinCore.h" // for printingIsPaused -#if LED_POWEROFF_TIMEOUT > 0 || BOTH(HAS_WIRED_LCD, PRINTER_EVENT_LEDS) || (defined(LCD_BACKLIGHT_TIMEOUT_MINS) && defined(NEOPIXEL_BKGD_INDEX_FIRST)) +#if LED_POWEROFF_TIMEOUT > 0 || ALL(HAS_WIRED_LCD, PRINTER_EVENT_LEDS) || (defined(LCD_BACKLIGHT_TIMEOUT_MINS) && defined(NEOPIXEL_BKGD_INDEX_FIRST)) #include "../feature/leds/leds.h" #endif @@ -32,7 +32,7 @@ #include "../feature/host_actions.h" #endif -#if BOTH(BROWSE_MEDIA_ON_INSERT, PASSWORD_ON_SD_PRINT_MENU) +#if ALL(BROWSE_MEDIA_ON_INSERT, PASSWORD_ON_SD_PRINT_MENU) #include "../feature/password/password.h" #endif @@ -68,7 +68,7 @@ MarlinUI ui; constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; #if HAS_STATUS_MESSAGE - #if ENABLED(STATUS_MESSAGE_SCROLLING) && EITHER(HAS_WIRED_LCD, DWIN_LCD_PROUI) + #if ENABLED(STATUS_MESSAGE_SCROLLING) && ANY(HAS_WIRED_LCD, DWIN_LCD_PROUI) uint8_t MarlinUI::status_scroll_offset; // = 0 #endif char MarlinUI::status_message[MAX_MESSAGE_LENGTH + 1]; @@ -154,7 +154,7 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; } #endif -#if EITHER(HAS_MARLINUI_MENU, EXTENSIBLE_UI) +#if ANY(HAS_MARLINUI_MENU, EXTENSIBLE_UI) bool MarlinUI::lcd_clicked; #endif @@ -270,7 +270,7 @@ void MarlinUI::init() { #endif // HAS_SHIFT_ENCODER - #if BOTH(HAS_ENCODER_ACTION, HAS_SLOW_BUTTONS) + #if ALL(HAS_ENCODER_ACTION, HAS_SLOW_BUTTONS) slow_buttons = 0; #endif @@ -339,7 +339,7 @@ void MarlinUI::init() { uint8_t MarlinUI::lcd_status_update_delay = 1; // First update one loop delayed - #if BOTH(FILAMENT_LCD_DISPLAY, HAS_MEDIA) + #if ALL(FILAMENT_LCD_DISPLAY, HAS_MEDIA) millis_t MarlinUI::next_filament_display; // = 0 #endif @@ -402,7 +402,7 @@ void MarlinUI::init() { } #endif - #if EITHER(REVERSE_MENU_DIRECTION, REVERSE_SELECT_DIRECTION) + #if ANY(REVERSE_MENU_DIRECTION, REVERSE_SELECT_DIRECTION) int8_t MarlinUI::encoderDirection = ENCODERBASE; #endif @@ -411,7 +411,7 @@ void MarlinUI::init() { uint8_t MarlinUI::repeat_delay; #endif - #if EITHER(AUTO_BED_LEVELING_UBL, G26_MESH_VALIDATION) + #if ANY(AUTO_BED_LEVELING_UBL, G26_MESH_VALIDATION) bool MarlinUI::external_control; // = false @@ -574,7 +574,7 @@ void MarlinUI::init() { #endif if (homed) { - #if EITHER(DELTA, Z_HOME_TO_MAX) + #if ANY(DELTA, Z_HOME_TO_MAX) if (RRK(EN_KEYPAD_F2)) _reprapworld_keypad_move(Z_AXIS, 1); #endif if (RRK(EN_KEYPAD_F3)) _reprapworld_keypad_move(Z_AXIS, -1); @@ -670,7 +670,7 @@ void MarlinUI::init() { #if HAS_MARLINUI_MENU if (use_click()) { - #if BOTH(FILAMENT_LCD_DISPLAY, HAS_MEDIA) + #if ALL(FILAMENT_LCD_DISPLAY, HAS_MEDIA) pause_filament_display(); #endif goto_screen(menu_main); @@ -702,7 +702,7 @@ void MarlinUI::init() { if (old_frm != new_frm) { feedrate_percentage = new_frm; encoderPosition = 0; - #if BOTH(HAS_SOUND, BEEP_ON_FEEDRATE_CHANGE) + #if ALL(HAS_SOUND, BEEP_ON_FEEDRATE_CHANGE) static millis_t next_beep; #ifndef GOT_MS const millis_t ms = millis(); @@ -1046,7 +1046,7 @@ void MarlinUI::init() { if (encoderPastThreshold || lcd_clicked) { if (encoderPastThreshold && TERN1(IS_TFTGLCD_PANEL, !external_control)) { - #if BOTH(HAS_MARLINUI_MENU, ENCODER_RATE_MULTIPLIER) + #if ALL(HAS_MARLINUI_MENU, ENCODER_RATE_MULTIPLIER) int32_t encoderMultiplier = 1; @@ -1112,7 +1112,7 @@ void MarlinUI::init() { refresh(LCDVIEW_REDRAW_NOW); } - #if BOTH(HAS_MARLINUI_MENU, SCROLL_LONG_FILENAMES) + #if ALL(HAS_MARLINUI_MENU, SCROLL_LONG_FILENAMES) // If scrolling of long file names is enabled and we are in the sd card menu, // cause a refresh to occur until all the text has scrolled into view. if (currentScreen == menu_media && !lcd_status_update_delay--) { @@ -1289,7 +1289,7 @@ void MarlinUI::init() { thermalManager.current_ADCKey_raw = HAL_ADC_RANGE; thermalManager.ADCKey_count = 0; if (currentkpADCValue < adc_other_button) - LOOP_L_N(i, ADC_KEY_NUM) { + for (uint8_t i = 0; i < ADC_KEY_NUM; ++i) { const raw_adc_t lo = pgm_read_word(&stADCKeyTable[i].ADCKeyValueMin), hi = pgm_read_word(&stADCKeyTable[i].ADCKeyValueMax); if (WITHIN(currentkpADCValue, lo, hi)) return pgm_read_byte(&stADCKeyTable[i].ADCKeyNo); @@ -1353,7 +1353,7 @@ void MarlinUI::init() { #endif // UP || DOWN || LEFT || RIGHT buttons = (newbutton | TERN0(HAS_SLOW_BUTTONS, slow_buttons) - #if BOTH(HAS_TOUCH_BUTTONS, HAS_ENCODER_ACTION) + #if ALL(HAS_TOUCH_BUTTONS, HAS_ENCODER_ACTION) | (touch_buttons & TERN(HAS_ENCODER_WHEEL, ~(EN_A | EN_B), 0xFF)) #endif ); @@ -1380,7 +1380,7 @@ void MarlinUI::init() { uint8_t val = 0; WRITE(SHIFT_LD_PIN, LOW); WRITE(SHIFT_LD_PIN, HIGH); - LOOP_L_N(i, 8) { + for (uint8_t i = 0; i < 8; ++i) { val >>= 1; if (READ(SHIFT_OUT_PIN)) SBI(val, 7); WRITE(SHIFT_CLK_PIN, HIGH); @@ -1413,7 +1413,7 @@ void MarlinUI::init() { case 3: ENCODER_SPIN(2, 1); break; case 1: ENCODER_SPIN(3, 0); break; } - #if BOTH(HAS_MARLINUI_MENU, AUTO_BED_LEVELING_UBL) + #if ALL(HAS_MARLINUI_MENU, AUTO_BED_LEVELING_UBL) external_encoder(); #endif lastEncoderBits = enc; @@ -1587,7 +1587,7 @@ void MarlinUI::init() { #if HAS_WIRED_LCD - #if BASIC_PROGRESS_BAR || BOTH(FILAMENT_LCD_DISPLAY, HAS_MEDIA) + #if BASIC_PROGRESS_BAR || ALL(FILAMENT_LCD_DISPLAY, HAS_MEDIA) const millis_t ms = millis(); #endif @@ -1598,13 +1598,13 @@ void MarlinUI::init() { #endif #endif - #if BOTH(FILAMENT_LCD_DISPLAY, HAS_MEDIA) + #if ALL(FILAMENT_LCD_DISPLAY, HAS_MEDIA) pause_filament_display(ms); // Show status message for 5s #endif #endif - #if ENABLED(STATUS_MESSAGE_SCROLLING) && EITHER(HAS_WIRED_LCD, DWIN_LCD_PROUI) + #if ENABLED(STATUS_MESSAGE_SCROLLING) && ANY(HAS_WIRED_LCD, DWIN_LCD_PROUI) status_scroll_offset = 0; #endif @@ -1670,7 +1670,7 @@ void MarlinUI::init() { TERN_(DWIN_LCD_PROUI, HMI_flag.abort_flag = true); } - #if BOTH(HAS_MARLINUI_MENU, PSU_CONTROL) + #if ALL(HAS_MARLINUI_MENU, PSU_CONTROL) void MarlinUI::poweroff() { queue.inject(F("M81" TERN_(POWER_OFF_WAIT_FOR_COOLDOWN, "S"))); @@ -1848,7 +1848,7 @@ void MarlinUI::init() { #endif } - #if EITHER(BABYSTEP_GFX_OVERLAY, MESH_EDIT_GFX_OVERLAY) + #if ANY(BABYSTEP_GFX_OVERLAY, MESH_EDIT_GFX_OVERLAY) void MarlinUI::zoffset_overlay(const_float_t zvalue) { // Determine whether the user is raising or lowering the nozzle. static int8_t dir; @@ -1863,7 +1863,7 @@ void MarlinUI::init() { #endif -#if BOTH(EXTENSIBLE_UI, ADVANCED_PAUSE_FEATURE) +#if ALL(EXTENSIBLE_UI, ADVANCED_PAUSE_FEATURE) void MarlinUI::pause_show_message( const PauseMessage message, diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index ccdbd6432280..f811545ef66b 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -88,7 +88,7 @@ typedef bool (*statusResetFunc_t)(); #endif // HAS_WIRED_LCD -#if EITHER(HAS_WIRED_LCD, DWIN_CREALITY_LCD_JYERSUI) +#if ANY(HAS_WIRED_LCD, DWIN_CREALITY_LCD_JYERSUI) #define LCD_WITH_BLINK 1 #define LCD_UPDATE_INTERVAL TERN(HAS_TOUCH_BUTTONS, 50, 100) #endif @@ -246,7 +246,7 @@ class MarlinUI { // LCD implementations static void clear_lcd(); - #if BOTH(HAS_MARLINUI_MENU, TOUCH_SCREEN_CALIBRATION) + #if ALL(HAS_MARLINUI_MENU, TOUCH_SCREEN_CALIBRATION) static void check_touch_calibration() { if (touch_calibration.need_calibration()) currentScreen = touch_calibration_screen; } @@ -313,7 +313,7 @@ class MarlinUI { static void set_progress_done() { progress_override = (PROGRESS_MASK + 1U) + 100U * (PROGRESS_SCALE); } static void progress_reset() { if (progress_override & (PROGRESS_MASK + 1U)) set_progress(0); } #endif - #if EITHER(SHOW_REMAINING_TIME, SET_PROGRESS_MANUALLY) + #if ANY(SHOW_REMAINING_TIME, SET_PROGRESS_MANUALLY) static uint32_t _calculated_remaining_time() { const duration_t elapsed = print_job_timer.duration(); const progress_t progress = _get_progress(); @@ -361,7 +361,7 @@ class MarlinUI { #if HAS_STATUS_MESSAGE - #if EITHER(HAS_WIRED_LCD, DWIN_LCD_PROUI) + #if ANY(HAS_WIRED_LCD, DWIN_LCD_PROUI) #if ENABLED(STATUS_MESSAGE_SCROLLING) #define MAX_MESSAGE_LENGTH _MAX(LONG_FILENAME_LENGTH, MAX_LANG_CHARSIZE * 2 * (LCD_WIDTH)) #else @@ -412,7 +412,7 @@ class MarlinUI { static void resume_print(); static void flow_fault(); - #if BOTH(HAS_MARLINUI_MENU, PSU_CONTROL) + #if ALL(HAS_MARLINUI_MENU, PSU_CONTROL) static void poweroff(); #endif @@ -471,7 +471,7 @@ class MarlinUI { FORCE_INLINE static void refresh_contrast() { set_contrast(contrast); } #endif - #if BOTH(FILAMENT_LCD_DISPLAY, HAS_MEDIA) + #if ALL(FILAMENT_LCD_DISPLAY, HAS_MEDIA) static millis_t next_filament_display; static void pause_filament_display(const millis_t ms=millis()) { next_filament_display = ms + 5000UL; } #endif @@ -510,7 +510,7 @@ class MarlinUI { static bool did_first_redraw; #endif - #if EITHER(BABYSTEP_GFX_OVERLAY, MESH_EDIT_GFX_OVERLAY) + #if ANY(BABYSTEP_GFX_OVERLAY, MESH_EDIT_GFX_OVERLAY) static void zoffset_overlay(const int8_t dir); static void zoffset_overlay(const_float_t zvalue); #endif @@ -534,7 +534,7 @@ class MarlinUI { #endif #if HAS_MEDIA - #if BOTH(SCROLL_LONG_FILENAMES, HAS_MARLINUI_MENU) + #if ALL(SCROLL_LONG_FILENAMES, HAS_MARLINUI_MENU) #define MARLINUI_SCROLL_NAME 1 #endif #if MARLINUI_SCROLL_NAME @@ -646,7 +646,7 @@ class MarlinUI { #endif - #if EITHER(HAS_MARLINUI_MENU, EXTENSIBLE_UI) + #if ANY(HAS_MARLINUI_MENU, EXTENSIBLE_UI) static bool lcd_clicked; static bool use_click() { const bool click = lcd_clicked; @@ -684,7 +684,7 @@ class MarlinUI { // // Special handling if a move is underway // - #if ANY(DELTA_CALIBRATION_MENU, DELTA_AUTO_CALIBRATION, PROBE_OFFSET_WIZARD, X_AXIS_TWIST_COMPENSATION) || (ENABLED(LCD_BED_LEVELING) && EITHER(PROBE_MANUALLY, MESH_BED_LEVELING)) + #if ANY(DELTA_CALIBRATION_MENU, DELTA_AUTO_CALIBRATION, PROBE_OFFSET_WIZARD, X_AXIS_TWIST_COMPENSATION) || (ENABLED(LCD_BED_LEVELING) && ANY(PROBE_MANUALLY, MESH_BED_LEVELING)) #define LCD_HAS_WAIT_FOR_MOVE 1 static bool wait_for_move; #else @@ -694,7 +694,7 @@ class MarlinUI { // // Block interaction while under external control // - #if HAS_MARLINUI_MENU && EITHER(AUTO_BED_LEVELING_UBL, G26_MESH_VALIDATION) + #if HAS_MARLINUI_MENU && ANY(AUTO_BED_LEVELING_UBL, G26_MESH_VALIDATION) static bool external_control; FORCE_INLINE static void capture() { external_control = true; } FORCE_INLINE static void release() { external_control = false; } @@ -727,7 +727,7 @@ class MarlinUI { * printer unusable in practice. */ static bool hw_button_pressed() { - LOOP_L_N(s, ENCODER_SAMPLES) { + for (uint8_t s = 0; s < ENCODER_SAMPLES; ++s) { if (!BUTTON_CLICK()) return false; safe_delay(1); } @@ -737,7 +737,7 @@ class MarlinUI { static bool hw_button_pressed() { return BUTTON_CLICK(); } #endif - #if EITHER(AUTO_BED_LEVELING_UBL, G26_MESH_VALIDATION) + #if ANY(AUTO_BED_LEVELING_UBL, G26_MESH_VALIDATION) static void wait_for_release(); #endif @@ -745,14 +745,14 @@ class MarlinUI { #define ENCODERBASE (TERN(REVERSE_ENCODER_DIRECTION, -1, +1)) - #if EITHER(REVERSE_MENU_DIRECTION, REVERSE_SELECT_DIRECTION) + #if ANY(REVERSE_MENU_DIRECTION, REVERSE_SELECT_DIRECTION) static int8_t encoderDirection; #else static constexpr int8_t encoderDirection = ENCODERBASE; #endif FORCE_INLINE static void encoder_direction_normal() { - #if EITHER(REVERSE_MENU_DIRECTION, REVERSE_SELECT_DIRECTION) + #if ANY(REVERSE_MENU_DIRECTION, REVERSE_SELECT_DIRECTION) encoderDirection = ENCODERBASE; #endif } diff --git a/Marlin/src/lcd/menu/game/brickout.cpp b/Marlin/src/lcd/menu/game/brickout.cpp index fc4d19b1d98d..078cbbcceee2 100644 --- a/Marlin/src/lcd/menu/game/brickout.cpp +++ b/Marlin/src/lcd/menu/game/brickout.cpp @@ -44,7 +44,7 @@ brickout_data_t &bdat = marlin_game_data.brickout; inline void reset_bricks(const uint16_t v) { bdat.brick_count = (BRICK_COLS) * (BRICK_ROWS); - LOOP_L_N(i, BRICK_ROWS) bdat.bricks[i] = v; + for (uint8_t i = 0; i < BRICK_ROWS; ++i) bdat.bricks[i] = v; } void reset_ball() { @@ -138,13 +138,13 @@ void BrickoutGame::game_screen() { // Draw bricks if (PAGE_CONTAINS(BRICK_TOP, BRICK_BOT)) { - LOOP_L_N(y, BRICK_ROWS) { + for (uint8_t y = 0; y < BRICK_ROWS; ++y) { const uint8_t yy = y * BRICK_H + BRICK_TOP; if (PAGE_CONTAINS(yy, yy + BRICK_H - 1)) { - LOOP_L_N(x, BRICK_COLS) { + for (uint8_t x = 0; x < BRICK_COLS; ++x) { if (TEST(bdat.bricks[y], x)) { const uint8_t xx = x * BRICK_W; - LOOP_L_N(v, BRICK_H - 1) + for (uint8_t v = 0; v < BRICK_H - 1; ++v) if (PAGE_CONTAINS(yy + v, yy + v)) u8g.drawHLine(xx, yy + v, BRICK_W - 1); } diff --git a/Marlin/src/lcd/menu/game/invaders.cpp b/Marlin/src/lcd/menu/game/invaders.cpp index 56e4c224dd14..1cb3e5bf3fcb 100644 --- a/Marlin/src/lcd/menu/game/invaders.cpp +++ b/Marlin/src/lcd/menu/game/invaders.cpp @@ -166,29 +166,29 @@ inline void update_invader_data() { uint8_t inv_mask = 0; // Get a list of all active invaders uint8_t sc = 0; - LOOP_L_N(y, INVADER_ROWS) { + for (uint8_t y = 0; y < INVADER_ROWS; ++y) { uint8_t m = idat.bugs[y]; if (m) idat.botmost = y + 1; inv_mask |= m; - LOOP_L_N(x, INVADER_COLS) + for (uint8_t x = 0; x < INVADER_COLS; ++x) if (TEST(m, x)) idat.shooters[sc++] = (y << 4) | x; } idat.leftmost = 0; - LOOP_L_N(i, INVADER_COLS) { if (TEST(inv_mask, i)) break; idat.leftmost -= INVADER_COL_W; } + for (uint8_t i = 0; i < INVADER_COLS; ++i) { if (TEST(inv_mask, i)) break; idat.leftmost -= INVADER_COL_W; } idat.rightmost = LCD_PIXEL_WIDTH - (INVADERS_WIDE); for (uint8_t i = INVADER_COLS; i--;) { if (TEST(inv_mask, i)) break; idat.rightmost += INVADER_COL_W; } if (idat.count == 2) idat.dir = idat.dir > 0 ? INVADER_VEL + 1 : -(INVADER_VEL + 1); } inline void reset_bullets() { - LOOP_L_N(i, COUNT(idat.bullet)) idat.bullet[i].v = 0; + for (uint8_t i = 0; i < COUNT(idat.bullet); ++i) idat.bullet[i].v = 0; } inline void reset_invaders() { idat.pos.x = 0; idat.pos.y = INVADER_TOP; idat.dir = INVADER_VEL; idat.count = (INVADER_COLS) * (INVADER_ROWS); - LOOP_L_N(i, INVADER_ROWS) idat.bugs[i] = _BV(INVADER_COLS) - 1; + for (uint8_t i = 0; i < INVADER_ROWS; ++i) idat.bugs[i] = _BV(INVADER_COLS) - 1; update_invader_data(); reset_bullets(); } @@ -274,7 +274,7 @@ void InvadersGame::game_screen() { // Find a free bullet laser_t *b = nullptr; - LOOP_L_N(i, COUNT(idat.bullet)) if (!idat.bullet[i].v) { b = &idat.bullet[i]; break; } + for (uint8_t i = 0; i < COUNT(idat.bullet); ++i) if (!idat.bullet[i].v) { b = &idat.bullet[i]; break; } if (b) { // Pick a random shooter and update the bullet //SERIAL_ECHOLNPGM("free bullet found"); @@ -322,7 +322,7 @@ void InvadersGame::game_screen() { } // laser in invader zone // Handle alien bullets - LOOP_L_N(s, COUNT(idat.bullet)) { + for (uint8_t s = 0; s < COUNT(idat.bullet); ++s) { laser_t *b = &idat.bullet[s]; if (b->v) { // Update alien bullet position @@ -371,11 +371,11 @@ void InvadersGame::game_screen() { // Draw invaders if (PAGE_CONTAINS(idat.pos.y, idat.pos.y + idat.botmost * (INVADER_ROW_H) - 2 - 1)) { int8_t yy = idat.pos.y; - LOOP_L_N(y, INVADER_ROWS) { + for (uint8_t y = 0; y < INVADER_ROWS; ++y) { const uint8_t type = inv_type[y]; if (PAGE_CONTAINS(yy, yy + INVADER_H - 1)) { int8_t xx = idat.pos.x; - LOOP_L_N(x, INVADER_COLS) { + for (uint8_t x = 0; x < INVADER_COLS; ++x) { if (TEST(idat.bugs[y], x)) u8g.drawBitmapP(xx, yy, 2, INVADER_H, invader[type][idat.game_blink]); xx += INVADER_COL_W; @@ -398,7 +398,7 @@ void InvadersGame::game_screen() { u8g.drawVLine(idat.laser.x, idat.laser.y, LASER_H); // Draw invader bullets - LOOP_L_N (i, COUNT(idat.bullet)) { + for (uint8_t i = 0; i < COUNT(idat.bullet); ++i) { if (idat.bullet[i].v && PAGE_CONTAINS(idat.bullet[i].y - (SHOT_H - 1), idat.bullet[i].y)) u8g.drawVLine(idat.bullet[i].x, idat.bullet[i].y - (SHOT_H - 1), SHOT_H); } diff --git a/Marlin/src/lcd/menu/game/maze.cpp b/Marlin/src/lcd/menu/game/maze.cpp index 85f752ee7de5..0c77f69e1ed4 100644 --- a/Marlin/src/lcd/menu/game/maze.cpp +++ b/Marlin/src/lcd/menu/game/maze.cpp @@ -83,7 +83,7 @@ void MazeGame::game_screen() { if (PAGE_UNDER(HEADER_H)) lcd_put_int(0, HEADER_H - 1, score); // Draw the maze - // LOOP_L_N(n, head_ind) { + // for (uint8_t n = 0; n < head_ind; ++n) { // const pos_t &p = maze_walls[n], &q = maze_walls[n + 1]; // if (p.x == q.x) { // const int8_t y1 = GAMEY(_MIN(p.y, q.y)), y2 = GAMEY(_MAX(p.y, q.y)); diff --git a/Marlin/src/lcd/menu/game/snake.cpp b/Marlin/src/lcd/menu/game/snake.cpp index c88893a6e6c7..2a78c089cfbe 100644 --- a/Marlin/src/lcd/menu/game/snake.cpp +++ b/Marlin/src/lcd/menu/game/snake.cpp @@ -84,14 +84,14 @@ void shorten_tail() { } if (shift) { sdat.head_ind--; - LOOP_LE_N(i, sdat.head_ind) + for (uint8_t i = 0; i <= sdat.head_ind; ++i) sdat.snake_tail[i] = sdat.snake_tail[i + 1]; } } // The food is on a line inline bool food_on_line() { - LOOP_L_N(n, sdat.head_ind) { + for (uint8_t n = 0; n < sdat.head_ind; ++n) { pos_t &p = sdat.snake_tail[n], &q = sdat.snake_tail[n + 1]; if (p.x == q.x) { if ((sdat.foodx == p.x - 1 || sdat.foodx == p.x) && WITHIN(sdat.foody, _MIN(p.y, q.y), _MAX(p.y, q.y))) @@ -151,7 +151,7 @@ bool snake_overlap() { // VERTICAL head segment? if (h1.x == h2.x) { // Loop from oldest to segment two away from head - LOOP_L_N(n, sdat.head_ind - 2) { + for (uint8_t n = 0; n < sdat.head_ind - 2; ++n) { // Segment p to q const pos_t &p = sdat.snake_tail[n], &q = sdat.snake_tail[n + 1]; if (p.x != q.x) { @@ -163,7 +163,7 @@ bool snake_overlap() { } else { // Loop from oldest to segment two away from head - LOOP_L_N(n, sdat.head_ind - 2) { + for (uint8_t n = 0; n < sdat.head_ind - 2; ++n) { // Segment p to q const pos_t &p = sdat.snake_tail[n], &q = sdat.snake_tail[n + 1]; if (p.y != q.y) { @@ -240,7 +240,7 @@ void SnakeGame::game_screen() { #if SNAKE_WH < 2 // At this scale just draw a line - LOOP_L_N(n, sdat.head_ind) { + for (uint8_t n = 0; n < sdat.head_ind; ++n) { const pos_t &p = sdat.snake_tail[n], &q = sdat.snake_tail[n + 1]; if (p.x == q.x) { const int8_t y1 = GAMEY(_MIN(p.y, q.y)), y2 = GAMEY(_MAX(p.y, q.y)); @@ -256,7 +256,7 @@ void SnakeGame::game_screen() { #elif SNAKE_WH == 2 // At this scale draw two lines - LOOP_L_N(n, sdat.head_ind) { + for (uint8_t n = 0; n < sdat.head_ind; ++n) { const pos_t &p = sdat.snake_tail[n], &q = sdat.snake_tail[n + 1]; if (p.x == q.x) { const int8_t y1 = GAMEY(_MIN(p.y, q.y)), y2 = GAMEY(_MAX(p.y, q.y)); @@ -275,7 +275,7 @@ void SnakeGame::game_screen() { #else // Draw a series of boxes - LOOP_L_N(n, sdat.head_ind) { + for (uint8_t n = 0; n < sdat.head_ind; ++n) { const pos_t &p = sdat.snake_tail[n], &q = sdat.snake_tail[n + 1]; if (p.x == q.x) { const int8_t y1 = _MIN(p.y, q.y), y2 = _MAX(p.y, q.y); diff --git a/Marlin/src/lcd/menu/menu.cpp b/Marlin/src/lcd/menu/menu.cpp index 911a35d482bd..a9574dd4d9af 100644 --- a/Marlin/src/lcd/menu/menu.cpp +++ b/Marlin/src/lcd/menu/menu.cpp @@ -176,7 +176,7 @@ void MarlinUI::goto_screen(screenFunc_t screen, const uint16_t encoder/*=0*/, co TERN_(SET_PROGRESS_PERCENT, progress_reset()); - #if BOTH(DOUBLECLICK_FOR_Z_BABYSTEPPING, BABYSTEPPING) + #if ALL(DOUBLECLICK_FOR_Z_BABYSTEPPING, BABYSTEPPING) static millis_t doubleclick_expire_ms = 0; // Going to menu_main from status screen? Remember first click time. // Going back to status screen within a very short time? Go to Z babystepping. diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index 0be23be71a84..7ef11d0e06c4 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -268,7 +268,7 @@ void menu_backlash(); } #endif -#if BOTH(AUTOTEMP, HAS_TEMP_HOTEND) || ANY(PID_AUTOTUNE_MENU, PID_EDIT_MENU, MPC_AUTOTUNE_MENU, MPC_EDIT_MENU) +#if ALL(AUTOTEMP, HAS_TEMP_HOTEND) || ANY(PID_AUTOTUNE_MENU, PID_EDIT_MENU, MPC_AUTOTUNE_MENU, MPC_EDIT_MENU) #define SHOW_MENU_ADVANCED_TEMPERATURE 1 #endif @@ -277,7 +277,7 @@ void menu_backlash(); // #if SHOW_MENU_ADVANCED_TEMPERATURE - #if BOTH(MPC_EDIT_MENU, MPC_INCLUDE_FAN) + #if ALL(MPC_EDIT_MENU, MPC_INCLUDE_FAN) #define MPC_EDIT_DEFS(N) editable.decimal = thermalManager.temp_hotend[N].fanCoefficient() #else #define MPC_EDIT_DEFS(...) @@ -294,7 +294,7 @@ void menu_backlash(); // // Autotemp, Min, Max, Fact // - #if BOTH(AUTOTEMP, HAS_TEMP_HOTEND) + #if ALL(AUTOTEMP, HAS_TEMP_HOTEND) EDIT_ITEM(int3, MSG_MIN, &planner.autotemp.min, 0, thermalManager.hotend_max_target(0)); EDIT_ITEM(int3, MSG_MAX, &planner.autotemp.max, 0, thermalManager.hotend_max_target(0)); EDIT_ITEM(float42_52, MSG_FACTOR, &planner.autotemp.factor, 0, 10); @@ -309,7 +309,7 @@ void menu_backlash(); // PID-P E5, PID-I E5, PID-D E5, PID-C E5, PID Autotune E5 // - #if BOTH(PIDTEMP, PID_EDIT_MENU) + #if ALL(PIDTEMP, PID_EDIT_MENU) #define __PID_HOTEND_MENU_ITEMS(N) \ raw_Kp = thermalManager.temp_hotend[N].pid.p(); \ raw_Ki = thermalManager.temp_hotend[N].pid.i(); \ @@ -342,7 +342,7 @@ void menu_backlash(); #endif - #if ENABLED(PID_EDIT_MENU) && EITHER(PIDTEMPBED, PIDTEMPCHAMBER) + #if ENABLED(PID_EDIT_MENU) && ANY(PIDTEMPBED, PIDTEMPCHAMBER) #define _PID_EDIT_ITEMS_TMPL(N,T) \ raw_Kp = T.pid.p(); \ raw_Ki = T.pid.i(); \ @@ -460,7 +460,7 @@ void menu_backlash(); EDIT_ITEM_FAST_N(float5, E_AXIS, MSG_VMAX_N, &planner.settings.max_feedrate_mm_s[E_AXIS_N(active_extruder)], 1, max_fr_edit_scaled.e); #endif #if ENABLED(DISTINCT_E_FACTORS) - LOOP_L_N(n, E_STEPPERS) + for (uint8_t n = 0; n < E_STEPPERS; ++n) EDIT_ITEM_FAST_N(float5, n, MSG_VMAX_EN, &planner.settings.max_feedrate_mm_s[E_AXIS_N(n)], 1, max_fr_edit_scaled.e); #endif @@ -532,7 +532,7 @@ void menu_backlash(); #if ENABLED(DISTINCT_E_FACTORS) EDIT_ITEM_FAST(long5_25, MSG_AMAX_E, &planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(active_extruder)], 100, max_accel_edit_scaled.e, []{ planner.refresh_acceleration_rates(); }); - LOOP_L_N(n, E_STEPPERS) + for (uint8_t n = 0; n < E_STEPPERS; ++n) EDIT_ITEM_FAST_N(long5_25, n, MSG_AMAX_EN, &planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(n)], 100, max_accel_edit_scaled.e, []{ if (MenuItemBase::itemIndex == active_extruder) planner.refresh_acceleration_rates(); @@ -656,7 +656,7 @@ void menu_advanced_steps_per_mm() { EDIT_ITEM_FAST_N(float72, a, MSG_N_STEPS, &planner.settings.axis_steps_per_mm[a], 5, 9999, []{ planner.refresh_positioning(); }); #if ENABLED(DISTINCT_E_FACTORS) - LOOP_L_N(n, E_STEPPERS) + for (uint8_t n = 0; n < E_STEPPERS; ++n) EDIT_ITEM_FAST_N(float72, n, MSG_EN_STEPS, &planner.settings.axis_steps_per_mm[E_AXIS_N(n)], 5, 9999, []{ const uint8_t e = MenuItemBase::itemIndex; if (e == active_extruder) diff --git a/Marlin/src/lcd/menu/menu_backlash.cpp b/Marlin/src/lcd/menu/menu_backlash.cpp index 1f3856918f43..a5f1f3746bf0 100644 --- a/Marlin/src/lcd/menu/menu_backlash.cpp +++ b/Marlin/src/lcd/menu/menu_backlash.cpp @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfigPre.h" -#if BOTH(HAS_MARLINUI_MENU, BACKLASH_GCODE) +#if ALL(HAS_MARLINUI_MENU, BACKLASH_GCODE) #include "menu_item.h" @@ -39,7 +39,7 @@ void menu_backlash() { editable.uint8 = backlash.get_correction_uint8(); EDIT_ITEM_FAST(percent, MSG_BACKLASH_CORRECTION, &editable.uint8, backlash.all_off, backlash.all_on, []{ backlash.set_correction_uint8(editable.uint8); }); - #if DISABLED(CORE_BACKLASH) || EITHER(MARKFORGED_XY, MARKFORGED_YX) + #if DISABLED(CORE_BACKLASH) || ANY(MARKFORGED_XY, MARKFORGED_YX) #define _CAN_CALI AXIS_CAN_CALIBRATE #else #define _CAN_CALI(A) true diff --git a/Marlin/src/lcd/menu/menu_bed_leveling.cpp b/Marlin/src/lcd/menu/menu_bed_leveling.cpp index dcf77cb3eb3a..efc05aabde48 100644 --- a/Marlin/src/lcd/menu/menu_bed_leveling.cpp +++ b/Marlin/src/lcd/menu/menu_bed_leveling.cpp @@ -43,7 +43,7 @@ #endif #endif -#if EITHER(PROBE_MANUALLY, MESH_BED_LEVELING) +#if ANY(PROBE_MANUALLY, MESH_BED_LEVELING) #include "../../module/motion.h" #include "../../gcode/queue.h" @@ -169,7 +169,7 @@ if (ui.should_draw()) { MenuItem_static::draw(1, GET_TEXT_F(MSG_LEVEL_BED_WAITING)); // Color UI needs a control to detect a touch - #if BOTH(TOUCH_SCREEN, HAS_GRAPHICAL_TFT) + #if ALL(TOUCH_SCREEN, HAS_GRAPHICAL_TFT) touch.add_control(CLICK, 0, 0, TFT_WIDTH, TFT_HEIGHT); #endif } @@ -249,7 +249,7 @@ void menu_bed_leveling() { #endif // Level Bed - #if EITHER(PROBE_MANUALLY, MESH_BED_LEVELING) + #if ANY(PROBE_MANUALLY, MESH_BED_LEVELING) // Manual leveling uses a guided procedure SUBMENU(MSG_LEVEL_BED, _lcd_level_bed_continue); #else diff --git a/Marlin/src/lcd/menu/menu_bed_tramming.cpp b/Marlin/src/lcd/menu/menu_bed_tramming.cpp index 8129a347c314..b6b3e7212485 100644 --- a/Marlin/src/lcd/menu/menu_bed_tramming.cpp +++ b/Marlin/src/lcd/menu/menu_bed_tramming.cpp @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfigPre.h" -#if BOTH(HAS_MARLINUI_MENU, LCD_BED_TRAMMING) +#if ALL(HAS_MARLINUI_MENU, LCD_BED_TRAMMING) #include "menu_item.h" #include "../../module/motion.h" @@ -43,7 +43,7 @@ #define BED_TRAMMING_HEIGHT 0.0 #endif -#if BOTH(HAS_STOWABLE_PROBE, BED_TRAMMING_USE_PROBE) && DISABLED(BLTOUCH) +#if ALL(HAS_STOWABLE_PROBE, BED_TRAMMING_USE_PROBE) && DISABLED(BLTOUCH) #define NEEDS_PROBE_DEPLOY 1 #endif @@ -152,7 +152,7 @@ static void _lcd_goto_next_corner() { } float z = BED_TRAMMING_Z_HOP; - #if BOTH(BED_TRAMMING_USE_PROBE, BLTOUCH) + #if ALL(BED_TRAMMING_USE_PROBE, BLTOUCH) z += bltouch.z_extra_clearance(); #endif line_to_z(z); @@ -187,7 +187,7 @@ static void _lcd_goto_next_corner() { if (PAGE_CONTAINS(y - (MENU_FONT_HEIGHT), y)) { SETCURSOR(TERN(TFT_COLOR_UI, 2, 0), cy); lcd_put_u8str(GET_TEXT_F(MSG_BED_TRAMMING_GOOD_POINTS)); - IF_ENABLED(TFT_COLOR_UI, lcd_moveto(12, cy)); + TERN_(TFT_COLOR_UI, lcd_moveto(12, cy)); lcd_put_u8str(GOOD_POINTS_TO_STR(good_points)); lcd_put_u8str(F("/")); lcd_put_u8str(GOOD_POINTS_TO_STR(nr_edge_points)); @@ -200,7 +200,7 @@ static void _lcd_goto_next_corner() { if (PAGE_CONTAINS(y - (MENU_FONT_HEIGHT), y)) { SETCURSOR(TERN(TFT_COLOR_UI, 2, 0), cy); lcd_put_u8str(GET_TEXT_F(MSG_BED_TRAMMING_LAST_Z)); - IF_ENABLED(TFT_COLOR_UI, lcd_moveto(12, 2)); + TERN_(TFT_COLOR_UI, lcd_moveto(12, 2)); lcd_put_u8str(LAST_Z_TO_STR(last_z)); } } diff --git a/Marlin/src/lcd/menu/menu_cancelobject.cpp b/Marlin/src/lcd/menu/menu_cancelobject.cpp index b2784bcd41b6..bcbd90ee3a60 100644 --- a/Marlin/src/lcd/menu/menu_cancelobject.cpp +++ b/Marlin/src/lcd/menu/menu_cancelobject.cpp @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfigPre.h" -#if BOTH(HAS_MARLINUI_MENU, CANCEL_OBJECTS) +#if ALL(HAS_MARLINUI_MENU, CANCEL_OBJECTS) #include "menu_item.h" #include "menu_addon.h" diff --git a/Marlin/src/lcd/menu/menu_configuration.cpp b/Marlin/src/lcd/menu/menu_configuration.cpp index 0611bda84b32..6440cae03302 100644 --- a/Marlin/src/lcd/menu/menu_configuration.cpp +++ b/Marlin/src/lcd/menu/menu_configuration.cpp @@ -59,7 +59,7 @@ #include "../../libs/buzzer.h" #endif -#if EITHER(LCD_PROGRESS_BAR_TEST, LCD_ENDSTOP_TEST) +#if ANY(LCD_PROGRESS_BAR_TEST, LCD_ENDSTOP_TEST) #include "../lcdprint.h" #define HAS_DEBUG_MENU 1 #endif @@ -68,7 +68,7 @@ #include "../../core/debug_out.h" void menu_advanced_settings(); -#if EITHER(DELTA_CALIBRATION_MENU, DELTA_AUTO_CALIBRATION) +#if ANY(DELTA_CALIBRATION_MENU, DELTA_AUTO_CALIBRATION) void menu_delta_calibrate(); #endif @@ -592,7 +592,7 @@ void menu_configuration() { #endif if (!busy) { - #if EITHER(DELTA_CALIBRATION_MENU, DELTA_AUTO_CALIBRATION) + #if ANY(DELTA_CALIBRATION_MENU, DELTA_AUTO_CALIBRATION) SUBMENU(MSG_DELTA_CALIBRATE, menu_delta_calibrate); #endif @@ -657,7 +657,7 @@ void menu_configuration() { // Preheat configurations #if HAS_PREHEAT && DISABLED(SLIM_LCD_MENUS) - LOOP_L_N(m, PREHEAT_COUNT) + for (uint8_t m = 0; m < PREHEAT_COUNT; ++m) SUBMENU_N_f(m, ui.get_preheat_label(m), MSG_PREHEAT_M_SETTINGS, _menu_configuration_preheat_settings); #endif diff --git a/Marlin/src/lcd/menu/menu_delta_calibrate.cpp b/Marlin/src/lcd/menu/menu_delta_calibrate.cpp index fe0be0439853..c7da12a61ee6 100644 --- a/Marlin/src/lcd/menu/menu_delta_calibrate.cpp +++ b/Marlin/src/lcd/menu/menu_delta_calibrate.cpp @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfigPre.h" -#if HAS_MARLINUI_MENU && EITHER(DELTA_CALIBRATION_MENU, DELTA_AUTO_CALIBRATION) +#if HAS_MARLINUI_MENU && ANY(DELTA_CALIBRATION_MENU, DELTA_AUTO_CALIBRATION) #include "menu_item.h" #include "../../module/delta.h" diff --git a/Marlin/src/lcd/menu/menu_filament.cpp b/Marlin/src/lcd/menu/menu_filament.cpp index 6fdcc2b48818..073ffc183855 100644 --- a/Marlin/src/lcd/menu/menu_filament.cpp +++ b/Marlin/src/lcd/menu/menu_filament.cpp @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfigPre.h" -#if BOTH(HAS_MARLINUI_MENU, ADVANCED_PAUSE_FEATURE) +#if ALL(HAS_MARLINUI_MENU, ADVANCED_PAUSE_FEATURE) #include "menu_item.h" #include "../../module/temperature.h" @@ -96,7 +96,7 @@ void _menu_temp_filament_op(const PauseMode mode, const int8_t extruder) { if (LCD_HEIGHT >= 4) STATIC_ITEM_F(change_filament_header(mode), SS_DEFAULT|SS_INVERT); BACK_ITEM(MSG_BACK); #if HAS_PREHEAT - LOOP_L_N(m, PREHEAT_COUNT) + for (uint8_t m = 0; m < PREHEAT_COUNT; ++m) ACTION_ITEM_N_f(m, ui.get_preheat_label(m), MSG_PREHEAT_M, _change_filament_with_preset); #endif EDIT_ITEM_FAST_N(int3, extruder, MSG_PREHEAT_CUSTOM, &thermalManager.temp_hotend[extruder].target, @@ -141,7 +141,7 @@ void menu_change_filament() { GCODES_ITEM_F(fmsg, F("M600 B0")); #else FSTR_P const fmsg = GET_TEXT_F(MSG_FILAMENTCHANGE_E); - LOOP_L_N(s, E_STEPPERS) { + for (uint8_t s = 0; s < E_STEPPERS; ++s) { if (thermalManager.targetTooColdToExtrude(s)) SUBMENU_N_F(s, fmsg, []{ _menu_temp_filament_op(PAUSE_MODE_CHANGE_FILAMENT, MenuItemBase::itemIndex); }); else { @@ -166,7 +166,7 @@ void menu_change_filament() { GCODES_ITEM_F(msg_load, F("M701")); #else FSTR_P const msg_load = GET_TEXT_F(MSG_FILAMENTLOAD_E); - LOOP_L_N(s, E_STEPPERS) { + for (uint8_t s = 0; s < E_STEPPERS; ++s) { if (thermalManager.targetTooColdToExtrude(s)) SUBMENU_N_F(s, msg_load, []{ _menu_temp_filament_op(PAUSE_MODE_LOAD_FILAMENT, MenuItemBase::itemIndex); }); else { @@ -194,7 +194,7 @@ void menu_change_filament() { GCODES_ITEM(MSG_FILAMENTUNLOAD_ALL, F("M702")); #endif FSTR_P const msg_unload = GET_TEXT_F(MSG_FILAMENTUNLOAD_E); - LOOP_L_N(s, E_STEPPERS) { + for (uint8_t s = 0; s < E_STEPPERS; ++s) { if (thermalManager.targetTooColdToExtrude(s)) SUBMENU_N_F(s, msg_unload, []{ _menu_temp_filament_op(PAUSE_MODE_UNLOAD_FILAMENT, MenuItemBase::itemIndex); }); else { diff --git a/Marlin/src/lcd/menu/menu_info.cpp b/Marlin/src/lcd/menu/menu_info.cpp index e2dd6c647527..59ed52e6f17b 100644 --- a/Marlin/src/lcd/menu/menu_info.cpp +++ b/Marlin/src/lcd/menu/menu_info.cpp @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfigPre.h" -#if BOTH(HAS_MARLINUI_MENU, LCD_INFO_MENU) +#if ALL(HAS_MARLINUI_MENU, LCD_INFO_MENU) #include "menu_item.h" diff --git a/Marlin/src/lcd/menu/menu_job_recovery.cpp b/Marlin/src/lcd/menu/menu_job_recovery.cpp index 6329c5839786..b2276aeb0cdd 100644 --- a/Marlin/src/lcd/menu/menu_job_recovery.cpp +++ b/Marlin/src/lcd/menu/menu_job_recovery.cpp @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfigPre.h" -#if BOTH(HAS_MARLINUI_MENU, POWER_LOSS_RECOVERY) +#if ALL(HAS_MARLINUI_MENU, POWER_LOSS_RECOVERY) #include "menu_item.h" #include "../../gcode/queue.h" diff --git a/Marlin/src/lcd/menu/menu_led.cpp b/Marlin/src/lcd/menu/menu_led.cpp index dea5ecceeb01..c7390b98cb20 100644 --- a/Marlin/src/lcd/menu/menu_led.cpp +++ b/Marlin/src/lcd/menu/menu_led.cpp @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfigPre.h" -#if HAS_MARLINUI_MENU && EITHER(LED_CONTROL_MENU, CASE_LIGHT_MENU) +#if HAS_MARLINUI_MENU && ANY(LED_CONTROL_MENU, CASE_LIGHT_MENU) #include "menu_item.h" diff --git a/Marlin/src/lcd/menu/menu_main.cpp b/Marlin/src/lcd/menu/menu_main.cpp index a202f624f7fc..4ccdb60bf14c 100644 --- a/Marlin/src/lcd/menu/menu_main.cpp +++ b/Marlin/src/lcd/menu/menu_main.cpp @@ -43,7 +43,7 @@ #include "game/game.h" #endif -#if EITHER(HAS_MEDIA, HOST_PROMPT_SUPPORT) || defined(ACTION_ON_CANCEL) +#if ANY(HAS_MEDIA, HOST_PROMPT_SUPPORT) || defined(ACTION_ON_CANCEL) #define MACHINE_CAN_STOP 1 #endif #if ANY(HAS_MEDIA, HOST_PROMPT_SUPPORT, PARK_HEAD_ON_PAUSE) || defined(ACTION_ON_PAUSE) @@ -88,7 +88,7 @@ void menu_configuration(); void menu_info(); #endif -#if EITHER(LED_CONTROL_MENU, CASE_LIGHT_MENU) +#if ANY(LED_CONTROL_MENU, CASE_LIGHT_MENU) void menu_led(); #endif @@ -273,7 +273,7 @@ void menu_main() { #endif } else { - #if BOTH(HAS_MEDIA, MEDIA_MENU_AT_TOP) + #if ALL(HAS_MEDIA, MEDIA_MENU_AT_TOP) // BEGIN MEDIA MENU #if ENABLED(MENU_ADDAUTOSTART) ACTION_ITEM(MSG_RUN_AUTO_FILES, card.autofile_begin); // Run Auto Files @@ -326,7 +326,7 @@ void menu_main() { SUBMENU(MSG_MOTION, menu_motion); } - #if BOTH(ADVANCED_PAUSE_FEATURE, DISABLE_ENCODER) + #if ALL(ADVANCED_PAUSE_FEATURE, DISABLE_ENCODER) FILAMENT_CHANGE_ITEM(); #endif @@ -366,7 +366,7 @@ void menu_main() { SUBMENU(MSG_INFO_MENU, menu_info); #endif - #if EITHER(LED_CONTROL_MENU, CASE_LIGHT_MENU) + #if ANY(LED_CONTROL_MENU, CASE_LIGHT_MENU) SUBMENU(MSG_LEDS, menu_led); #endif diff --git a/Marlin/src/lcd/menu/menu_media.cpp b/Marlin/src/lcd/menu/menu_media.cpp index 795ac2052b41..26f7a0517d31 100644 --- a/Marlin/src/lcd/menu/menu_media.cpp +++ b/Marlin/src/lcd/menu/menu_media.cpp @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfigPre.h" -#if BOTH(HAS_MARLINUI_MENU, HAS_MEDIA) +#if ALL(HAS_MARLINUI_MENU, HAS_MEDIA) #include "menu_item.h" #include "../../sd/cardreader.h" diff --git a/Marlin/src/lcd/menu/menu_mixer.cpp b/Marlin/src/lcd/menu/menu_mixer.cpp index 478792479cc1..21c18c820989 100644 --- a/Marlin/src/lcd/menu/menu_mixer.cpp +++ b/Marlin/src/lcd/menu/menu_mixer.cpp @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfigPre.h" -#if BOTH(HAS_MARLINUI_MENU, MIXING_EXTRUDER) +#if ALL(HAS_MARLINUI_MENU, MIXING_EXTRUDER) #include "menu_item.h" #include "menu_addon.h" @@ -170,7 +170,7 @@ void lcd_mixer_mix_edit() { #if CHANNEL_MIX_EDITING - LOOP_S_LE_N(n, 1, MIXING_STEPPERS) + for (uint8_t n = 1; n <= MIXING_STEPPERS; ++n) EDIT_ITEM_FAST_N(float42_52, n, MSG_MIX_COMPONENT_N, &mixer.collector[n-1], 0, 10); ACTION_ITEM(MSG_CYCLE_MIX, _lcd_mixer_cycle_mix); diff --git a/Marlin/src/lcd/menu/menu_mmu2.cpp b/Marlin/src/lcd/menu/menu_mmu2.cpp index ca3627ce1002..c9d163357bbd 100644 --- a/Marlin/src/lcd/menu/menu_mmu2.cpp +++ b/Marlin/src/lcd/menu/menu_mmu2.cpp @@ -22,7 +22,7 @@ #include "../../inc/MarlinConfig.h" -#if BOTH(HAS_MARLINUI_MENU, MMU2_MENUS) +#if ALL(HAS_MARLINUI_MENU, MMU2_MENUS) #include "../../MarlinCore.h" #include "../../feature/mmu/mmu2.h" diff --git a/Marlin/src/lcd/menu/menu_motion.cpp b/Marlin/src/lcd/menu/menu_motion.cpp index bab03db60627..67fcbdd8511e 100644 --- a/Marlin/src/lcd/menu/menu_motion.cpp +++ b/Marlin/src/lcd/menu/menu_motion.cpp @@ -119,7 +119,7 @@ void lcd_move_axis(const AxisEnum axis) { #endif // E_MANUAL -#if EITHER(PROBE_OFFSET_WIZARD, X_AXIS_TWIST_COMPENSATION) +#if ANY(PROBE_OFFSET_WIZARD, X_AXIS_TWIST_COMPENSATION) void _goto_manual_move_z(const_float_t scale) { ui.manual_move.menu_scale = scale; @@ -207,7 +207,7 @@ void menu_move() { START_MENU(); BACK_ITEM(MSG_MOTION); - #if BOTH(HAS_SOFTWARE_ENDSTOPS, SOFT_ENDSTOPS_MENU_ITEM) + #if ALL(HAS_SOFTWARE_ENDSTOPS, SOFT_ENDSTOPS_MENU_ITEM) EDIT_ITEM(bool, MSG_LCD_SOFT_ENDSTOPS, &soft_endstop._enabled); #endif @@ -530,7 +530,7 @@ void menu_motion() { // // Auto Z-Align // - #if EITHER(Z_STEPPER_AUTO_ALIGN, MECHANICAL_GANTRY_CALIBRATION) + #if ANY(Z_STEPPER_AUTO_ALIGN, MECHANICAL_GANTRY_CALIBRATION) GCODES_ITEM(MSG_AUTO_Z_ALIGN, F("G34")); #endif diff --git a/Marlin/src/lcd/menu/menu_password.cpp b/Marlin/src/lcd/menu/menu_password.cpp index b50194d60dc8..33d4231cd543 100644 --- a/Marlin/src/lcd/menu/menu_password.cpp +++ b/Marlin/src/lcd/menu/menu_password.cpp @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfigPre.h" -#if BOTH(HAS_MARLINUI_MENU, PASSWORD_FEATURE) +#if ALL(HAS_MARLINUI_MENU, PASSWORD_FEATURE) #include "../../feature/password/password.h" @@ -85,7 +85,7 @@ void Password::authentication_done() { // A single digit was completed void Password::digit_entered() { uint32_t multiplier = CAT(1e, PASSWORD_LENGTH); // 1e5 = 100000 - LOOP_LE_N(i, digit_no) multiplier /= 10; + for (uint8_t i = 0; i <= digit_no; ++i) multiplier /= 10; value_entry += editable.uint8 * multiplier; string[digit_no++] = '0' + editable.uint8; diff --git a/Marlin/src/lcd/menu/menu_probe_offset.cpp b/Marlin/src/lcd/menu/menu_probe_offset.cpp index 0dd118ed2230..82bf23ca842e 100644 --- a/Marlin/src/lcd/menu/menu_probe_offset.cpp +++ b/Marlin/src/lcd/menu/menu_probe_offset.cpp @@ -59,7 +59,7 @@ void probe_offset_wizard_menu() { STATIC_ITEM(MSG_MOVE_NOZZLE_TO_BED, SS_CENTER|SS_INVERT); STATIC_ITEM_F(F("Z"), SS_CENTER, ftostr42_52(current_position.z)); - STATIC_ITEM(MSG_ZPROBE_ZOFFSET, SS_LEFT, ftostr42_52(calculated_z_offset)); + STATIC_ITEM(MSG_ZPROBE_ZOFFSET, SS_FULL, ftostr42_52(calculated_z_offset)); SUBMENU(MSG_MOVE_1MM, []{ _goto_manual_move_z( 1); }); SUBMENU(MSG_MOVE_01MM, []{ _goto_manual_move_z( 0.1f); }); diff --git a/Marlin/src/lcd/menu/menu_temperature.cpp b/Marlin/src/lcd/menu/menu_temperature.cpp index c53459769076..710cef6468a1 100644 --- a/Marlin/src/lcd/menu/menu_temperature.cpp +++ b/Marlin/src/lcd/menu/menu_temperature.cpp @@ -35,7 +35,7 @@ #include "../../module/motion.h" #endif -#if EITHER(HAS_COOLER, LASER_COOLANT_FLOW_METER) +#if ANY(HAS_COOLER, LASER_COOLANT_FLOW_METER) #include "../../feature/cooler.h" #endif @@ -179,7 +179,7 @@ void menu_temperature() { #endif #if ENABLED(SINGLENOZZLE_STANDBY_TEMP) - LOOP_S_L_N(e, 1, EXTRUDERS) + for (uint8_t e = 1; e < EXTRUDERS; ++e) EDIT_ITEM_FAST_N(int3, e, MSG_NOZZLE_STANDBY, &thermalManager.singlenozzle_temp[e], 0, thermalManager.hotend_max_target(0)); #endif @@ -266,7 +266,7 @@ void menu_temperature() { // // Preheat for all Materials // - LOOP_L_N(m, PREHEAT_COUNT) { + for (uint8_t m = 0; m < PREHEAT_COUNT; ++m) { editable.int8 = m; #if HAS_MULTI_HOTEND || HAS_HEATED_BED SUBMENU_f(ui.get_preheat_label(m), MSG_PREHEAT_M, menu_preheat_m); @@ -293,7 +293,7 @@ void menu_temperature() { START_MENU(); BACK_ITEM(MSG_MAIN_MENU); - LOOP_L_N(m, PREHEAT_COUNT) { + for (uint8_t m = 0; m < PREHEAT_COUNT; ++m) { editable.int8 = m; #if HAS_MULTI_HOTEND || HAS_HEATED_BED SUBMENU_f(ui.get_preheat_label(m), MSG_PREHEAT_M, menu_preheat_m); diff --git a/Marlin/src/lcd/menu/menu_touch_screen.cpp b/Marlin/src/lcd/menu/menu_touch_screen.cpp index 130308dadffa..93380cb0e04a 100644 --- a/Marlin/src/lcd/menu/menu_touch_screen.cpp +++ b/Marlin/src/lcd/menu/menu_touch_screen.cpp @@ -22,7 +22,7 @@ #include "../../inc/MarlinConfigPre.h" -#if BOTH(HAS_MARLINUI_MENU, TOUCH_SCREEN_CALIBRATION) +#if ALL(HAS_MARLINUI_MENU, TOUCH_SCREEN_CALIBRATION) #include "menu_item.h" #include "../marlinui.h" diff --git a/Marlin/src/lcd/menu/menu_tramming_wizard.cpp b/Marlin/src/lcd/menu/menu_tramming_wizard.cpp index 8fb251c23862..e0f88ea1bb85 100644 --- a/Marlin/src/lcd/menu/menu_tramming_wizard.cpp +++ b/Marlin/src/lcd/menu/menu_tramming_wizard.cpp @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfigPre.h" -#if BOTH(HAS_MARLINUI_MENU, ASSISTED_TRAMMING_WIZARD) +#if ALL(HAS_MARLINUI_MENU, ASSISTED_TRAMMING_WIZARD) #include "menu_item.h" diff --git a/Marlin/src/lcd/menu/menu_tune.cpp b/Marlin/src/lcd/menu/menu_tune.cpp index 081b9f58a02d..c36ac013b86f 100644 --- a/Marlin/src/lcd/menu/menu_tune.cpp +++ b/Marlin/src/lcd/menu/menu_tune.cpp @@ -119,7 +119,7 @@ void menu_tune() { // // Manual bed leveling, Bed Z: // - #if BOTH(MESH_BED_LEVELING, LCD_BED_LEVELING) + #if ALL(MESH_BED_LEVELING, LCD_BED_LEVELING) EDIT_ITEM(float43, MSG_MESH_Z_OFFSET, &bedlevel.z_offset, -1, 1); #endif @@ -135,7 +135,7 @@ void menu_tune() { #endif #if ENABLED(SINGLENOZZLE_STANDBY_TEMP) - LOOP_S_L_N(e, 1, EXTRUDERS) + for (uint8_t e = 1; e < EXTRUDERS; ++e) EDIT_ITEM_FAST_N(int3, e, MSG_NOZZLE_STANDBY, &thermalManager.singlenozzle_temp[e], 0, thermalManager.hotend_max_target(0)); #endif diff --git a/Marlin/src/lcd/menu/menu_ubl.cpp b/Marlin/src/lcd/menu/menu_ubl.cpp index d6f42faa5558..c8fd33d26df0 100644 --- a/Marlin/src/lcd/menu/menu_ubl.cpp +++ b/Marlin/src/lcd/menu/menu_ubl.cpp @@ -26,7 +26,7 @@ #include "../../inc/MarlinConfigPre.h" -#if BOTH(HAS_MARLINUI_MENU, AUTO_BED_LEVELING_UBL) +#if ALL(HAS_MARLINUI_MENU, AUTO_BED_LEVELING_UBL) #include "menu_item.h" #include "../../gcode/gcode.h" diff --git a/Marlin/src/lcd/menu/menu_x_twist.cpp b/Marlin/src/lcd/menu/menu_x_twist.cpp index 86ef3be7b999..56872b73ee25 100644 --- a/Marlin/src/lcd/menu/menu_x_twist.cpp +++ b/Marlin/src/lcd/menu/menu_x_twist.cpp @@ -150,12 +150,12 @@ void xatc_wizard_goto_next_point() { else { // Compute the z-offset by averaging the values found with this wizard z_offset = 0; - LOOP_L_N(i, XATC_MAX_POINTS) z_offset += xatc.z_offset[i]; + for (uint8_t i = 0; i < XATC_MAX_POINTS; ++i) z_offset += xatc.z_offset[i]; z_offset /= XATC_MAX_POINTS; // Subtract the average from the values found with this wizard. // This way they are indipendent from the z-offset - LOOP_L_N(i, XATC_MAX_POINTS) xatc.z_offset[i] -= z_offset; + for (uint8_t i = 0; i < XATC_MAX_POINTS; ++i) xatc.z_offset[i] -= z_offset; ui.goto_screen(xatc_wizard_update_z_offset); } @@ -170,7 +170,7 @@ void xatc_wizard_homing_done() { MenuItem_static::draw(1, GET_TEXT_F(MSG_LEVEL_BED_WAITING)); // Color UI needs a control to detect a touch - #if BOTH(TOUCH_SCREEN, HAS_GRAPHICAL_TFT) + #if ALL(TOUCH_SCREEN, HAS_GRAPHICAL_TFT) touch.add_control(CLICK, 0, 0, TFT_WIDTH, TFT_HEIGHT); #endif } diff --git a/Marlin/src/lcd/tft/canvas.cpp b/Marlin/src/lcd/tft/canvas.cpp index 3fb500e8e21b..ac3a2d76c389 100644 --- a/Marlin/src/lcd/tft/canvas.cpp +++ b/Marlin/src/lcd/tft/canvas.cpp @@ -26,31 +26,31 @@ #include "canvas.h" -uint16_t CANVAS::width, CANVAS::height; -uint16_t CANVAS::startLine, CANVAS::endLine; -uint16_t CANVAS::background_color; -uint16_t *CANVAS::buffer = TFT::buffer; - -void CANVAS::New(uint16_t x, uint16_t y, uint16_t width, uint16_t height) { - CANVAS::width = width; - CANVAS::height = height; +uint16_t Canvas::width, Canvas::height; +uint16_t Canvas::startLine, Canvas::endLine; +uint16_t Canvas::background_color; +uint16_t *Canvas::buffer = TFT::buffer; + +void Canvas::instantiate(uint16_t x, uint16_t y, uint16_t width, uint16_t height) { + Canvas::width = width; + Canvas::height = height; startLine = 0; endLine = 0; tft.set_window(x, y, x + width - 1, y + height - 1); } -void CANVAS::Continue() { +void Canvas::next() { startLine = endLine; endLine = TFT_BUFFER_SIZE < width * (height - startLine) ? startLine + TFT_BUFFER_SIZE / width : height; } -bool CANVAS::ToScreen() { +bool Canvas::toScreen() { tft.write_sequence(buffer, width * (endLine - startLine)); return endLine == height; } -void CANVAS::SetBackground(uint16_t color) { +void Canvas::setBackground(uint16_t color) { /* TODO: test and optimize performance */ /* uint32_t count = (endLine - startLine) * width; @@ -67,35 +67,35 @@ void CANVAS::SetBackground(uint16_t color) { extern uint16_t gradient(uint16_t colorA, uint16_t colorB, uint16_t factor); -void CANVAS::AddText(uint16_t x, uint16_t y, uint16_t color, uint16_t *string, uint16_t maxWidth) { - if (endLine < y || startLine > y + GetFontHeight()) return; +void Canvas::addText(uint16_t x, uint16_t y, uint16_t color, uint16_t *string, uint16_t maxWidth) { + if (endLine < y || startLine > y + getFontHeight()) return; if (maxWidth == 0) maxWidth = width - x; uint16_t colors[16]; uint16_t stringWidth = 0; - if (GetFontType() == FONT_MARLIN_GLYPHS_2BPP) { + if (getFontType() == FONT_MARLIN_GLYPHS_2BPP) { for (uint8_t i = 0; i < 3; i++) { colors[i] = gradient(ENDIAN_COLOR(color), ENDIAN_COLOR(background_color), ((i+1) << 8) / 3); colors[i] = ENDIAN_COLOR(colors[i]); } } for (uint16_t i = 0 ; *(string + i) ; i++) { - glyph_t *glyph = Glyph(string + i); - if (stringWidth + glyph->BBXWidth > maxWidth) break; - switch (GetFontType()) { + glyph_t *pGlyph = glyph(string + i); + if (stringWidth + pGlyph->BBXWidth > maxWidth) break; + switch (getFontType()) { case FONT_MARLIN_GLYPHS_1BPP: - AddImage(x + stringWidth + glyph->BBXOffsetX, y + GetFontAscent() - glyph->BBXHeight - glyph->BBXOffsetY, glyph->BBXWidth, glyph->BBXHeight, GREYSCALE1, ((uint8_t *)glyph) + sizeof(glyph_t), &color); + addImage(x + stringWidth + pGlyph->BBXOffsetX, y + getFontAscent() - pGlyph->BBXHeight - pGlyph->BBXOffsetY, pGlyph->BBXWidth, pGlyph->BBXHeight, GREYSCALE1, ((uint8_t *)pGlyph) + sizeof(glyph_t), &color); break; case FONT_MARLIN_GLYPHS_2BPP: - AddImage(x + stringWidth + glyph->BBXOffsetX, y + GetFontAscent() - glyph->BBXHeight - glyph->BBXOffsetY, glyph->BBXWidth, glyph->BBXHeight, GREYSCALE2, ((uint8_t *)glyph) + sizeof(glyph_t), colors); + addImage(x + stringWidth + pGlyph->BBXOffsetX, y + getFontAscent() - pGlyph->BBXHeight - pGlyph->BBXOffsetY, pGlyph->BBXWidth, pGlyph->BBXHeight, GREYSCALE2, ((uint8_t *)pGlyph) + sizeof(glyph_t), colors); break; } - stringWidth += glyph->DWidth; + stringWidth += pGlyph->DWidth; } } -void CANVAS::AddImage(int16_t x, int16_t y, MarlinImage image, uint16_t *colors) { +void Canvas::addImage(int16_t x, int16_t y, MarlinImage image, uint16_t *colors) { uint16_t *data = (uint16_t *)Images[image].data; if (!data) return; @@ -104,7 +104,7 @@ void CANVAS::AddImage(int16_t x, int16_t y, MarlinImage image, uint16_t *colors) colorMode_t color_mode = Images[image].colorMode; if (color_mode != HIGHCOLOR) - return AddImage(x, y, image_width, image_height, color_mode, (uint8_t *)data, colors); + return addImage(x, y, image_width, image_height, color_mode, (uint8_t *)data, colors); // HIGHCOLOR - 16 bits per pixel @@ -123,7 +123,7 @@ void CANVAS::AddImage(int16_t x, int16_t y, MarlinImage image, uint16_t *colors) } } -void CANVAS::AddImage(int16_t x, int16_t y, uint8_t image_width, uint8_t image_height, colorMode_t color_mode, uint8_t *data, uint16_t *colors) { +void Canvas::addImage(int16_t x, int16_t y, uint8_t image_width, uint8_t image_height, colorMode_t color_mode, uint8_t *data, uint16_t *colors) { uint8_t bitsPerPixel; switch (color_mode) { case GREYSCALE1: bitsPerPixel = 1; break; @@ -161,7 +161,7 @@ void CANVAS::AddImage(int16_t x, int16_t y, uint8_t image_width, uint8_t image_h } } -void CANVAS::AddRectangle(uint16_t x, uint16_t y, uint16_t rectangleWidth, uint16_t rectangleHeight, uint16_t color) { +void Canvas::addRect(uint16_t x, uint16_t y, uint16_t rectangleWidth, uint16_t rectangleHeight, uint16_t color) { if (endLine < y || startLine > y + rectangleHeight) return; for (uint16_t i = 0; i < rectangleHeight; i++) { @@ -180,7 +180,7 @@ void CANVAS::AddRectangle(uint16_t x, uint16_t y, uint16_t rectangleWidth, uint1 } } -void CANVAS::AddBar(uint16_t x, uint16_t y, uint16_t barWidth, uint16_t barHeight, uint16_t color) { +void Canvas::addBar(uint16_t x, uint16_t y, uint16_t barWidth, uint16_t barHeight, uint16_t color) { if (endLine < y || startLine > y + barHeight) return; for (uint16_t i = 0; i < barHeight; i++) { @@ -192,6 +192,6 @@ void CANVAS::AddBar(uint16_t x, uint16_t y, uint16_t barWidth, uint16_t barHeigh } } -CANVAS Canvas; +Canvas tftCanvas; #endif // HAS_GRAPHICAL_TFT diff --git a/Marlin/src/lcd/tft/canvas.h b/Marlin/src/lcd/tft/canvas.h index 1c9c7bb13a27..d271ae7af3f7 100644 --- a/Marlin/src/lcd/tft/canvas.h +++ b/Marlin/src/lcd/tft/canvas.h @@ -28,32 +28,32 @@ #include "../../inc/MarlinConfig.h" -class CANVAS { +class Canvas { private: static uint16_t background_color; static uint16_t width, height; static uint16_t startLine, endLine; static uint16_t *buffer; - inline static glyph_t *Glyph(uint16_t *character) { return TFT_String::glyph(character); } - inline static uint16_t GetFontType() { return TFT_String::font_type(); } - inline static uint16_t GetFontAscent() { return TFT_String::font_ascent(); } - inline static uint16_t GetFontHeight() { return TFT_String::font_height(); } + inline static glyph_t *glyph(uint16_t *character) { return TFT_String::glyph(character); } + inline static uint16_t getFontType() { return TFT_String::font_type(); } + inline static uint16_t getFontAscent() { return TFT_String::font_ascent(); } + inline static uint16_t getFontHeight() { return TFT_String::font_height(); } - static void AddImage(int16_t x, int16_t y, uint8_t image_width, uint8_t image_height, colorMode_t color_mode, uint8_t *data, uint16_t *colors); - static void AddImage(uint16_t x, uint16_t y, uint16_t imageWidth, uint16_t imageHeight, uint16_t color, uint16_t bgColor, uint8_t *image); + static void addImage(int16_t x, int16_t y, uint8_t image_width, uint8_t image_height, colorMode_t color_mode, uint8_t *data, uint16_t *colors); + static void addImage(uint16_t x, uint16_t y, uint16_t imageWidth, uint16_t imageHeight, uint16_t color, uint16_t bgColor, uint8_t *image); public: - static void New(uint16_t x, uint16_t y, uint16_t width, uint16_t height); - static void Continue(); - static bool ToScreen(); + static void instantiate(uint16_t x, uint16_t y, uint16_t width, uint16_t height); + static void next(); + static bool toScreen(); - static void SetBackground(uint16_t color); - static void AddText(uint16_t x, uint16_t y, uint16_t color, uint16_t *string, uint16_t maxWidth); - static void AddImage(int16_t x, int16_t y, MarlinImage image, uint16_t *colors); + static void setBackground(uint16_t color); + static void addText(uint16_t x, uint16_t y, uint16_t color, uint16_t *string, uint16_t maxWidth); + static void addImage(int16_t x, int16_t y, MarlinImage image, uint16_t *colors); - static void AddRectangle(uint16_t x, uint16_t y, uint16_t width, uint16_t height, uint16_t color); - static void AddBar(uint16_t x, uint16_t y, uint16_t width, uint16_t height, uint16_t color); + static void addRect(uint16_t x, uint16_t y, uint16_t width, uint16_t height, uint16_t color); + static void addBar(uint16_t x, uint16_t y, uint16_t width, uint16_t height, uint16_t color); }; -extern CANVAS Canvas; +extern Canvas tftCanvas; diff --git a/Marlin/src/lcd/tft/tft_queue.cpp b/Marlin/src/lcd/tft/tft_queue.cpp index 1cec4a715947..fb96a440eaa8 100644 --- a/Marlin/src/lcd/tft/tft_queue.cpp +++ b/Marlin/src/lcd/tft/tft_queue.cpp @@ -107,17 +107,17 @@ void TFT_Queue::canvas(queueTask_t *task) { if (task->state == TASK_STATE_READY) { task->state = TASK_STATE_IN_PROGRESS; - Canvas.New(task_parameters->x, task_parameters->y, task_parameters->width, task_parameters->height); + tftCanvas.instantiate(task_parameters->x, task_parameters->y, task_parameters->width, task_parameters->height); } - Canvas.Continue(); + tftCanvas.next(); for (i = 0; i < task_parameters->count; i++) { switch (*item) { case CANVAS_SET_BACKGROUND: - Canvas.SetBackground(((parametersCanvasBackground_t *)item)->color); + tftCanvas.setBackground(((parametersCanvasBackground_t *)item)->color); break; case CANVAS_ADD_TEXT: - Canvas.AddText(((parametersCanvasText_t *)item)->x, ((parametersCanvasText_t *)item)->y, ((parametersCanvasText_t *)item)->color, (uint16_t*)(item + sizeof(parametersCanvasText_t)), ((parametersCanvasText_t *)item)->maxWidth); + tftCanvas.addText(((parametersCanvasText_t *)item)->x, ((parametersCanvasText_t *)item)->y, ((parametersCanvasText_t *)item)->color, (uint16_t*)(item + sizeof(parametersCanvasText_t)), ((parametersCanvasText_t *)item)->maxWidth); break; case CANVAS_ADD_IMAGE: @@ -126,20 +126,20 @@ void TFT_Queue::canvas(queueTask_t *task) { image = ((parametersCanvasImage_t *)item)->image; colors = (uint16_t *)(item + sizeof(parametersCanvasImage_t)); - Canvas.AddImage(((parametersCanvasImage_t *)item)->x, ((parametersCanvasImage_t *)item)->y, image, colors); + tftCanvas.addImage(((parametersCanvasImage_t *)item)->x, ((parametersCanvasImage_t *)item)->y, image, colors); break; case CANVAS_ADD_BAR: - Canvas.AddBar(((parametersCanvasBar_t *)item)->x, ((parametersCanvasBar_t *)item)->y, ((parametersCanvasBar_t *)item)->width, ((parametersCanvasBar_t *)item)->height, ((parametersCanvasBar_t *)item)->color); + tftCanvas.addBar(((parametersCanvasBar_t *)item)->x, ((parametersCanvasBar_t *)item)->y, ((parametersCanvasBar_t *)item)->width, ((parametersCanvasBar_t *)item)->height, ((parametersCanvasBar_t *)item)->color); break; - case CANVAS_ADD_RECTANGLE: - Canvas.AddRectangle(((parametersCanvasRectangle_t *)item)->x, ((parametersCanvasRectangle_t *)item)->y, ((parametersCanvasRectangle_t *)item)->width, ((parametersCanvasRectangle_t *)item)->height, ((parametersCanvasRectangle_t *)item)->color); + case CANVAS_ADD_RECT: + tftCanvas.addRect(((parametersCanvasRectangle_t *)item)->x, ((parametersCanvasRectangle_t *)item)->y, ((parametersCanvasRectangle_t *)item)->width, ((parametersCanvasRectangle_t *)item)->height, ((parametersCanvasRectangle_t *)item)->color); break; } item = ((parametersCanvasBackground_t *)item)->nextParameter; } - if (Canvas.ToScreen()) task->state = TASK_STATE_COMPLETED; + if (tftCanvas.toScreen()) task->state = TASK_STATE_COMPLETED; } void TFT_Queue::fill(uint16_t x, uint16_t y, uint16_t width, uint16_t height, uint16_t color) { @@ -265,7 +265,7 @@ void TFT_Queue::add_text(uint16_t x, uint16_t y, uint16_t color, const uint16_t end_of_queue += sizeof(parametersCanvasText_t); uint16_t *character = (uint16_t *)end_of_queue; - /* TODO: Deal with maxWidth */ + // TODO: Deal with maxWidth while ((*character++ = *pointer++) != 0); end_of_queue = (uint8_t *)character; @@ -373,7 +373,7 @@ void TFT_Queue::add_rectangle(uint16_t x, uint16_t y, uint16_t width, uint16_t h parametersCanvasRectangle_t *parameters = (parametersCanvasRectangle_t *)end_of_queue; last_parameter = end_of_queue; - parameters->type = CANVAS_ADD_RECTANGLE; + parameters->type = CANVAS_ADD_RECT; parameters->x = x; parameters->y = y; parameters->width = width; diff --git a/Marlin/src/lcd/tft/tft_queue.h b/Marlin/src/lcd/tft/tft_queue.h index ed929166cb98..59a13dd43a46 100644 --- a/Marlin/src/lcd/tft/tft_queue.h +++ b/Marlin/src/lcd/tft/tft_queue.h @@ -47,7 +47,7 @@ enum CanvasSubtype : uint8_t { CANVAS_ADD_TEXT, CANVAS_ADD_IMAGE, CANVAS_ADD_BAR, - CANVAS_ADD_RECTANGLE, + CANVAS_ADD_RECT, }; typedef struct __attribute__((__packed__)) { diff --git a/Marlin/src/lcd/tft/ui_1024x600.cpp b/Marlin/src/lcd/tft/ui_1024x600.cpp index 460f3a345b55..e43ccf74500a 100644 --- a/Marlin/src/lcd/tft/ui_1024x600.cpp +++ b/Marlin/src/lcd/tft/ui_1024x600.cpp @@ -36,7 +36,7 @@ #include "../../module/planner.h" #include "../../module/motion.h" -#if DISABLED(LCD_PROGRESS_BAR) && BOTH(FILAMENT_LCD_DISPLAY, HAS_MEDIA) +#if DISABLED(LCD_PROGRESS_BAR) && ALL(FILAMENT_LCD_DISPLAY, HAS_MEDIA) #include "../../feature/filwidth.h" #include "../../gcode/parser.h" #endif @@ -627,7 +627,7 @@ struct { static void quick_feedback() { #if HAS_CHIRP ui.chirp(); // Buzz and wait. Is the delay needed for buttons to settle? - #if BOTH(HAS_MARLINUI_MENU, HAS_BEEPER) + #if ALL(HAS_MARLINUI_MENU, HAS_BEEPER) for (int8_t i = 5; i--;) { buzzer.tick(); delay(2); } #elif HAS_MARLINUI_MENU delay(10); @@ -837,7 +837,7 @@ static void moveAxis(const AxisEnum axis, const int8_t direction) { } #endif -#if BOTH(HAS_BED_PROBE, TOUCH_SCREEN) +#if ALL(HAS_BED_PROBE, TOUCH_SCREEN) static void z_select() { motionAxisState.z_selection *= -1; quick_feedback(); @@ -936,7 +936,7 @@ void MarlinUI::move_axis_screen() { motionAxisState.zTypePos.x = x; motionAxisState.zTypePos.y = y; TERN_(HAS_Z_AXIS, drawCurZSelection()); - #if BOTH(HAS_BED_PROBE, TOUCH_SCREEN) + #if ALL(HAS_BED_PROBE, TOUCH_SCREEN) if (!busy) touch.add_control(BUTTON, x, y, BTN_WIDTH, 34 * 2, (intptr_t)z_select); #endif diff --git a/Marlin/src/lcd/tft/ui_320x240.cpp b/Marlin/src/lcd/tft/ui_320x240.cpp index c2918711f47b..0d145f10eb9d 100644 --- a/Marlin/src/lcd/tft/ui_320x240.cpp +++ b/Marlin/src/lcd/tft/ui_320x240.cpp @@ -36,7 +36,7 @@ #include "../../module/planner.h" #include "../../module/motion.h" -#if DISABLED(LCD_PROGRESS_BAR) && BOTH(FILAMENT_LCD_DISPLAY, HAS_MEDIA) +#if DISABLED(LCD_PROGRESS_BAR) && ALL(FILAMENT_LCD_DISPLAY, HAS_MEDIA) #include "../../feature/filwidth.h" #include "../../gcode/parser.h" #endif @@ -708,7 +708,7 @@ struct { static void quick_feedback() { #if HAS_CHIRP ui.chirp(); // Buzz and wait. Is the delay needed for buttons to settle? - #if BOTH(HAS_MARLINUI_MENU, HAS_BEEPER) + #if ALL(HAS_MARLINUI_MENU, HAS_BEEPER) for (int8_t i = 5; i--;) { buzzer.tick(); delay(2); } #elif HAS_MARLINUI_MENU delay(10); @@ -1029,7 +1029,7 @@ void MarlinUI::move_axis_screen() { drawBtn(zplus_x, y, "X+", (intptr_t)x_plus, imgRight, X_BTN_COLOR, !busy); - #if BOTH(HAS_BED_PROBE, TOUCH_SCREEN) + #if ALL(HAS_BED_PROBE, TOUCH_SCREEN) if (!busy) touch.add_control(BUTTON, x, y, BTN_WIDTH, 34 * 2, (intptr_t)z_select); #endif @@ -1129,7 +1129,7 @@ void MarlinUI::move_axis_screen() { motionAxisState.zTypePos.x = x; motionAxisState.zTypePos.y = y; TERN_(HAS_Z_AXIS, drawCurZSelection()); - #if BOTH(HAS_BED_PROBE, TOUCH_SCREEN) + #if ALL(HAS_BED_PROBE, TOUCH_SCREEN) if (!busy) touch.add_control(BUTTON, x, y, BTN_WIDTH, 34 * 2, (intptr_t)z_select); #endif diff --git a/Marlin/src/lcd/tft/ui_480x320.cpp b/Marlin/src/lcd/tft/ui_480x320.cpp index e1ddfe5e1ab1..75ec50adc284 100644 --- a/Marlin/src/lcd/tft/ui_480x320.cpp +++ b/Marlin/src/lcd/tft/ui_480x320.cpp @@ -36,7 +36,7 @@ #include "../../module/planner.h" #include "../../module/motion.h" -#if DISABLED(LCD_PROGRESS_BAR) && BOTH(FILAMENT_LCD_DISPLAY, HAS_MEDIA) +#if DISABLED(LCD_PROGRESS_BAR) && ALL(FILAMENT_LCD_DISPLAY, HAS_MEDIA) #include "../../feature/filwidth.h" #include "../../gcode/parser.h" #endif @@ -627,7 +627,7 @@ struct { static void quick_feedback() { #if HAS_CHIRP ui.chirp(); // Buzz and wait. Is the delay needed for buttons to settle? - #if BOTH(HAS_MARLINUI_MENU, HAS_BEEPER) + #if ALL(HAS_MARLINUI_MENU, HAS_BEEPER) for (int8_t i = 5; i--;) { buzzer.tick(); delay(2); } #elif HAS_MARLINUI_MENU delay(10); @@ -837,7 +837,7 @@ static void moveAxis(const AxisEnum axis, const int8_t direction) { } #endif // TOUCH_SCREEN -#if BOTH(HAS_BED_PROBE, TOUCH_SCREEN) +#if ALL(HAS_BED_PROBE, TOUCH_SCREEN) static void z_select() { motionAxisState.z_selection *= -1; quick_feedback(); @@ -940,7 +940,7 @@ void MarlinUI::move_axis_screen() { motionAxisState.zTypePos.x = x; motionAxisState.zTypePos.y = y; TERN_(HAS_Z_AXIS, drawCurZSelection()); - #if BOTH(HAS_BED_PROBE, TOUCH_SCREEN) + #if ALL(HAS_BED_PROBE, TOUCH_SCREEN) if (!busy) touch.add_control(BUTTON, x, y, BTN_WIDTH, 34 * 2, (intptr_t)z_select); #endif diff --git a/Marlin/src/libs/BL24CXX.cpp b/Marlin/src/libs/BL24CXX.cpp index 4b5a23e4c550..adfdc1387cf2 100644 --- a/Marlin/src/libs/BL24CXX.cpp +++ b/Marlin/src/libs/BL24CXX.cpp @@ -141,7 +141,7 @@ void IIC::nAck() { void IIC::send_byte(uint8_t txd) { SDA_OUT(); IIC_SCL_0(); // Pull down the clock to start data transmission - LOOP_L_N(t, 8) { + for (uint8_t t = 0; t < 8; ++t) { // IIC_SDA = (txd & 0x80) >> 7; if (txd & 0x80) IIC_SDA_1(); else IIC_SDA_0(); txd <<= 1; @@ -157,7 +157,7 @@ void IIC::send_byte(uint8_t txd) { uint8_t IIC::read_byte(unsigned char ack_chr) { unsigned char receive = 0; SDA_IN(); // SDA is set as input - LOOP_L_N(i, 8) { + for (uint8_t i = 0; i < 8; ++i) { IIC_SCL_0(); delay_us(2); IIC_SCL_1(); @@ -228,7 +228,7 @@ void BL24CXX::writeOneByte(uint16_t WriteAddr, uint8_t DataToWrite) { // DataToWrite: the first address of the data array // Len: The length of the data to be written 2, 4 void BL24CXX::writeLenByte(uint16_t WriteAddr, uint32_t DataToWrite, uint8_t Len) { - LOOP_L_N(t, Len) + for (uint8_t t = 0; t < Len; ++t) writeOneByte(WriteAddr + t, (DataToWrite >> (8 * t)) & 0xFF); } @@ -239,7 +239,7 @@ void BL24CXX::writeLenByte(uint16_t WriteAddr, uint32_t DataToWrite, uint8_t Len // Len: The length of the data to be read 2,4 uint32_t BL24CXX::readLenByte(uint16_t ReadAddr, uint8_t Len) { uint32_t temp = 0; - LOOP_L_N(t, Len) { + for (uint8_t t = 0; t < Len; ++t) { temp <<= 8; temp += readOneByte(ReadAddr + Len - t - 1); } diff --git a/Marlin/src/libs/duration_t.h b/Marlin/src/libs/duration_t.h index 69a648441feb..e45ce01496c7 100644 --- a/Marlin/src/libs/duration_t.h +++ b/Marlin/src/libs/duration_t.h @@ -67,7 +67,7 @@ struct duration_t { } /** - * @brief Formats the duration as years + * @brief Format the duration as years * @return The number of years */ inline uint8_t year() const { @@ -75,7 +75,7 @@ struct duration_t { } /** - * @brief Formats the duration as days + * @brief Format the duration as days * @return The number of days */ inline uint16_t day() const { @@ -83,7 +83,7 @@ struct duration_t { } /** - * @brief Formats the duration as hours + * @brief Format the duration as hours * @return The number of hours */ inline uint32_t hour() const { @@ -91,7 +91,7 @@ struct duration_t { } /** - * @brief Formats the duration as minutes + * @brief Format the duration as minutes * @return The number of minutes */ inline uint32_t minute() const { @@ -99,7 +99,7 @@ struct duration_t { } /** - * @brief Formats the duration as seconds + * @brief Format the duration as seconds * @return The number of seconds */ inline uint32_t second() const { @@ -112,7 +112,7 @@ struct duration_t { #endif /** - * @brief Formats the duration as a string + * @brief Format the duration as a string * @details String will be formatted using a "full" representation of duration * * @param buffer The array pointed to must be able to accommodate 22 bytes @@ -142,7 +142,7 @@ struct duration_t { } /** - * @brief Formats the duration as a string + * @brief Format the duration as a string * @details String will be formatted using a "digital" representation of duration * * @param buffer The array pointed to must be able to accommodate 10 bytes diff --git a/Marlin/src/libs/nozzle.cpp b/Marlin/src/libs/nozzle.cpp index e675c53cb106..10ebd71efd9a 100644 --- a/Marlin/src/libs/nozzle.cpp +++ b/Marlin/src/libs/nozzle.cpp @@ -22,7 +22,7 @@ #include "../inc/MarlinConfig.h" -#if EITHER(NOZZLE_CLEAN_FEATURE, NOZZLE_PARK_FEATURE) +#if ANY(NOZZLE_CLEAN_FEATURE, NOZZLE_PARK_FEATURE) #include "nozzle.h" @@ -63,7 +63,7 @@ Nozzle nozzle; #endif // Start the stroke pattern - LOOP_L_N(i, strokes >> 1) { + for (uint8_t i = 0; i < strokes >> 1; ++i) { #if ENABLED(NOZZLE_CLEAN_NO_Y) do_blocking_move_to_x(end.x); do_blocking_move_to_x(start.x); @@ -105,7 +105,7 @@ Nozzle nozzle; const bool horiz = ABS(diff.x) >= ABS(diff.y); // Do a horizontal wipe? const float P = (horiz ? diff.x : diff.y) / zigs; // Period of each zig / zag const xyz_pos_t *side; - LOOP_L_N(j, strokes) { + for (uint8_t j = 0; j < strokes; ++j) { for (int8_t i = 0; i < zigs; i++) { side = (i & 1) ? &end : &start; if (horiz) @@ -143,8 +143,8 @@ Nozzle nozzle; #endif TERN(NOZZLE_CLEAN_NO_Z, do_blocking_move_to_xy, do_blocking_move_to)(start); - LOOP_L_N(s, strokes) - LOOP_L_N(i, NOZZLE_CLEAN_CIRCLE_FN) + for (uint8_t s = 0; s < strokes; ++s) + for (uint8_t i = 0; i < NOZZLE_CLEAN_CIRCLE_FN; ++i) do_blocking_move_to_xy( middle.x + sin((RADIANS(360) / NOZZLE_CLEAN_CIRCLE_FN) * i) * radius, middle.y + cos((RADIANS(360) / NOZZLE_CLEAN_CIRCLE_FN) * i) * radius @@ -170,7 +170,7 @@ Nozzle nozzle; xyz_pos_t middle[HOTENDS] = NOZZLE_CLEAN_CIRCLE_MIDDLE; #endif - const uint8_t arrPos = EITHER(SINGLENOZZLE, MIXING_EXTRUDER) ? 0 : active_extruder; + const uint8_t arrPos = ANY(SINGLENOZZLE, MIXING_EXTRUDER) ? 0 : active_extruder; switch (pattern) { #if DISABLED(NOZZLE_CLEAN_PATTERN_LINE) diff --git a/Marlin/src/libs/numtostr.cpp b/Marlin/src/libs/numtostr.cpp index 2938229a7ae1..e27373263556 100644 --- a/Marlin/src/libs/numtostr.cpp +++ b/Marlin/src/libs/numtostr.cpp @@ -25,14 +25,25 @@ #include "../inc/MarlinConfigPre.h" #include "../core/utility.h" -char conv[9] = { 0 }; +constexpr char DIGIT(const uint8_t n) { return '0' + n; } + +template +constexpr char DIGIMOD(const T1 n, const T2 f) { return DIGIT((n / f) % 10); } + +template +constexpr char RJDIGIT(const T1 n, const T2 f) { return (n >= (T1)f ? DIGIMOD(n, f) : ' '); } + +template +constexpr char MINUSOR(T &n, const char alt) { return (n >= 0) ? alt : (n = -n) ? '-' : '-'; } -#define DIGIT(n) ('0' + (n)) -#define DIGIMOD(n, f) DIGIT(((n)/(f)) % 10) -#define RJDIGIT(n, f) ((n) >= (f) ? DIGIMOD(n, f) : ' ') -#define MINUSOR(n, alt) (n >= 0 ? (alt) : (n = -n, '-')) -#define INTFLOAT(V,N) (((V) * 10 * pow(10, N) + ((V) < 0 ? -5: 5)) / 10) // pow10? -#define UINTFLOAT(V,N) INTFLOAT((V) < 0 ? -(V) : (V), N) +constexpr long INTFLOAT(const float V, const int N) { + return long((V * 10.0f * pow(10.0f, N) + (V < 0.0f ? -5.0f : 5.0f)) / 10.0f); +} +constexpr long UINTFLOAT(const float V, const int N) { + return INTFLOAT(V < 0.0f ? -V : V, N); +} + +char conv[9] = { 0 }; // Format uint8_t (0-100) as rj string with 123% / _12% / __1% format const char* pcttostrpctrj(const uint8_t i) { diff --git a/Marlin/src/libs/vector_3.cpp b/Marlin/src/libs/vector_3.cpp index 02945fe6871a..a222b5cc2e7e 100644 --- a/Marlin/src/libs/vector_3.cpp +++ b/Marlin/src/libs/vector_3.cpp @@ -93,8 +93,8 @@ void matrix_3x3::apply_rotation_xyz(float &_x, float &_y, float &_z) { // Reset to identity. No rotate or translate. void matrix_3x3::set_to_identity() { - LOOP_L_N(i, 3) - LOOP_L_N(j, 3) + for (uint8_t i = 0; i < 3; ++i) + for (uint8_t j = 0; j < 3; ++j) vectors[i][j] = float(i == j); } @@ -131,16 +131,16 @@ matrix_3x3 matrix_3x3::create_look_at(const vector_3 &target) { // Get a transposed copy of the matrix matrix_3x3 matrix_3x3::transpose(const matrix_3x3 &original) { matrix_3x3 new_matrix; - LOOP_L_N(i, 3) - LOOP_L_N(j, 3) + for (uint8_t i = 0; i < 3; ++i) + for (uint8_t j = 0; j < 3; ++j) new_matrix.vectors[i][j] = original.vectors[j][i]; return new_matrix; } void matrix_3x3::debug(FSTR_P const title) { if (title) SERIAL_ECHOLNF(title); - LOOP_L_N(i, 3) { - LOOP_L_N(j, 3) { + for (uint8_t i = 0; i < 3; ++i) { + for (uint8_t j = 0; j < 3; ++j) { serial_offset(vectors[i][j], 2); SERIAL_CHAR(' '); } diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index a22c4f03817b..3031e7d69489 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -31,7 +31,7 @@ #include "temperature.h" #include "../lcd/marlinui.h" -#define DEBUG_OUT BOTH(USE_SENSORLESS, DEBUG_LEVELING_FEATURE) +#define DEBUG_OUT ALL(USE_SENSORLESS, DEBUG_LEVELING_FEATURE) #include "../core/debug_out.h" #if ENABLED(ENDSTOP_INTERRUPTS_FEATURE) @@ -480,7 +480,7 @@ void __O2 Endstops::report_states() { #endif #if MULTI_FILAMENT_SENSOR #define _CASE_RUNOUT(N) case N: pin = FIL_RUNOUT##N##_PIN; state = FIL_RUNOUT##N##_STATE; break; - LOOP_S_LE_N(i, 1, NUM_RUNOUT_SENSORS) { + for (uint8_t i = 1; i <= NUM_RUNOUT_SENSORS; ++i) { pin_t pin; uint8_t state; switch (i) { @@ -1136,11 +1136,11 @@ void Endstops::update() { void Endstops::clear_endstop_state() { TERN_(X_SPI_SENSORLESS, CBI(live_state, X_ENDSTOP)); - #if BOTH(X_SPI_SENSORLESS, X_DUAL_ENDSTOPS) + #if ALL(X_SPI_SENSORLESS, X_DUAL_ENDSTOPS) CBI(live_state, X2_ENDSTOP); #endif TERN_(Y_SPI_SENSORLESS, CBI(live_state, Y_ENDSTOP)); - #if BOTH(Y_SPI_SENSORLESS, Y_DUAL_ENDSTOPS) + #if ALL(Y_SPI_SENSORLESS, Y_DUAL_ENDSTOPS) CBI(live_state, Y2_ENDSTOP); #endif TERN_(Z_SPI_SENSORLESS, CBI(live_state, Z_ENDSTOP)); diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index e6df20a99843..d7b6d76fae8d 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -257,7 +257,7 @@ void report_current_position_projected() { AutoReporter position_auto_reporter; #endif -#if EITHER(FULL_REPORT_TO_HOST_FEATURE, REALTIME_REPORTING_COMMANDS) +#if ANY(FULL_REPORT_TO_HOST_FEATURE, REALTIME_REPORTING_COMMANDS) M_StateEnum M_State_grbl = M_INIT; @@ -941,7 +941,7 @@ void restore_feedrate_and_scaling() { if (TERN0(DELTA, !all_axes_homed())) return; - #if BOTH(HAS_HOTEND_OFFSET, DELTA) + #if ALL(HAS_HOTEND_OFFSET, DELTA) // The effector center position will be the target minus the hotend offset. const xy_pos_t offs = hotend_offset[active_extruder]; #elif ENABLED(POLARGRAPH) @@ -1232,7 +1232,7 @@ float get_move_distance(const xyze_pos_t &diff OPTARG(HAS_ROTATIONAL_AXES, bool // Minimum number of seconds to move the given distance const float seconds = cartesian_mm / ( - #if BOTH(HAS_ROTATIONAL_AXES, INCH_MODE_SUPPORT) + #if ALL(HAS_ROTATIONAL_AXES, INCH_MODE_SUPPORT) cartes_move ? scaled_fr_mm_s : LINEAR_UNIT(scaled_fr_mm_s) #else scaled_fr_mm_s @@ -1542,7 +1542,7 @@ float get_move_distance(const xyze_pos_t &diff OPTARG(HAS_ROTATIONAL_AXES, bool void prepare_line_to_destination() { apply_motion_limits(destination); - #if EITHER(PREVENT_COLD_EXTRUSION, PREVENT_LENGTHY_EXTRUDE) + #if ANY(PREVENT_COLD_EXTRUSION, PREVENT_LENGTHY_EXTRUDE) if (!DEBUGGING(DRYRUN) && destination.e != current_position.e) { bool ignore_e = thermalManager.tooColdToExtrude(active_extruder); @@ -1873,12 +1873,12 @@ void prepare_line_to_destination() { if (is_home_dir) { if (TERN0(HOMING_Z_WITH_PROBE, axis == Z_AXIS)) { - #if BOTH(HAS_HEATED_BED, WAIT_FOR_BED_HEATER) + #if ALL(HAS_HEATED_BED, WAIT_FOR_BED_HEATER) // Wait for bed to heat back up between probing points thermalManager.wait_for_bed_heating(); #endif - #if BOTH(HAS_HOTEND, WAIT_FOR_HOTEND) + #if ALL(HAS_HOTEND, WAIT_FOR_HOTEND) // Wait for the hotend to heat back up between probing points thermalManager.wait_for_hotend_heating(active_extruder); #endif @@ -1895,7 +1895,7 @@ void prepare_line_to_destination() { #endif } - #if EITHER(MORGAN_SCARA, MP_SCARA) + #if ANY(MORGAN_SCARA, MP_SCARA) // Tell the planner the axis is at 0 current_position[axis] = 0; sync_plan_position(); @@ -2093,11 +2093,11 @@ void prepare_line_to_destination() { void homeaxis(const AxisEnum axis) { - #if EITHER(MORGAN_SCARA, MP_SCARA) + #if ANY(MORGAN_SCARA, MP_SCARA) // Only Z homing (with probe) is permitted if (axis != Z_AXIS) { BUZZ(100, 880); return; } #else - #define _CAN_HOME(A) (axis == _AXIS(A) && (EITHER(A##_SPI_SENSORLESS, HAS_##A##_ENDSTOP) || TERN0(HOMING_Z_WITH_PROBE, _AXIS(A) == Z_AXIS))) + #define _CAN_HOME(A) (axis == _AXIS(A) && (ANY(A##_SPI_SENSORLESS, HAS_##A##_ENDSTOP) || TERN0(HOMING_Z_WITH_PROBE, _AXIS(A) == Z_AXIS))) #define _ANDCANT(N) && !_CAN_HOME(N) if (true MAIN_AXIS_MAP(_ANDCANT)) return; #endif @@ -2173,7 +2173,7 @@ void prepare_line_to_destination() { // If a second homing move is configured... if (bump) { - #if BOTH(HOMING_Z_WITH_PROBE, BLTOUCH) + #if ALL(HOMING_Z_WITH_PROBE, BLTOUCH) if (axis == Z_AXIS && !bltouch.high_speed_mode) bltouch.stow(); // Intermediate STOW (in LOW SPEED MODE) #endif @@ -2195,7 +2195,7 @@ void prepare_line_to_destination() { } #endif - #if BOTH(HOMING_Z_WITH_PROBE, BLTOUCH) + #if ALL(HOMING_Z_WITH_PROBE, BLTOUCH) if (axis == Z_AXIS && !bltouch.high_speed_mode && bltouch.deploy()) return; // Intermediate DEPLOY (in LOW SPEED MODE) #endif @@ -2206,7 +2206,7 @@ void prepare_line_to_destination() { do_homing_move(axis, rebump, get_homing_bump_feedrate(axis), true); } - #if BOTH(HOMING_Z_WITH_PROBE, BLTOUCH) + #if ALL(HOMING_Z_WITH_PROBE, BLTOUCH) if (axis == Z_AXIS) bltouch.stow(); // The final STOW #endif @@ -2443,7 +2443,7 @@ void set_axis_is_at_home(const AxisEnum axis) { } #endif - #if EITHER(MORGAN_SCARA, AXEL_TPARA) + #if ANY(MORGAN_SCARA, AXEL_TPARA) scara_set_axis_is_at_home(axis); #elif ENABLED(DELTA) current_position[axis] = (axis == Z_AXIS) ? DIFF_TERN(HAS_BED_PROBE, delta_height, probe.offset.z) : base_home_pos(axis); diff --git a/Marlin/src/module/motion.h b/Marlin/src/module/motion.h index b7e37f6b7043..1e6d02d2a7c8 100644 --- a/Marlin/src/module/motion.h +++ b/Marlin/src/module/motion.h @@ -271,7 +271,7 @@ void report_current_position_projected(); extern AutoReporter position_auto_reporter; #endif -#if EITHER(FULL_REPORT_TO_HOST_FEATURE, REALTIME_REPORTING_COMMANDS) +#if ANY(FULL_REPORT_TO_HOST_FEATURE, REALTIME_REPORTING_COMMANDS) #define HAS_GRBL_STATE 1 /** * Machine states for GRBL or TinyG @@ -434,9 +434,6 @@ void restore_feedrate_and_scaling(); typedef bits_t(NUM_AXES) main_axes_bits_t; constexpr main_axes_bits_t main_axes_mask = _BV(NUM_AXES) - 1; -typedef bits_t(NUM_AXES + EXTRUDERS) e_axis_bits_t; -constexpr e_axis_bits_t e_axis_mask = (_BV(EXTRUDERS) - 1) << NUM_AXES; - void set_axis_is_at_home(const AxisEnum axis); #if HAS_ENDSTOPS diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 02a7d05cae3a..6b645fa1337e 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -795,7 +795,7 @@ void Planner::calculate_trapezoid_for_block(block_t * const block, const_float_t NOLESS(initial_rate, uint32_t(MINIMAL_STEP_RATE)); NOLESS(final_rate, uint32_t(MINIMAL_STEP_RATE)); - #if EITHER(S_CURVE_ACCELERATION, LIN_ADVANCE) + #if ANY(S_CURVE_ACCELERATION, LIN_ADVANCE) // If we have some plateau time, the cruise rate will be the nominal rate uint32_t cruise_rate = block->nominal_rate; #endif @@ -829,7 +829,7 @@ void Planner::calculate_trapezoid_for_block(block_t * const block, const_float_t accelerate_steps = _MIN(uint32_t(_MAX(accelerate_steps_float, 0)), block->step_event_count); decelerate_steps = block->step_event_count - accelerate_steps; - #if EITHER(S_CURVE_ACCELERATION, LIN_ADVANCE) + #if ANY(S_CURVE_ACCELERATION, LIN_ADVANCE) // We won't reach the cruising rate. Let's calculate the speed we will reach cruise_rate = final_speed(initial_rate, accel, accelerate_steps); #endif @@ -1349,7 +1349,7 @@ void Planner::check_axes_activity() { if (has_blocks_queued()) { - #if EITHER(HAS_TAIL_FAN_SPEED, BARICUDA) + #if ANY(HAS_TAIL_FAN_SPEED, BARICUDA) block_t *block = &block_buffer[block_buffer_tail]; #endif @@ -1520,7 +1520,7 @@ void Planner::check_axes_activity() { * The multiplier converts a given E value into a length. */ void Planner::calculate_volumetric_multipliers() { - LOOP_L_N(i, COUNT(filament_size)) { + for (uint8_t i = 0; i < COUNT(filament_size); ++i) { volumetric_multiplier[i] = calculate_volumetric_multiplier(filament_size[i]); refresh_e_factor(i); } @@ -1773,7 +1773,7 @@ float Planner::get_axis_position_mm(const AxisEnum axis) { else axis_steps = DIFF_TERN(BACKLASH_COMPENSATION, stepper.position(axis), backlash.get_applied_steps(axis)); - #elif EITHER(MARKFORGED_XY, MARKFORGED_YX) + #elif ANY(MARKFORGED_XY, MARKFORGED_YX) // Requesting one of the joined axes? if (axis == CORE_AXIS_1 || axis == CORE_AXIS_2) { @@ -1925,7 +1925,7 @@ bool Planner::_populate_block( ); //*/ - #if EITHER(PREVENT_COLD_EXTRUSION, PREVENT_LENGTHY_EXTRUDE) + #if ANY(PREVENT_COLD_EXTRUSION, PREVENT_LENGTHY_EXTRUDE) if (dist.e) { #if ENABLED(PREVENT_COLD_EXTRUSION) if (thermalManager.tooColdToExtrude(extruder)) { @@ -2260,7 +2260,7 @@ bool Planner::_populate_block( #if ENABLED(DISABLE_OTHER_EXTRUDERS) // Enable only the selected extruder // Count down all steppers that were recently moved - LOOP_L_N(i, E_STEPPERS) + for (uint8_t i = 0; i < E_STEPPERS; ++i) if (extruder_last_move[i]) extruder_last_move[i]--; // Switching Extruder uses one E stepper motor per two nozzles @@ -2299,7 +2299,7 @@ bool Planner::_populate_block( // Example: At 120mm/s a 60mm move involving XYZ axes takes 0.5s. So this will give 2.0. // Example 2: At 120Β°/s a 60Β° move involving only rotational axes takes 0.5s. So this will give 2.0. float inverse_secs = inverse_millimeters * ( - #if BOTH(HAS_ROTATIONAL_AXES, INCH_MODE_SUPPORT) + #if ALL(HAS_ROTATIONAL_AXES, INCH_MODE_SUPPORT) cartesian_move ? fr_mm_s : LINEAR_UNIT(fr_mm_s) #else fr_mm_s @@ -2310,7 +2310,7 @@ bool Planner::_populate_block( const uint8_t moves_queued = nonbusy_movesplanned(); // Slow down when the buffer starts to empty, rather than wait at the corner for a buffer refill - #if EITHER(SLOWDOWN, HAS_WIRED_LCD) || defined(XY_FREQUENCY_LIMIT) + #if ANY(SLOWDOWN, HAS_WIRED_LCD) || defined(XY_FREQUENCY_LIMIT) // Segment time in microseconds int32_t segment_time_us = LROUND(1000000.0f / inverse_secs); #endif @@ -2419,8 +2419,8 @@ bool Planner::_populate_block( xs2 = xs1; xs1 = xs0; ys2 = ys1; ys1 = ys0; } - xs0 = TEST(direction_change, X_AXIS) ? segment_time_us : xy_freq_min_interval_us; - ys0 = TEST(direction_change, Y_AXIS) ? segment_time_us : xy_freq_min_interval_us; + xs0 = direction_change.x ? segment_time_us : xy_freq_min_interval_us; + ys0 = direction_change.y ? segment_time_us : xy_freq_min_interval_us; if (segment_time_us < xy_freq_min_interval_us) { const int32_t least_xy_segment_time = _MIN(_MAX(xs0, xs1, xs2), _MAX(ys0, ys1, ys2)); @@ -2907,7 +2907,7 @@ void Planner::buffer_sync_block(const BlockFlagBit sync_flag/*=BLOCK_BIT_SYNC_PO #if ENABLED(BACKLASH_COMPENSATION) LOOP_NUM_AXES(axis) block->position[axis] += backlash.get_applied_steps((AxisEnum)axis); #endif - #if BOTH(HAS_FAN, LASER_SYNCHRONOUS_M106_M107) + #if ALL(HAS_FAN, LASER_SYNCHRONOUS_M106_M107) FANS_LOOP(i) block->fan_speed[i] = thermalManager.fan_speed[i]; #endif diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index ee79c913af52..c45ff6ad1d1d 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -650,7 +650,7 @@ class Planner { filament_size[e] = v; if (v > 0) volumetric_area_nominal = CIRCLE_AREA(v * 0.5); //TODO: should it be per extruder // make sure all extruders have some sane value for the filament size - LOOP_L_N(i, COUNT(filament_size)) + for (uint8_t i = 0; i < COUNT(filament_size); ++i) if (!filament_size[i]) filament_size[i] = DEFAULT_NOMINAL_FILAMENT_DIA; } @@ -938,7 +938,7 @@ class Planner { } // SCARA AB and Polar YB axes are in degrees, not mm - #if EITHER(IS_SCARA, POLAR) + #if ANY(IS_SCARA, POLAR) FORCE_INLINE static float get_axis_position_degrees(const AxisEnum axis) { return get_axis_position_mm(axis); } #endif @@ -1041,7 +1041,7 @@ class Planner { return target_velocity_sqr - 2 * accel * distance; } - #if EITHER(S_CURVE_ACCELERATION, LIN_ADVANCE) + #if ANY(S_CURVE_ACCELERATION, LIN_ADVANCE) /** * Calculate the speed reached given initial speed, acceleration and distance */ diff --git a/Marlin/src/module/printcounter.h b/Marlin/src/module/printcounter.h index 63cc1da158e8..ebf61a3a1ce0 100644 --- a/Marlin/src/module/printcounter.h +++ b/Marlin/src/module/printcounter.h @@ -54,7 +54,7 @@ struct printStatistics { // 16 bytes class PrintCounter: public Stopwatch { private: typedef Stopwatch super; - typedef IF::type eeprom_address_t; + typedef IF::type eeprom_address_t; static printStatistics data; diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index 1e01cfd9b616..0bece02c15a8 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -57,9 +57,9 @@ float largest_sensorless_adj = 0; #endif -#if EITHER(HAS_QUIET_PROBING, USE_SENSORLESS) +#if ANY(HAS_QUIET_PROBING, USE_SENSORLESS) #include "stepper/indirection.h" - #if BOTH(HAS_QUIET_PROBING, PROBING_ESTEPPERS_OFF) + #if ALL(HAS_QUIET_PROBING, PROBING_ESTEPPERS_OFF) #include "stepper.h" #endif #if USE_SENSORLESS @@ -429,7 +429,7 @@ FORCE_INLINE void probe_specific_action(const bool deploy) { #endif } -#if EITHER(PREHEAT_BEFORE_PROBING, PREHEAT_BEFORE_LEVELING) +#if ANY(PREHEAT_BEFORE_PROBING, PREHEAT_BEFORE_LEVELING) #if ENABLED(PREHEAT_BEFORE_PROBING) #ifndef PROBING_NOZZLE_TEMP @@ -490,7 +490,7 @@ FORCE_INLINE void probe_specific_action(const bool deploy) { void Probe::probe_error_stop() { SERIAL_ERROR_START(); SERIAL_ECHOPGM(STR_STOP_PRE); - #if EITHER(Z_PROBE_SLED, Z_PROBE_ALLEN_KEY) + #if ANY(Z_PROBE_SLED, Z_PROBE_ALLEN_KEY) SERIAL_ECHOPGM(STR_STOP_UNHOMED); #elif ENABLED(BLTOUCH) SERIAL_ECHOPGM(STR_STOP_BLTOUCH); @@ -515,7 +515,7 @@ bool Probe::set_deployed(const bool deploy, const bool no_return/*=false*/) { // Make room for probe to deploy (or stow) // Fix-mounted probe should only raise for deploy // unless PAUSE_BEFORE_DEPLOY_STOW is enabled - #if EITHER(FIX_MOUNTED_PROBE, NOZZLE_AS_PROBE) && DISABLED(PAUSE_BEFORE_DEPLOY_STOW) + #if ANY(FIX_MOUNTED_PROBE, NOZZLE_AS_PROBE) && DISABLED(PAUSE_BEFORE_DEPLOY_STOW) const bool z_raise_wanted = deploy; #else constexpr bool z_raise_wanted = true; @@ -527,7 +527,7 @@ bool Probe::set_deployed(const bool deploy, const bool no_return/*=false*/) { do_z_clearance(zdest); } - #if EITHER(Z_PROBE_SLED, Z_PROBE_ALLEN_KEY) + #if ANY(Z_PROBE_SLED, Z_PROBE_ALLEN_KEY) if (homing_needed_error(TERN_(Z_PROBE_SLED, _BV(X_AXIS)))) { probe_error_stop(); return true; @@ -588,11 +588,11 @@ bool Probe::set_deployed(const bool deploy, const bool no_return/*=false*/) { bool Probe::probe_down_to_z(const_float_t z, const_feedRate_t fr_mm_s) { DEBUG_SECTION(log_probe, "Probe::probe_down_to_z", DEBUGGING(LEVELING)); - #if BOTH(HAS_HEATED_BED, WAIT_FOR_BED_HEATER) + #if ALL(HAS_HEATED_BED, WAIT_FOR_BED_HEATER) thermalManager.wait_for_bed_heating(); #endif - #if BOTH(HAS_TEMP_HOTEND, WAIT_FOR_HOTEND) + #if ALL(HAS_TEMP_HOTEND, WAIT_FOR_HOTEND) thermalManager.wait_for_hotend_heating(active_extruder); #endif @@ -654,7 +654,7 @@ bool Probe::probe_down_to_z(const_float_t z, const_feedRate_t fr_mm_s) { return true; // Stow in LOW SPEED MODE on every trigger #endif - #if BOTH(HAS_Z_SERVO_PROBE, Z_SERVO_INTERMEDIATE_STOW) + #if ALL(HAS_Z_SERVO_PROBE, Z_SERVO_INTERMEDIATE_STOW) probe_specific_action(false); // Always stow #endif @@ -689,7 +689,7 @@ bool Probe::probe_down_to_z(const_float_t z, const_feedRate_t fr_mm_s) { * @return TRUE if the tare cold not be completed */ bool Probe::tare() { - #if BOTH(PROBE_ACTIVATION_SWITCH, PROBE_TARE_ONLY_WHILE_INACTIVE) + #if ALL(PROBE_ACTIVATION_SWITCH, PROBE_TARE_ONLY_WHILE_INACTIVE) if (endstops.probe_switch_activated()) { if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Cannot tare an active probe"); return true; @@ -811,7 +811,7 @@ float Probe::run_z_probe(const bool sanity_check/*=true*/, const_float_t z_min_p #if EXTRA_PROBING > 0 // Insert Z measurement into probes[]. Keep it sorted ascending. - LOOP_LE_N(i, p) { // Iterate the saved Zs to insert the new Z + for (uint8_t i = 0; i <= p; ++i) { // Iterate the saved Zs to insert the new Z if (i == p || probes[i] > z) { // Last index or new Z is smaller than this Z for (int8_t m = p; --m >= i;) probes[m + 1] = probes[m]; // Shift items down after the insertion point probes[i] = z; // Insert the new Z measurement @@ -849,7 +849,7 @@ float Probe::run_z_probe(const bool sanity_check/*=true*/, const_float_t z_min_p max_avg_idx--; else min_avg_idx++; // Return the average value of all remaining probes. - LOOP_S_LE_N(i, min_avg_idx, max_avg_idx) + for (uint8_t i = min_avg_idx; i <= max_avg_idx; ++i) probes_z_sum += probes[i]; #endif diff --git a/Marlin/src/module/probe.h b/Marlin/src/module/probe.h index 98b4b107cd4f..05a97d947024 100644 --- a/Marlin/src/module/probe.h +++ b/Marlin/src/module/probe.h @@ -79,7 +79,7 @@ class Probe { static xyz_pos_t offset; - #if EITHER(PREHEAT_BEFORE_PROBING, PREHEAT_BEFORE_LEVELING) + #if ANY(PREHEAT_BEFORE_PROBING, PREHEAT_BEFORE_LEVELING) static void preheat_for_probing(const celsius_t hotend_temp, const celsius_t bed_temp, const bool early=false); #endif diff --git a/Marlin/src/module/scara.cpp b/Marlin/src/module/scara.cpp index 4c42ace884de..9c149670e92e 100644 --- a/Marlin/src/module/scara.cpp +++ b/Marlin/src/module/scara.cpp @@ -39,7 +39,7 @@ float segments_per_second = DEFAULT_SEGMENTS_PER_SECOND; -#if EITHER(MORGAN_SCARA, MP_SCARA) +#if ANY(MORGAN_SCARA, MP_SCARA) static constexpr xy_pos_t scara_offset = { SCARA_OFFSET_X, SCARA_OFFSET_Y }; diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index 28eee57c086f..1defac29771d 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -56,11 +56,13 @@ #include "../gcode/gcode.h" #include "../MarlinCore.h" -#if EITHER(EEPROM_SETTINGS, SD_FIRMWARE_UPDATE) +#if ANY(EEPROM_SETTINGS, SD_FIRMWARE_UPDATE) #include "../HAL/shared/eeprom_api.h" #endif -#include "probe.h" +#if HAS_BED_PROBE + #include "probe.h" +#endif #if HAS_LEVELING #include "../feature/bedlevel/bedlevel.h" @@ -695,7 +697,7 @@ void MarlinSettings::postprocess() { #endif } -#if BOTH(PRINTCOUNTER, EEPROM_SETTINGS) +#if ALL(PRINTCOUNTER, EEPROM_SETTINGS) #include "printcounter.h" static_assert( !WITHIN(STATS_EEPROM_ADDRESS, EEPROM_OFFSET, EEPROM_OFFSET + sizeof(SettingsData)) && @@ -739,10 +741,10 @@ void MarlinSettings::postprocess() { // This file simply uses the DEBUG_ECHO macros to implement EEPROM_CHITCHAT. // For deeper debugging of EEPROM issues enable DEBUG_EEPROM_READWRITE. // -#define DEBUG_OUT EITHER(EEPROM_CHITCHAT, DEBUG_LEVELING_FEATURE) +#define DEBUG_OUT ANY(EEPROM_CHITCHAT, DEBUG_LEVELING_FEATURE) #include "../core/debug_out.h" -#if BOTH(EEPROM_CHITCHAT, HOST_PROMPT_SUPPORT) +#if ALL(EEPROM_CHITCHAT, HOST_PROMPT_SUPPORT) #define HOST_EEPROM_CHITCHAT 1 #endif @@ -874,7 +876,7 @@ void MarlinSettings::postprocess() { { #if HAS_HOTEND_OFFSET // Skip hotend 0 which must be 0 - LOOP_S_L_N(e, 1, HOTENDS) + for (uint8_t e = 1; e < HOTENDS; ++e) EEPROM_WRITE(hotend_offset[e]); #endif } @@ -1885,7 +1887,7 @@ void MarlinSettings::postprocess() { { #if HAS_HOTEND_OFFSET // Skip hotend 0 which must be 0 - LOOP_S_L_N(e, 1, HOTENDS) + for (uint8_t e = 1; e < HOTENDS; ++e) EEPROM_READ(hotend_offset[e]); #endif } @@ -2803,14 +2805,14 @@ void MarlinSettings::postprocess() { bedlevel.report_state(); if (!bedlevel.sanity_check()) { - #if BOTH(EEPROM_CHITCHAT, DEBUG_LEVELING_FEATURE) + #if ALL(EEPROM_CHITCHAT, DEBUG_LEVELING_FEATURE) bedlevel.echo_name(); DEBUG_ECHOLNPGM(" initialized.\n"); #endif } else { eeprom_error = ERR_EEPROM_CORRUPT; - #if BOTH(EEPROM_CHITCHAT, DEBUG_LEVELING_FEATURE) + #if ALL(EEPROM_CHITCHAT, DEBUG_LEVELING_FEATURE) DEBUG_ECHOPGM("?Can't enable "); bedlevel.echo_name(); DEBUG_ECHOLNPGM("."); @@ -2888,7 +2890,7 @@ void MarlinSettings::postprocess() { return success; } reset(); - #if EITHER(EEPROM_AUTO_INIT, EEPROM_INIT_NOW) + #if ANY(EEPROM_AUTO_INIT, EEPROM_INIT_NOW) (void)save(); SERIAL_ECHO_MSG("EEPROM Initialized"); #endif @@ -3294,7 +3296,7 @@ void MarlinSettings::reset() { #if HAS_FAN constexpr uint8_t fpre[] = { REPEAT2_S(1, INCREMENT(PREHEAT_COUNT), _PITEM, FAN_SPEED) }; #endif - LOOP_L_N(i, PREHEAT_COUNT) { + for (uint8_t i = 0; i < PREHEAT_COUNT; ++i) { TERN_(HAS_HOTEND, ui.material_preset[i].hotend_temp = hpre[i]); TERN_(HAS_HEATED_BED, ui.material_preset[i].bed_temp = bpre[i]); TERN_(HAS_FAN, ui.material_preset[i].fan_speed = fpre[i]); @@ -3435,10 +3437,10 @@ void MarlinSettings::reset() { #if DISABLED(NO_VOLUMETRICS) parser.volumetric_enabled = ENABLED(VOLUMETRIC_DEFAULT_ON); - LOOP_L_N(q, COUNT(planner.filament_size)) + for (uint8_t q = 0; q < COUNT(planner.filament_size); ++q) planner.filament_size[q] = DEFAULT_NOMINAL_FILAMENT_DIA; #if ENABLED(VOLUMETRIC_EXTRUDER_LIMIT) - LOOP_L_N(q, COUNT(planner.volumetric_extruder_limit)) + for (uint8_t q = 0; q < COUNT(planner.volumetric_extruder_limit); ++q) planner.volumetric_extruder_limit[q] = DEFAULT_VOLUMETRIC_EXTRUDER_LIMIT; #endif #endif @@ -3469,7 +3471,7 @@ void MarlinSettings::reset() { #if HAS_MOTOR_CURRENT_PWM constexpr uint32_t tmp_motor_current_setting[MOTOR_CURRENT_COUNT] = PWM_MOTOR_CURRENT; - LOOP_L_N(q, MOTOR_CURRENT_COUNT) + for (uint8_t q = 0; q < MOTOR_CURRENT_COUNT; ++q) stepper.set_digipot_current(q, (stepper.motor_current_setting[q] = tmp_motor_current_setting[q])); #endif @@ -3479,7 +3481,7 @@ void MarlinSettings::reset() { #if HAS_MOTOR_CURRENT_SPI static constexpr uint32_t tmp_motor_current_setting[] = DIGIPOT_MOTOR_CURRENT; DEBUG_ECHOLNPGM("Writing Digipot"); - LOOP_L_N(q, COUNT(tmp_motor_current_setting)) + for (uint8_t q = 0; q < COUNT(tmp_motor_current_setting); ++q) stepper.set_digipot_current(q, tmp_motor_current_setting[q]); DEBUG_ECHOLNPGM("Digipot Written"); #endif @@ -3590,7 +3592,7 @@ void MarlinSettings::reset() { postprocess(); - #if EITHER(EEPROM_CHITCHAT, DEBUG_LEVELING_FEATURE) + #if ANY(EEPROM_CHITCHAT, DEBUG_LEVELING_FEATURE) FSTR_P const hdsl = F("Hardcoded Default Settings Loaded"); TERN_(HOST_EEPROM_CHITCHAT, hostui.notify(hdsl)); DEBUG_ECHO_START(); DEBUG_ECHOLNF(hdsl); @@ -3686,8 +3688,8 @@ void MarlinSettings::reset() { #if ENABLED(MESH_BED_LEVELING) if (leveling_is_valid()) { - LOOP_L_N(py, GRID_MAX_POINTS_Y) { - LOOP_L_N(px, GRID_MAX_POINTS_X) { + for (uint8_t py = 0; py < GRID_MAX_POINTS_Y; ++py) { + for (uint8_t px = 0; px < GRID_MAX_POINTS_X; ++px) { CONFIG_ECHO_START(); SERIAL_ECHOPGM(" G29 S3 I", px, " J", py); SERIAL_ECHOLNPAIR_F_P(SP_Z_STR, LINEAR_UNIT(bedlevel.z_values[px][py]), 5); @@ -3712,8 +3714,8 @@ void MarlinSettings::reset() { #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) if (leveling_is_valid()) { - LOOP_L_N(py, GRID_MAX_POINTS_Y) { - LOOP_L_N(px, GRID_MAX_POINTS_X) { + for (uint8_t py = 0; py < GRID_MAX_POINTS_Y; ++py) { + for (uint8_t px = 0; px < GRID_MAX_POINTS_X; ++px) { CONFIG_ECHO_START(); SERIAL_ECHOPGM(" G29 W I", px, " J", py); SERIAL_ECHOLNPAIR_F_P(SP_Z_STR, LINEAR_UNIT(bedlevel.z_values[px][py]), 5); @@ -3743,7 +3745,7 @@ void MarlinSettings::reset() { // // M666 Endstops Adjustment // - #if EITHER(DELTA, HAS_EXTRA_ENDSTOPS) + #if ANY(DELTA, HAS_EXTRA_ENDSTOPS) gcode.M666_report(forReplay); #endif @@ -3765,7 +3767,7 @@ void MarlinSettings::reset() { TERN_(PIDTEMPCHAMBER, gcode.M309_report(forReplay)); #if HAS_USER_THERMISTORS - LOOP_L_N(i, USER_THERMISTORS) + for (uint8_t i = 0; i < USER_THERMISTORS; ++i) thermalManager.M305_report(i, forReplay); #endif diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index 3188f77da8bb..66dd114616df 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -148,7 +148,7 @@ Stepper stepper; // Singleton // public: -#if EITHER(HAS_EXTRA_ENDSTOPS, Z_STEPPER_AUTO_ALIGN) +#if ANY(HAS_EXTRA_ENDSTOPS, Z_STEPPER_AUTO_ALIGN) bool Stepper::separate_multi_axis = false; #endif @@ -182,7 +182,7 @@ bool Stepper::abort_current_block; bool Stepper::locked_Y_motor = false, Stepper::locked_Y2_motor = false; #endif -#if EITHER(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN) +#if ANY(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN) bool Stepper::locked_Z_motor = false, Stepper::locked_Z2_motor = false #if NUM_Z_STEPPERS >= 3 , Stepper::locked_Z3_motor = false @@ -218,7 +218,7 @@ uint32_t Stepper::advance_divisor = 0, Stepper::decelerate_after, // The count at which to start decelerating Stepper::step_event_count; // The total event count for the current block -#if EITHER(HAS_MULTI_EXTRUDER, MIXING_EXTRUDER) +#if ANY(HAS_MULTI_EXTRUDER, MIXING_EXTRUDER) uint8_t Stepper::stepper_extruder; #else constexpr uint8_t Stepper::stepper_extruder; @@ -1967,7 +1967,7 @@ void Stepper::pulse_phase_isr() { PULSE_PREP(W); #endif - #if EITHER(HAS_E0_STEP, MIXING_EXTRUDER) + #if ANY(HAS_E0_STEP, MIXING_EXTRUDER) PULSE_PREP(E); #if ENABLED(LIN_ADVANCE) @@ -2558,7 +2558,7 @@ hal_timer_t Stepper::block_phase_isr() { * If DeltaA == -DeltaB, the movement is only in the 2nd axis (Y or Z, handled below) * If DeltaA == DeltaB, the movement is only in the 1st axis (X) */ - #if EITHER(COREXY, COREXZ) + #if ANY(COREXY, COREXZ) #define X_CMP(A,B) ((A)==(B)) #else #define X_CMP(A,B) ((A)!=(B)) @@ -2578,7 +2578,7 @@ hal_timer_t Stepper::block_phase_isr() { * If DeltaA == DeltaB, the movement is only in the 1st axis (X or Y) * If DeltaA == -DeltaB, the movement is only in the 2nd axis (Y or Z) */ - #if EITHER(COREYX, COREYZ) + #if ANY(COREYX, COREYZ) #define Y_CMP(A,B) ((A)==(B)) #else #define Y_CMP(A,B) ((A)!=(B)) @@ -2598,7 +2598,7 @@ hal_timer_t Stepper::block_phase_isr() { * If DeltaA == DeltaB, the movement is only in the 1st axis (X or Y, already handled above) * If DeltaA == -DeltaB, the movement is only in the 2nd axis (Z) */ - #if EITHER(COREZX, COREZY) + #if ANY(COREZX, COREZY) #define Z_CMP(A,B) ((A)==(B)) #else #define Z_CMP(A,B) ((A)!=(B)) @@ -2842,7 +2842,7 @@ void Stepper::init() { #if MB(ALLIGATOR) const float motor_current[] = MOTOR_CURRENT; unsigned int digipot_motor = 0; - LOOP_L_N(i, 3 + EXTRUDERS) { + for (uint8_t i = 0; i < 3 + EXTRUDERS; ++i) { digipot_motor = 255 * (motor_current[i] / 2.5); dac084s085::setValue(i, digipot_motor); } @@ -2856,7 +2856,7 @@ void Stepper::init() { TERN_(HAS_X2_DIR, X2_DIR_INIT()); #if HAS_Y_DIR Y_DIR_INIT(); - #if BOTH(HAS_Y2_STEPPER, HAS_Y2_DIR) + #if ALL(HAS_Y2_STEPPER, HAS_Y2_DIR) Y2_DIR_INIT(); #endif #endif @@ -2908,7 +2908,7 @@ void Stepper::init() { #endif X_ENABLE_INIT(); if (X_ENABLE_INIT_STATE) X_ENABLE_WRITE(X_ENABLE_INIT_STATE); - #if BOTH(HAS_X2_STEPPER, HAS_X2_ENABLE) + #if ALL(HAS_X2_STEPPER, HAS_X2_ENABLE) X2_ENABLE_INIT(); if (X_ENABLE_INIT_STATE) X2_ENABLE_WRITE(X_ENABLE_INIT_STATE); #endif @@ -2919,7 +2919,7 @@ void Stepper::init() { #endif Y_ENABLE_INIT(); if (Y_ENABLE_INIT_STATE) Y_ENABLE_WRITE(Y_ENABLE_INIT_STATE); - #if BOTH(HAS_Y2_STEPPER, HAS_Y2_ENABLE) + #if ALL(HAS_Y2_STEPPER, HAS_Y2_ENABLE) Y2_ENABLE_INIT(); if (Y_ENABLE_INIT_STATE) Y2_ENABLE_WRITE(Y_ENABLE_INIT_STATE); #endif @@ -3725,7 +3725,7 @@ void Stepper::report_positions() { void Stepper::refresh_motor_power() { if (!initialized) return; - LOOP_L_N(i, COUNT(motor_current_setting)) { + for (uint8_t i = 0; i < COUNT(motor_current_setting); ++i) { switch (i) { #if ANY_PIN(MOTOR_CURRENT_PWM_XY, MOTOR_CURRENT_PWM_X, MOTOR_CURRENT_PWM_Y, MOTOR_CURRENT_PWM_I, MOTOR_CURRENT_PWM_J, MOTOR_CURRENT_PWM_K, MOTOR_CURRENT_PWM_U, MOTOR_CURRENT_PWM_V, MOTOR_CURRENT_PWM_W) case 0: @@ -3821,7 +3821,7 @@ void Stepper::report_positions() { SPI.begin(); SET_OUTPUT(DIGIPOTSS_PIN); - LOOP_L_N(i, COUNT(motor_current_setting)) + for (uint8_t i = 0; i < COUNT(motor_current_setting); ++i) set_digipot_current(i, motor_current_setting[i]); #elif HAS_MOTOR_CURRENT_PWM diff --git a/Marlin/src/module/stepper.h b/Marlin/src/module/stepper.h index a2c9861abc6b..9f49e353a753 100644 --- a/Marlin/src/module/stepper.h +++ b/Marlin/src/module/stepper.h @@ -83,6 +83,9 @@ typedef struct { }; } stepper_flags_t; +typedef bits_t(NUM_AXES + E_STATES) e_axis_bits_t; +constexpr e_axis_bits_t e_axis_mask = (_BV(E_STATES) - 1) << NUM_AXES; + // All the stepper enable pins constexpr pin_t ena_pins[] = { NUM_AXIS_LIST_(X_ENABLE_PIN, Y_ENABLE_PIN, Z_ENABLE_PIN, I_ENABLE_PIN, J_ENABLE_PIN, K_ENABLE_PIN, U_ENABLE_PIN, V_ENABLE_PIN, W_ENABLE_PIN) @@ -290,7 +293,7 @@ class Stepper { public: - #if EITHER(HAS_EXTRA_ENDSTOPS, Z_STEPPER_AUTO_ALIGN) + #if ANY(HAS_EXTRA_ENDSTOPS, Z_STEPPER_AUTO_ALIGN) static bool separate_multi_axis; #endif @@ -337,7 +340,7 @@ class Stepper { #if ENABLED(Y_DUAL_ENDSTOPS) static bool locked_Y_motor, locked_Y2_motor; #endif - #if EITHER(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN) + #if ANY(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN) static bool locked_Z_motor, locked_Z2_motor #if NUM_Z_STEPPERS >= 3 , locked_Z3_motor @@ -375,7 +378,7 @@ class Stepper { decelerate_after, // The point from where we need to start decelerating step_event_count; // The total event count for the current block - #if EITHER(HAS_MULTI_EXTRUDER, MIXING_EXTRUDER) + #if ANY(HAS_MULTI_EXTRUDER, MIXING_EXTRUDER) static uint8_t stepper_extruder; #else static constexpr uint8_t stepper_extruder = 0; @@ -547,7 +550,7 @@ class Stepper { static void microstep_readings(); #endif - #if EITHER(HAS_EXTRA_ENDSTOPS, Z_STEPPER_AUTO_ALIGN) + #if ANY(HAS_EXTRA_ENDSTOPS, Z_STEPPER_AUTO_ALIGN) FORCE_INLINE static void set_separate_multi_axis(const bool state) { separate_multi_axis = state; } #endif #if ENABLED(X_DUAL_ENDSTOPS) @@ -558,7 +561,7 @@ class Stepper { FORCE_INLINE static void set_y_lock(const bool state) { locked_Y_motor = state; } FORCE_INLINE static void set_y2_lock(const bool state) { locked_Y2_motor = state; } #endif - #if EITHER(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN) + #if ANY(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN) FORCE_INLINE static void set_z1_lock(const bool state) { locked_Z_motor = state; } FORCE_INLINE static void set_z2_lock(const bool state) { locked_Z2_motor = state; } #if NUM_Z_STEPPERS >= 3 diff --git a/Marlin/src/module/stepper/trinamic.cpp b/Marlin/src/module/stepper/trinamic.cpp index 7649c52f5ce6..ce99d87f0996 100644 --- a/Marlin/src/module/stepper/trinamic.cpp +++ b/Marlin/src/module/stepper/trinamic.cpp @@ -501,7 +501,7 @@ enum StealthIndex : uint8_t { struct { const void *ptr[TMCAxis::TOTAL]; bool began(const TMCAxis a, const void * const p) { - LOOP_L_N(i, a) if (p == ptr[i]) return true; + for (uint8_t i = 0; i < a; ++i) if (p == ptr[i]) return true; ptr[a] = p; return false; }; } sp_helper; @@ -514,154 +514,154 @@ enum StealthIndex : uint8_t { #ifdef X_HARDWARE_SERIAL HW_SERIAL_BEGIN(X); #else - stepperX.beginSerial(TMC_BAUD_RATE); + stepperX.beginSerial(TMC_X_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(X2) #ifdef X2_HARDWARE_SERIAL HW_SERIAL_BEGIN(X2); #else - stepperX2.beginSerial(TMC_BAUD_RATE); + stepperX2.beginSerial(TMC_X2_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(Y) #ifdef Y_HARDWARE_SERIAL HW_SERIAL_BEGIN(Y); #else - stepperY.beginSerial(TMC_BAUD_RATE); + stepperY.beginSerial(TMC_Y_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(Y2) #ifdef Y2_HARDWARE_SERIAL HW_SERIAL_BEGIN(Y2); #else - stepperY2.beginSerial(TMC_BAUD_RATE); + stepperY2.beginSerial(TMC_Y2_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(Z) #ifdef Z_HARDWARE_SERIAL HW_SERIAL_BEGIN(Z); #else - stepperZ.beginSerial(TMC_BAUD_RATE); + stepperZ.beginSerial(TMC_Z_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(Z2) #ifdef Z2_HARDWARE_SERIAL HW_SERIAL_BEGIN(Z2); #else - stepperZ2.beginSerial(TMC_BAUD_RATE); + stepperZ2.beginSerial(TMC_Z2_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(Z3) #ifdef Z3_HARDWARE_SERIAL HW_SERIAL_BEGIN(Z3); #else - stepperZ3.beginSerial(TMC_BAUD_RATE); + stepperZ3.beginSerial(TMC_Z3_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(Z4) #ifdef Z4_HARDWARE_SERIAL HW_SERIAL_BEGIN(Z4); #else - stepperZ4.beginSerial(TMC_BAUD_RATE); + stepperZ4.beginSerial(TMC_Z4_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(I) #ifdef I_HARDWARE_SERIAL HW_SERIAL_BEGIN(I); #else - stepperI.beginSerial(TMC_BAUD_RATE); + stepperI.beginSerial(TMC_I_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(J) #ifdef J_HARDWARE_SERIAL HW_SERIAL_BEGIN(J); #else - stepperJ.beginSerial(TMC_BAUD_RATE); + stepperJ.beginSerial(TMC_J_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(K) #ifdef K_HARDWARE_SERIAL HW_SERIAL_BEGIN(K); #else - stepperK.beginSerial(TMC_BAUD_RATE); + stepperK.beginSerial(TMC_K_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(U) #ifdef U_HARDWARE_SERIAL HW_SERIAL_BEGIN(U); #else - stepperU.beginSerial(TMC_BAUD_RATE); + stepperU.beginSerial(TMC_U_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(V) #ifdef V_HARDWARE_SERIAL HW_SERIAL_BEGIN(V); #else - stepperV.beginSerial(TMC_BAUD_RATE); + stepperV.beginSerial(TMC_V_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(W) #ifdef W_HARDWARE_SERIAL HW_SERIAL_BEGIN(W); #else - stepperW.beginSerial(TMC_BAUD_RATE); + stepperW.beginSerial(TMC_W_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(E0) #ifdef E0_HARDWARE_SERIAL HW_SERIAL_BEGIN(E0); #else - stepperE0.beginSerial(TMC_BAUD_RATE); + stepperE0.beginSerial(TMC_E0_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(E1) #ifdef E1_HARDWARE_SERIAL HW_SERIAL_BEGIN(E1); #else - stepperE1.beginSerial(TMC_BAUD_RATE); + stepperE1.beginSerial(TMC_E1_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(E2) #ifdef E2_HARDWARE_SERIAL HW_SERIAL_BEGIN(E2); #else - stepperE2.beginSerial(TMC_BAUD_RATE); + stepperE2.beginSerial(TMC_E2_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(E3) #ifdef E3_HARDWARE_SERIAL HW_SERIAL_BEGIN(E3); #else - stepperE3.beginSerial(TMC_BAUD_RATE); + stepperE3.beginSerial(TMC_E3_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(E4) #ifdef E4_HARDWARE_SERIAL HW_SERIAL_BEGIN(E4); #else - stepperE4.beginSerial(TMC_BAUD_RATE); + stepperE4.beginSerial(TMC_E4_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(E5) #ifdef E5_HARDWARE_SERIAL HW_SERIAL_BEGIN(E5); #else - stepperE5.beginSerial(TMC_BAUD_RATE); + stepperE5.beginSerial(TMC_E5_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(E6) #ifdef E6_HARDWARE_SERIAL HW_SERIAL_BEGIN(E6); #else - stepperE6.beginSerial(TMC_BAUD_RATE); + stepperE6.beginSerial(TMC_E6_BAUD_RATE); #endif #endif #if AXIS_HAS_UART(E7) #ifdef E7_HARDWARE_SERIAL HW_SERIAL_BEGIN(E7); #else - stepperE7.beginSerial(TMC_BAUD_RATE); + stepperE7.beginSerial(TMC_E7_BAUD_RATE); #endif #endif } diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index f785a683eb4a..7383f6a1c3de 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -37,7 +37,7 @@ #include "planner.h" #include "printcounter.h" -#if EITHER(HAS_COOLER, LASER_COOLANT_FLOW_METER) +#if ANY(HAS_COOLER, LASER_COOLANT_FLOW_METER) #include "../feature/cooler.h" #include "../feature/spindle_laser.h" #endif @@ -156,7 +156,7 @@ #include "probe.h" #endif -#if EITHER(MPCTEMP, PID_EXTRUSION_SCALING) +#if ANY(MPCTEMP, PID_EXTRUSION_SCALING) #include "stepper.h" #endif @@ -373,7 +373,7 @@ PGMSTR(str_t_heating_failed, STR_T_HEATING_FAILED); redundant_info_t Temperature::temp_redundant; #endif -#if EITHER(AUTO_POWER_E_FANS, HAS_FANCHECK) +#if ANY(AUTO_POWER_E_FANS, HAS_FANCHECK) uint8_t Temperature::autofan_speed[HOTENDS] = ARRAY_N_1(HOTENDS, FAN_OFF_PWM); #endif @@ -385,7 +385,7 @@ PGMSTR(str_t_heating_failed, STR_T_HEATING_FAILED); uint8_t Temperature::coolerfan_speed = FAN_OFF_PWM; #endif -#if BOTH(FAN_SOFT_PWM, USE_CONTROLLER_FAN) +#if ALL(FAN_SOFT_PWM, USE_CONTROLLER_FAN) uint8_t Temperature::soft_pwm_controller_speed = FAN_OFF_PWM; #endif @@ -439,7 +439,7 @@ PGMSTR(str_t_heating_failed, STR_T_HEATING_FAILED); #endif - #if EITHER(PROBING_FANS_OFF, ADVANCED_PAUSE_FANS_PAUSE) + #if ANY(PROBING_FANS_OFF, ADVANCED_PAUSE_FANS_PAUSE) bool Temperature::fans_paused; // = false; uint8_t Temperature::saved_fan_speed[FAN_COUNT] = ARRAY_N_1(FAN_COUNT, FAN_OFF_PWM); #endif @@ -489,7 +489,7 @@ PGMSTR(str_t_heating_failed, STR_T_HEATING_FAILED); } #endif - #if EITHER(PROBING_FANS_OFF, ADVANCED_PAUSE_FANS_PAUSE) + #if ANY(PROBING_FANS_OFF, ADVANCED_PAUSE_FANS_PAUSE) void Temperature::set_fans_paused(const bool p) { if (p != fans_paused) { @@ -573,7 +573,7 @@ PGMSTR(str_t_heating_failed, STR_T_HEATING_FAILED); raw_adc_t Temperature::maxtemp_raw_SOC = TEMP_SENSOR_SOC_RAW_HI_TEMP; #endif -#if BOTH(HAS_MARLINUI_MENU, PREVENT_COLD_EXTRUSION) && E_MANUAL > 0 +#if ALL(HAS_MARLINUI_MENU, PREVENT_COLD_EXTRUSION) && E_MANUAL > 0 bool Temperature::allow_cold_extrude_override = false; #else constexpr bool Temperature::allow_cold_extrude_override; @@ -698,15 +698,15 @@ volatile bool Temperature::raw_temps_ready = false; #define ONHEATINGSTART() C_TERN(ischamber, printerEventLEDs.onChamberHeatingStart(), B_TERN(isbed, printerEventLEDs.onBedHeatingStart(), printerEventLEDs.onHotendHeatingStart())) #define ONHEATING(S,C,T) C_TERN(ischamber, printerEventLEDs.onChamberHeating(S,C,T), B_TERN(isbed, printerEventLEDs.onBedHeating(S,C,T), printerEventLEDs.onHotendHeating(S,C,T))) - #define WATCH_PID DISABLED(NO_WATCH_PID_TUNING) && (BOTH(WATCH_CHAMBER, PIDTEMPCHAMBER) || BOTH(WATCH_BED, PIDTEMPBED) || BOTH(WATCH_HOTENDS, PIDTEMP)) + #define WATCH_PID DISABLED(NO_WATCH_PID_TUNING) && (ALL(WATCH_CHAMBER, PIDTEMPCHAMBER) || ALL(WATCH_BED, PIDTEMPBED) || ALL(WATCH_HOTENDS, PIDTEMP)) #if WATCH_PID - #if BOTH(THERMAL_PROTECTION_CHAMBER, PIDTEMPCHAMBER) + #if ALL(THERMAL_PROTECTION_CHAMBER, PIDTEMPCHAMBER) #define C_GTV(T,A,B) ((T) ? (A) : (B)) #else #define C_GTV(T,A,B) (B) #endif - #if BOTH(THERMAL_PROTECTION_BED, PIDTEMPBED) + #if ALL(THERMAL_PROTECTION_BED, PIDTEMPBED) #define B_GTV(T,A,B) ((T) ? (A) : (B)) #else #define B_GTV(T,A,B) (B) @@ -835,7 +835,7 @@ volatile bool Temperature::raw_temps_ready = false; // Make sure heating is actually working #if WATCH_PID - if (BOTH(WATCH_BED, WATCH_HOTENDS) || isbed == DISABLED(WATCH_HOTENDS) || ischamber == DISABLED(WATCH_HOTENDS)) { + if (ALL(WATCH_BED, WATCH_HOTENDS) || isbed == DISABLED(WATCH_HOTENDS) || ischamber == DISABLED(WATCH_HOTENDS)) { if (!heated) { // If not yet reached target... if (current_temp > next_watch_temp) { // Over the watch temp? next_watch_temp = current_temp + watch_temp_increase; // - set the next temp to watch for @@ -868,7 +868,7 @@ volatile bool Temperature::raw_temps_ready = false; SERIAL_ECHOPGM(STR_PID_AUTOTUNE); SERIAL_ECHOLNPGM(STR_PID_AUTOTUNE_FINISHED); TERN_(HOST_PROMPT_SUPPORT, hostui.notify(GET_TEXT_F(MSG_PID_AUTOTUNE_DONE))); - #if EITHER(PIDTEMPBED, PIDTEMPCHAMBER) + #if ANY(PIDTEMPBED, PIDTEMPCHAMBER) FSTR_P const estring = GHV(F("chamber"), F("bed"), FPSTR(NUL_STR)); say_default_(); SERIAL_ECHOF(estring); SERIAL_ECHOLNPGM("Kp ", tune_pid.p); say_default_(); SERIAL_ECHOF(estring); SERIAL_ECHOLNPGM("Ki ", tune_pid.i); @@ -939,7 +939,7 @@ volatile bool Temperature::raw_temps_ready = false; #if ENABLED(MPC_AUTOTUNE) - #if EITHER(MPC_FAN_0_ALL_HOTENDS, MPC_FAN_0_ACTIVE_HOTEND) + #if ANY(MPC_FAN_0_ALL_HOTENDS, MPC_FAN_0_ACTIVE_HOTEND) #define SINGLEFAN 1 #endif @@ -1400,7 +1400,7 @@ int16_t Temperature::getHeaterPower(const heater_id_t heater_id) { }while(0) uint8_t fanDone = 0; - LOOP_L_N(f, COUNT(fanBit)) { + for (uint8_t f = 0; f < COUNT(fanBit); ++f) { const uint8_t realFan = pgm_read_byte(&fanBit[f]); if (TEST(fanDone, realFan)) continue; const bool fan_on = TEST(fanState, realFan); @@ -1416,13 +1416,13 @@ int16_t Temperature::getHeaterPower(const heater_id_t heater_id) { break; #endif default: - #if EITHER(AUTO_POWER_E_FANS, HAS_FANCHECK) + #if ANY(AUTO_POWER_E_FANS, HAS_FANCHECK) autofan_speed[realFan] = fan_on ? EXTRUDER_AUTO_FAN_SPEED : 0; #endif break; } - #if BOTH(HAS_FANCHECK, HAS_PWMFANCHECK) + #if ALL(HAS_FANCHECK, HAS_PWMFANCHECK) #define _AUTOFAN_SPEED() fan_check.is_measuring() ? 255 : EXTRUDER_AUTO_FAN_SPEED #else #define _AUTOFAN_SPEED() EXTRUDER_AUTO_FAN_SPEED @@ -1789,7 +1789,7 @@ void Temperature::mintemp_error(const heater_id_t heater_id) { } #endif // WATCH_BED - #if BOTH(PROBING_HEATERS_OFF, BED_LIMIT_SWITCHING) + #if ALL(PROBING_HEATERS_OFF, BED_LIMIT_SWITCHING) #define PAUSE_CHANGE_REQD 1 #endif @@ -1877,11 +1877,11 @@ void Temperature::mintemp_error(const heater_id_t heater_id) { } #endif - #if EITHER(CHAMBER_FAN, CHAMBER_VENT) || DISABLED(PIDTEMPCHAMBER) + #if ANY(CHAMBER_FAN, CHAMBER_VENT) || DISABLED(PIDTEMPCHAMBER) static bool flag_chamber_excess_heat; // = false; #endif - #if EITHER(CHAMBER_FAN, CHAMBER_VENT) + #if ANY(CHAMBER_FAN, CHAMBER_VENT) static bool flag_chamber_off; // = false if (temp_chamber.target > CHAMBER_MINTEMP) { @@ -2646,22 +2646,22 @@ void Temperature::updateTemperaturesFromRawValues() { if (temp_bed.target > 0 && !is_bed_preheating() && TP_CMP(BED, mintemp_raw_BED, temp_bed.getraw())) mintemp_error(H_BED); #endif - #if BOTH(HAS_HEATED_CHAMBER, THERMAL_PROTECTION_CHAMBER) + #if ALL(HAS_HEATED_CHAMBER, THERMAL_PROTECTION_CHAMBER) if (TP_CMP(CHAMBER, temp_chamber.getraw(), maxtemp_raw_CHAMBER)) maxtemp_error(H_CHAMBER); if (temp_chamber.target > 0 && TP_CMP(CHAMBER, mintemp_raw_CHAMBER, temp_chamber.getraw())) mintemp_error(H_CHAMBER); #endif - #if BOTH(HAS_COOLER, THERMAL_PROTECTION_COOLER) + #if ALL(HAS_COOLER, THERMAL_PROTECTION_COOLER) if (cutter.unitPower > 0 && TP_CMP(COOLER, temp_cooler.getraw(), maxtemp_raw_COOLER)) maxtemp_error(H_COOLER); if (TP_CMP(COOLER, mintemp_raw_COOLER, temp_cooler.getraw())) mintemp_error(H_COOLER); #endif - #if BOTH(HAS_TEMP_BOARD, THERMAL_PROTECTION_BOARD) + #if ALL(HAS_TEMP_BOARD, THERMAL_PROTECTION_BOARD) if (TP_CMP(BOARD, temp_board.getraw(), maxtemp_raw_BOARD)) maxtemp_error(H_BOARD); if (TP_CMP(BOARD, mintemp_raw_BOARD, temp_board.getraw())) mintemp_error(H_BOARD); #endif - #if BOTH(HAS_TEMP_SOC, THERMAL_PROTECTION_SOC) + #if ALL(HAS_TEMP_SOC, THERMAL_PROTECTION_SOC) if (TP_CMP(SOC, temp_soc.getraw(), maxtemp_raw_SOC)) maxtemp_error(H_SOC); #endif #undef TP_CMP @@ -3011,12 +3011,12 @@ void Temperature::init() { while (analog_to_celsius_cooler(maxtemp_raw_COOLER) < COOLER_MAXTEMP) maxtemp_raw_COOLER -= TEMPDIR(COOLER) * (OVERSAMPLENR); #endif - #if BOTH(HAS_TEMP_BOARD, THERMAL_PROTECTION_BOARD) + #if ALL(HAS_TEMP_BOARD, THERMAL_PROTECTION_BOARD) while (analog_to_celsius_board(mintemp_raw_BOARD) < BOARD_MINTEMP) mintemp_raw_BOARD += TEMPDIR(BOARD) * (OVERSAMPLENR); while (analog_to_celsius_board(maxtemp_raw_BOARD) > BOARD_MAXTEMP) maxtemp_raw_BOARD -= TEMPDIR(BOARD) * (OVERSAMPLENR); #endif - #if BOTH(HAS_TEMP_SOC, THERMAL_PROTECTION_SOC) + #if ALL(HAS_TEMP_SOC, THERMAL_PROTECTION_SOC) while (analog_to_celsius_soc(maxtemp_raw_SOC) > SOC_MAXTEMP) maxtemp_raw_SOC -= OVERSAMPLENR; #endif @@ -3272,7 +3272,7 @@ void Temperature::disable_all_heaters() { #endif // PROBING_HEATERS_OFF -#if EITHER(SINGLENOZZLE_STANDBY_TEMP, SINGLENOZZLE_STANDBY_FAN) +#if ANY(SINGLENOZZLE_STANDBY_TEMP, SINGLENOZZLE_STANDBY_FAN) void Temperature::singlenozzle_change(const uint8_t old_tool, const uint8_t new_tool) { #if ENABLED(SINGLENOZZLE_STANDBY_FAN) @@ -3641,7 +3641,7 @@ void Temperature::isr() { static SoftPWM soft_pwm_cooler; #endif - #if BOTH(FAN_SOFT_PWM, USE_CONTROLLER_FAN) + #if ALL(FAN_SOFT_PWM, USE_CONTROLLER_FAN) static SoftPWM soft_pwm_controller; #endif diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index c4dae4c6e5a7..b0cb3d778ebe 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -273,7 +273,7 @@ typedef struct { float p, i, d, c, f; } raw_pidcf_t; base::reset(); prev_e_pos = 0; lpq_ptr = 0; - LOOP_L_N(i, LPQ_ARR_SZ) lpq[i] = 0; + for (uint8_t i = 0; i < LPQ_ARR_SZ; ++i) lpq[i] = 0; } float get_extrusion_scale_output(const bool is_active, const int32_t e_position, const float e_mm_per_step, const int16_t lpq_len) { @@ -369,7 +369,7 @@ typedef struct { float p, i, d, c, f; } raw_pidcf_t; }; typedef - #if BOTH(PID_EXTRUSION_SCALING, PID_FAN_SCALING) + #if ALL(PID_EXTRUSION_SCALING, PID_FAN_SCALING) PIDCF_t<0, PID_MAX, LPQ_MAX_LEN, PID_FAN_SCALING_MIN_SPEED, PID_FAN_SCALING_LIN_FACTOR> #elif ENABLED(PID_EXTRUSION_SCALING) PIDC_t<0, PID_MAX, LPQ_MAX_LEN> @@ -409,7 +409,7 @@ typedef struct { float p, i, d, c, f; } raw_pidcf_t; #endif -#if ENABLED(G26_MESH_VALIDATION) && EITHER(HAS_MARLINUI_MENU, EXTENSIBLE_UI) +#if ENABLED(G26_MESH_VALIDATION) && ANY(HAS_MARLINUI_MENU, EXTENSIBLE_UI) #define G26_CLICK_CAN_CANCEL 1 #endif @@ -485,7 +485,7 @@ struct PIDHeaterInfo : public HeaterInfo { #if HAS_TEMP_PROBE typedef temp_info_t probe_info_t; #endif -#if EITHER(HAS_COOLER, HAS_TEMP_COOLER) +#if ANY(HAS_COOLER, HAS_TEMP_COOLER) typedef heater_info_t cooler_info_t; #endif #if HAS_TEMP_BOARD @@ -628,7 +628,7 @@ class Temperature { static redundant_info_t temp_redundant; #endif - #if EITHER(AUTO_POWER_E_FANS, HAS_FANCHECK) + #if ANY(AUTO_POWER_E_FANS, HAS_FANCHECK) static uint8_t autofan_speed[HOTENDS]; #endif #if ENABLED(AUTO_POWER_CHAMBER_FAN) @@ -643,11 +643,11 @@ class Temperature { soft_pwm_count_fan[FAN_COUNT]; #endif - #if BOTH(FAN_SOFT_PWM, USE_CONTROLLER_FAN) + #if ALL(FAN_SOFT_PWM, USE_CONTROLLER_FAN) static uint8_t soft_pwm_controller_speed; #endif - #if BOTH(HAS_MARLINUI_MENU, PREVENT_COLD_EXTRUSION) && E_MANUAL > 0 + #if ALL(HAS_MARLINUI_MENU, PREVENT_COLD_EXTRUSION) && E_MANUAL > 0 static bool allow_cold_extrude_override; static void set_menu_cold_override(const bool allow) { allow_cold_extrude_override = allow; } #else @@ -671,7 +671,7 @@ class Temperature { static bool hotEnoughToExtrude(const uint8_t e) { return !tooColdToExtrude(e); } static bool targetHotEnoughToExtrude(const uint8_t e) { return !targetTooColdToExtrude(e); } - #if EITHER(SINGLENOZZLE_STANDBY_TEMP, SINGLENOZZLE_STANDBY_FAN) + #if ANY(SINGLENOZZLE_STANDBY_TEMP, SINGLENOZZLE_STANDBY_FAN) #if ENABLED(SINGLENOZZLE_STANDBY_TEMP) static celsius_t singlenozzle_temp[EXTRUDERS]; #endif @@ -767,11 +767,11 @@ class Temperature { static raw_adc_t mintemp_raw_COOLER, maxtemp_raw_COOLER; #endif - #if BOTH(HAS_TEMP_BOARD, THERMAL_PROTECTION_BOARD) + #if ALL(HAS_TEMP_BOARD, THERMAL_PROTECTION_BOARD) static raw_adc_t mintemp_raw_BOARD, maxtemp_raw_BOARD; #endif - #if BOTH(HAS_TEMP_SOC, THERMAL_PROTECTION_SOC) + #if ALL(HAS_TEMP_SOC, THERMAL_PROTECTION_SOC) static raw_adc_t maxtemp_raw_SOC; #endif @@ -877,7 +877,7 @@ class Temperature { #if HAS_FAN static uint8_t fan_speed[FAN_COUNT]; - #define FANS_LOOP(I) LOOP_L_N(I, FAN_COUNT) + #define FANS_LOOP(I) for (uint8_t I = 0; I < FAN_COUNT; ++I) static void set_fan_speed(const uint8_t fan, const uint16_t speed); @@ -885,7 +885,7 @@ class Temperature { static void report_fan_speed(const uint8_t fan); #endif - #if EITHER(PROBING_FANS_OFF, ADVANCED_PAUSE_FANS_PAUSE) + #if ANY(PROBING_FANS_OFF, ADVANCED_PAUSE_FANS_PAUSE) static bool fans_paused; static uint8_t saved_fan_speed[FAN_COUNT]; #endif @@ -913,7 +913,7 @@ class Temperature { static void set_temp_fan_speed(const uint8_t fan, const uint16_t command_or_speed); #endif - #if EITHER(PROBING_FANS_OFF, ADVANCED_PAUSE_FANS_PAUSE) + #if ANY(PROBING_FANS_OFF, ADVANCED_PAUSE_FANS_PAUSE) void set_fans_paused(const bool p); #endif diff --git a/Marlin/src/module/tool_change.cpp b/Marlin/src/module/tool_change.cpp index cce3669355e1..d65b3fb32ab5 100644 --- a/Marlin/src/module/tool_change.cpp +++ b/Marlin/src/module/tool_change.cpp @@ -24,7 +24,6 @@ #include "tool_change.h" -#include "probe.h" #include "motion.h" #include "planner.h" #include "temperature.h" @@ -92,6 +91,10 @@ #include "../feature/pause.h" #endif +#if HAS_BED_PROBE + #include "probe.h" +#endif + #if ENABLED(TOOLCHANGE_FILAMENT_SWAP) #if TOOLCHANGE_FS_WIPE_RETRACT <= 0 #undef TOOLCHANGE_FS_WIPE_RETRACT @@ -250,7 +253,7 @@ void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_axis, 0. #elif ENABLED(PARKING_EXTRUDER) void pe_solenoid_init() { - LOOP_LE_N(n, 1) pe_solenoid_set_pin_state(n, !PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE); + for (uint8_t n = 0; n <= 1; ++n) pe_solenoid_set_pin_state(n, !PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE); } void pe_solenoid_set_pin_state(const uint8_t extruder_num, const uint8_t state) { @@ -1165,7 +1168,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { if (new_tool != old_tool || TERN0(PARKING_EXTRUDER, extruder_parked)) { // PARKING_EXTRUDER may need to attach old_tool when homing destination = current_position; - #if BOTH(TOOLCHANGE_FILAMENT_SWAP, HAS_FAN) && TOOLCHANGE_FS_FAN >= 0 + #if ALL(TOOLCHANGE_FILAMENT_SWAP, HAS_FAN) && TOOLCHANGE_FS_FAN >= 0 // Store and stop fan. Restored on any exit. REMEMBER(fan, thermalManager.fan_speed[TOOLCHANGE_FS_FAN], 0); #endif @@ -1277,7 +1280,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { fast_line_to_current(Z_AXIS); } move_nozzle_servo(new_tool); - #elif EITHER(MECHANICAL_SWITCHING_EXTRUDER, MECHANICAL_SWITCHING_NOZZLE) + #elif ANY(MECHANICAL_SWITCHING_EXTRUDER, MECHANICAL_SWITCHING_NOZZLE) if (!no_move) { current_position.z = _MIN(current_position.z + toolchange_settings.z_raise, _MIN(TERN(HAS_SOFTWARE_ENDSTOPS, soft_endstop.max.z, Z_MAX_POS), Z_MAX_POS)); fast_line_to_current(Z_AXIS); @@ -1308,7 +1311,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { const bool should_move = safe_to_move && !no_move && IsRunning(); if (should_move) { - #if EITHER(SINGLENOZZLE_STANDBY_TEMP, SINGLENOZZLE_STANDBY_FAN) + #if ANY(SINGLENOZZLE_STANDBY_TEMP, SINGLENOZZLE_STANDBY_FAN) thermalManager.singlenozzle_change(old_tool, new_tool); #endif @@ -1469,7 +1472,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { // If using MECHANICAL_SWITCHING extruder/nozzle, set HOTEND_OFFSET in Z axis after running EVENT_GCODE_TOOLCHANGE // so that nozzle does not lower below print surface if new hotend Z offset is higher than old hotend Z offset. - #if EITHER(MECHANICAL_SWITCHING_EXTRUDER, MECHANICAL_SWITCHING_NOZZLE) + #if ANY(MECHANICAL_SWITCHING_EXTRUDER, MECHANICAL_SWITCHING_NOZZLE) #if HAS_HOTEND_OFFSET xyz_pos_t diff = hotend_offset[new_tool] - hotend_offset[old_tool]; TERN_(DUAL_X_CARRIAGE, diff.x = 0); diff --git a/Marlin/src/pins/esp32/pins_GODI_CONTROLLER_V1_0.h b/Marlin/src/pins/esp32/pins_GODI_CONTROLLER_V1_0.h index 35fc4e035d81..6f8046988e37 100644 --- a/Marlin/src/pins/esp32/pins_GODI_CONTROLLER_V1_0.h +++ b/Marlin/src/pins/esp32/pins_GODI_CONTROLLER_V1_0.h @@ -129,7 +129,7 @@ // Heaters / Fans // -#if EITHER(EDUTRONICS_12864OLED_SH1106, EDUTRONICS_12864OLED_SSD1306) +#if ANY(EDUTRONICS_12864OLED_SH1106, EDUTRONICS_12864OLED_SSD1306) #define LCDSCREEN_NAME "EDUTRONICS 12864 OLED" #define BTN_EN2 1 #define BTN_EN1 3 diff --git a/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h b/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h index 546fa82c0d9f..2dea1edacc59 100644 --- a/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h +++ b/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h @@ -177,7 +177,7 @@ #if SD_CONNECTION_IS(ONBOARD) #define FORCE_SOFT_SPI #endif - #if BOTH(MKS_MINI_12864_V3, HAS_MEDIA) + #if ALL(MKS_MINI_12864_V3, HAS_MEDIA) #define PAUSE_LCD_FOR_BUSY_SD #endif #else diff --git a/Marlin/src/pins/linux/pins_RAMPS_LINUX.h b/Marlin/src/pins/linux/pins_RAMPS_LINUX.h index 4f32304dde9d..19ea927531b8 100644 --- a/Marlin/src/pins/linux/pins_RAMPS_LINUX.h +++ b/Marlin/src/pins/linux/pins_RAMPS_LINUX.h @@ -477,7 +477,7 @@ #define LCD_PINS_EN 51 // SID (MOSI) #define LCD_PINS_D4 52 // SCK (CLK) clock - #elif BOTH(IS_NEWPANEL, PANEL_ONE) + #elif ALL(IS_NEWPANEL, PANEL_ONE) #define LCD_PINS_RS 40 #define LCD_PINS_EN 42 @@ -509,7 +509,7 @@ #else - #if EITHER(MKS_12864OLED, MKS_12864OLED_SSD1306) + #if ANY(MKS_12864OLED, MKS_12864OLED_SSD1306) #define LCD_PINS_DC 25 // Set as output on init #define LCD_PINS_RS 27 // Pull low for 1s to init // DOGM SPI LCD Support @@ -593,7 +593,7 @@ #define LCD_SDSS SDSS #define SD_DETECT_PIN 49 - #elif EITHER(VIKI2, miniVIKI) + #elif ANY(VIKI2, miniVIKI) #define DOGLCD_CS 45 #define DOGLCD_A0 44 diff --git a/Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h b/Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h index 423c89b8c949..c498af3a64d9 100644 --- a/Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h +++ b/Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h @@ -130,7 +130,7 @@ #define LCD_PINS_EN P0_18 // (MOSI) EXP1-3 #define LCD_PINS_D4 P0_15 // (SCK) EXP1-5 - #if BOTH(HAS_MARLINUI_HD44780, IS_RRD_SC) + #if ALL(HAS_MARLINUI_HD44780, IS_RRD_SC) #error "REPRAP_DISCOUNT_SMART_CONTROLLER displays aren't supported by the BIQU B300 v1.0" #endif diff --git a/Marlin/src/pins/lpc1768/pins_BIQU_BQ111_A4.h b/Marlin/src/pins/lpc1768/pins_BIQU_BQ111_A4.h index 278ba12dd508..3fb29b90929d 100644 --- a/Marlin/src/pins/lpc1768/pins_BIQU_BQ111_A4.h +++ b/Marlin/src/pins/lpc1768/pins_BIQU_BQ111_A4.h @@ -107,7 +107,7 @@ #define LCD_PINS_EN P0_18 // (MOSI) EXP1-3 #define LCD_PINS_D4 P0_15 // (SCK) EXP1-5 - #if BOTH(HAS_MARLINUI_HD44780, IS_RRD_SC) + #if ALL(HAS_MARLINUI_HD44780, IS_RRD_SC) #error "REPRAP_DISCOUNT_SMART_CONTROLLER displays aren't supported by the BIQU BQ111-A4" #endif diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h index ec21a1b39dda..8cca8ec44081 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h @@ -407,7 +407,7 @@ #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN EXP1_06_PIN #endif diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h index 9aa6a2b21b02..a3fb8f648875 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h @@ -450,7 +450,7 @@ #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN EXP1_06_PIN #endif diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h index 2b01b4ce6f9a..75eea8e0f6ca 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h @@ -27,8 +27,8 @@ // https://github.com/bigtreetech/BTT-Expansion-module/tree/master/BTT%20EXP-MOT //#define BTT_MOTOR_EXPANSION -#if BOTH(HAS_WIRED_LCD, BTT_MOTOR_EXPANSION) - #if EITHER(CR10_STOCKDISPLAY, ENDER2_STOCKDISPLAY) +#if ALL(HAS_WIRED_LCD, BTT_MOTOR_EXPANSION) + #if ANY(CR10_STOCKDISPLAY, ENDER2_STOCKDISPLAY) #define EXP_MOT_USE_EXP2_ONLY 1 #else #error "You can't use both an LCD and a Motor Expansion Module on EXP1/EXP2 at the same time." diff --git a/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h b/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h index 6d76fb2c8fcc..a4150aa22f21 100644 --- a/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h +++ b/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h @@ -240,7 +240,7 @@ #define LCD_SDSS P0_28 // EXP2.4 #define LCD_PINS_EN P0_18 // EXP1.3 #define LCD_PINS_D4 P0_15 // EXP1.5 - #if EITHER(VIKI2, miniVIKI) + #if ANY(VIKI2, miniVIKI) #define DOGLCD_SCK SD_SCK_PIN #define DOGLCD_MOSI SD_MOSI_PIN #endif @@ -265,7 +265,7 @@ //#define FORCE_SOFT_SPI // Use this if default of hardware SPI causes display problems // results in LCD soft SPI mode 3, SD soft SPI mode 0 - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN P2_12 // J8-4 (LCD_D6 on FYSETC schematic) #endif diff --git a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h index 54a91e364d1f..42a0155471b2 100644 --- a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h +++ b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h @@ -371,7 +371,7 @@ #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN EXP1_06_PIN #endif diff --git a/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h b/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h index a6341ec5295d..f3b134cd36f4 100644 --- a/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h +++ b/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h @@ -207,9 +207,9 @@ #endif #ifndef FAN0_PIN - #if EITHER(FET_ORDER_EFB, FET_ORDER_EFF) // Hotend, Fan, Bed or Hotend, Fan, Fan + #if ANY(FET_ORDER_EFB, FET_ORDER_EFF) // Hotend, Fan, Bed or Hotend, Fan, Fan #define FAN0_PIN MOSFET_B_PIN - #elif EITHER(FET_ORDER_EEF, FET_ORDER_SF) // Hotend, Hotend, Fan or Spindle, Fan + #elif ANY(FET_ORDER_EEF, FET_ORDER_SF) // Hotend, Hotend, Fan or Spindle, Fan #define FAN0_PIN MOSFET_C_PIN #elif FET_ORDER_EEB // Hotend, Hotend, Bed #define FAN0_PIN P1_18 // (4) IO pin. Buffer needed @@ -353,7 +353,7 @@ //#define SHIFT_EN_PIN P1_22 // (41) J5-4 & AUX-4 #endif - #if EITHER(VIKI2, miniVIKI) + #if ANY(VIKI2, miniVIKI) #define DOGLCD_CS P0_16 // (16) #define DOGLCD_A0 P2_06 // (59) J3-8 & AUX-2 #define DOGLCD_SCK P0_15 // (52) (SCK) J3-9 & AUX-3 @@ -378,7 +378,7 @@ #define LCD_RESET_PIN P0_16 // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN P1_00 #endif diff --git a/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_GT.h b/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_GT.h index 5899cb0f503a..8412f1c12d3b 100644 --- a/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_GT.h +++ b/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_GT.h @@ -108,7 +108,7 @@ // // Display // -#if EITHER(VIKI2, miniVIKI) +#if ANY(VIKI2, miniVIKI) #define BEEPER_PIN P1_31 #define DOGLCD_A0 P2_06 #define DOGLCD_CS P0_16 diff --git a/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI.h b/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI.h index 1a8192bafe20..92e97ca8753d 100644 --- a/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI.h +++ b/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI.h @@ -158,7 +158,7 @@ //#define SHIFT_EN_PIN P1_22 // (41) J5-4 & AUX-4 #endif - #if EITHER(VIKI2, miniVIKI) + #if ANY(VIKI2, miniVIKI) #define BEEPER_PIN P1_30 // (37) may change if cable changes #define DOGLCD_CS P0_26 // (63) J5-3 & AUX-2 #define DOGLCD_SCK SD_SCK_PIN diff --git a/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h b/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h index 2e04f7869a73..966ff5ef957f 100644 --- a/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h +++ b/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h @@ -260,7 +260,7 @@ #define LCD_PINS_D7 EXP1_01_PIN #define ADC_KEYPAD_PIN P1_23 // Repurpose servo pin for ADC - CONNECTING TO 5V WILL DAMAGE THE BOARD! - #elif EITHER(MKS_MINI_12864, ENDER2_STOCKDISPLAY) + #elif ANY(MKS_MINI_12864, ENDER2_STOCKDISPLAY) #define BTN_EN1 EXP1_03_PIN #define BTN_EN2 EXP1_05_PIN diff --git a/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h b/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h index f86cd5d3c695..362aafe12e75 100644 --- a/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h +++ b/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h @@ -190,7 +190,7 @@ // A custom EXP1 cable is required colored LEDs. Pins 1-5, 9, 10 of the cable go to pins 1-5, 9, 10 // on the board's EXP1 connector. Pins 6, 7, and 8 of the EXP1 cable go to the Ethernet connector. // Rev 1.2 displays do NOT require the RGB LEDs. 2.0 and 2.1 displays do require RGB. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN P1_16 // EXP1-6 => Ethernet pin 6 (top row, 3 from left) #endif diff --git a/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h b/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h index e8c48c1b7a58..ba781466232e 100644 --- a/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h +++ b/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h @@ -389,7 +389,7 @@ #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN EXP1_06_PIN #endif diff --git a/Marlin/src/pins/lpc1769/pins_SMOOTHIEBOARD.h b/Marlin/src/pins/lpc1769/pins_SMOOTHIEBOARD.h index 3e7e784b59ab..3db18e4acfea 100644 --- a/Marlin/src/pins/lpc1769/pins_SMOOTHIEBOARD.h +++ b/Marlin/src/pins/lpc1769/pins_SMOOTHIEBOARD.h @@ -93,7 +93,7 @@ // // LCD / Controller // -#if EITHER(VIKI2, miniVIKI) +#if ANY(VIKI2, miniVIKI) #define BEEPER_PIN P1_31 #define DOGLCD_A0 P2_11 diff --git a/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h b/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h index 1982652af6c5..634e50c223af 100644 --- a/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h +++ b/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h @@ -217,7 +217,7 @@ #endif -#if EITHER(CR10_STOCKDISPLAY, MKS_MINI_12864) +#if ANY(CR10_STOCKDISPLAY, MKS_MINI_12864) #define BTN_EN1 EXP1_03_PIN #define BTN_EN2 EXP1_05_PIN #define BTN_ENC EXP1_02_PIN diff --git a/Marlin/src/pins/mega/pins_GT2560_REV_A.h b/Marlin/src/pins/mega/pins_GT2560_REV_A.h index 61c61f94fff4..783a93a85b93 100644 --- a/Marlin/src/pins/mega/pins_GT2560_REV_A.h +++ b/Marlin/src/pins/mega/pins_GT2560_REV_A.h @@ -47,14 +47,12 @@ #define Y_MAX_PIN 28 #define Z_MIN_PIN 30 -#if ENABLED(BLTOUCH) - #if MB(GT2560_REV_A_PLUS) - #define SERVO0_PIN 11 - #define Z_MAX_PIN 32 - #else - #define SERVO0_PIN 32 - #define Z_MAX_PIN -1 - #endif +#if ENABLED(BLTOUCH) && !defined(SERVO0_PIN) + #define SERVO0_PIN 32 +#endif + +#if SERVO0_PIN == 32 + #define Z_MAX_PIN -1 #else #define Z_MAX_PIN 32 #endif @@ -102,64 +100,100 @@ // // Misc. Functions // -#define SDSS 53 + +// Power monitoring pins - set to 0 for main VIN, 1 for dedicated bed supply rail. +// Don't forget to enable POWER_MONITOR_VOLTAGE in Configuration_adv.h +// and set POWER_MONITOR_VOLTS_PER_VOLT to 0.090909. +#define POWER_MONITOR_VOLTAGE_PIN 0 + +/** LCD SDCARD + * ------ ------ + * (TX1) 18 | 1 2 | 19 (RX1) (MISO) 50 | 1 2 | 52 (SCK) + * (RX2) 17 | 3 4 | 20 (SDA) 42 | 3 4 | 53 (SS) + * (TX2) 16 | 5 6 21 (SCL) 40 | 5 6 51 (MOSI) + * 5 | 7 8 | 6 38 | 7 8 | RESET + * GND | 9 10 | 5V GND | 9 10 | 5V/3V3 + * ------ ------ + * SV1 SV3 + * + * GT2560 LCD & SD headers follow typical EXP1 & EXP2 format. + * SD header voltage pin set by link pads beneath the header; R25 for 5V, R44 for 3.3V (default) + * Pins 20 (SDA) and 21 (SCL) have external 10K pull-ups on the board. + */ + +#define EXP1_01_PIN 18 // TX1 / BEEPER +#define EXP1_02_PIN 19 // RX1 / ENC +#define EXP1_03_PIN 17 // RX2 / CS +#define EXP1_04_PIN 20 // SDA / A0 +#define EXP1_05_PIN 16 // TX2 / LCD_RS +#define EXP1_06_PIN 21 // SCL / CS +#define EXP1_07_PIN 5 // D6 / A0 +#define EXP1_08_PIN 6 // D7 / D4 + +#define EXP2_01_PIN 50 // MISO +#define EXP2_02_PIN 52 // SCK +#define EXP2_03_PIN 42 // EN2 +#define EXP2_04_PIN 53 // SDSS +#define EXP2_05_PIN 40 // EN1 +#define EXP2_06_PIN 51 // MOSI +#define EXP2_07_PIN 38 // SD_DET +#define EXP2_08_PIN -1 // RESET + +#define SDSS EXP2_04_PIN #define LED_PIN 13 -#define PS_ON_PIN 12 -#define SUICIDE_PIN 54 // Must be enabled at startup to keep power flowing -#define KILL_PIN -1 #if HAS_WIRED_LCD - #define BEEPER_PIN 18 + #define BEEPER_PIN EXP1_01_PIN #if IS_NEWPANEL #if ENABLED(MKS_MINI_12864) - #define DOGLCD_A0 5 - #define DOGLCD_CS 21 - #define BTN_EN1 40 - #define BTN_EN2 42 + #define DOGLCD_CS EXP1_06_PIN + #define DOGLCD_A0 EXP1_07_PIN + #define BTN_EN1 EXP2_05_PIN + #define BTN_EN2 EXP2_03_PIN #elif ENABLED(FYSETC_MINI_12864) // Disconnect EXP2-1 and EXP2-2, otherwise future firmware upload won't work. - #define DOGLCD_A0 20 - #define DOGLCD_CS 17 + #define DOGLCD_CS EXP1_03_PIN + #define DOGLCD_A0 EXP1_04_PIN - #define NEOPIXEL_PIN 21 - #define BTN_EN1 42 - #define BTN_EN2 40 + #define NEOPIXEL_PIN EXP1_06_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN - #define LCD_RESET_PIN 16 + #define LCD_RESET_PIN EXP1_05_PIN #define LCD_CONTRAST_INIT 220 #define LCD_BACKLIGHT_PIN -1 #else - #define LCD_PINS_RS 20 - #define LCD_PINS_EN 17 - #define LCD_PINS_D4 16 - #define LCD_PINS_D5 21 - #define LCD_PINS_D6 5 - #define LCD_PINS_D7 6 - #define BTN_EN1 42 - #define BTN_EN2 40 + #define LCD_PINS_RS EXP1_04_PIN + #define LCD_PINS_EN EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_07_PIN + #define LCD_PINS_D7 EXP1_08_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN #endif - #define BTN_ENC 19 - #define SD_DETECT_PIN 38 + #define BTN_ENC EXP1_02_PIN + #define SD_DETECT_PIN EXP2_07_PIN #else // !IS_NEWPANEL - #define SHIFT_CLK_PIN 38 - #define SHIFT_LD_PIN 42 - #define SHIFT_OUT_PIN 40 - #define SHIFT_EN_PIN 17 - - #define LCD_PINS_RS 16 - #define LCD_PINS_EN 5 - #define LCD_PINS_D4 6 - #define LCD_PINS_D5 21 - #define LCD_PINS_D6 20 - #define LCD_PINS_D7 19 + #define SHIFT_CLK_PIN EXP2_07_PIN + #define SHIFT_LD_PIN EXP2_03_PIN + #define SHIFT_OUT_PIN EXP2_05_PIN + #define SHIFT_EN_PIN EXP1_03_PIN + + #define LCD_PINS_RS EXP1_05_PIN + #define LCD_PINS_EN EXP1_07_PIN + #define LCD_PINS_D4 EXP1_08_PIN + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_04_PIN + #define LCD_PINS_D7 EXP1_02_PIN #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder diff --git a/Marlin/src/pins/mega/pins_GT2560_REV_A_PLUS.h b/Marlin/src/pins/mega/pins_GT2560_REV_A_PLUS.h index a982a0e00e73..1905f58108d0 100644 --- a/Marlin/src/pins/mega/pins_GT2560_REV_A_PLUS.h +++ b/Marlin/src/pins/mega/pins_GT2560_REV_A_PLUS.h @@ -30,8 +30,6 @@ #define BOARD_INFO_NAME "GT2560 Rev.A+" -#include "pins_GT2560_REV_A.h" +#define SERVO0_PIN 11 -#if DISABLED(BLTOUCH) - #define SERVO0_PIN 32 -#endif +#include "pins_GT2560_REV_A.h" diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 6ee6401badfc..0ae0312daef3 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -61,7 +61,7 @@ #endif #endif -#if !(BOTH(HAS_WIRED_LCD, IS_NEWPANEL) && ANY(PANEL_ONE, VIKI2, miniVIKI, WYH_L12864, MINIPANEL, REPRAPWORLD_KEYPAD)) +#if !(ALL(HAS_WIRED_LCD, IS_NEWPANEL) && ANY(PANEL_ONE, VIKI2, miniVIKI, WYH_L12864, MINIPANEL, REPRAPWORLD_KEYPAD)) #define HAS_FREE_AUX2_PINS 1 #endif @@ -93,7 +93,7 @@ #if _ENDSTOP_IS_ANY(Y_MIN_PIN) || _ENDSTOP_IS_ANY(Y_MAX_PIN) #define NEEDS_Y_MINMAX 1 #endif -#if _ENDSTOP_IS_ANY(Z_MIN_PIN) || _ENDSTOP_IS_ANY(Z_MAX_PIN) || BOTH(Z_HOME_TO_MAX, Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) +#if _ENDSTOP_IS_ANY(Z_MIN_PIN) || _ENDSTOP_IS_ANY(Z_MAX_PIN) || ALL(Z_HOME_TO_MAX, Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) #define NEEDS_Z_MINMAX 1 #endif #undef _ENDSTOP_IS_ANY @@ -810,11 +810,11 @@ #elif MB(BTT_SKR_SE_BX_V3) #include "stm32h7/pins_BTT_SKR_SE_BX_V3.h" // STM32H7 env:BTT_SKR_SE_BX #elif MB(BTT_SKR_V3_0) - #include "stm32h7/pins_BTT_SKR_V3_0.h" // STM32H7 env:STM32H723Vx_btt env:STM32H743Vx_btt + #include "stm32h7/pins_BTT_SKR_V3_0.h" // STM32H743Vx/STM32H723VG env:STM32H743Vx_btt env:STM32H723VG_btt #elif MB(BTT_SKR_V3_0_EZ) - #include "stm32h7/pins_BTT_SKR_V3_0_EZ.h" // STM32H7 env:STM32H723Vx_btt env:STM32H743Vx_btt + #include "stm32h7/pins_BTT_SKR_V3_0_EZ.h" // STM32H743Vx/STM32H723VG env:STM32H743Vx_btt env:STM32H723VG_btt #elif MB(BTT_OCTOPUS_MAX_EZ_V1_0) - #include "stm32h7/pins_BTT_OCTOPUS_MAX_EZ.h" // STM32H7 env:STM32H723Vx_btt env:STM32H723Zx_btt + #include "stm32h7/pins_BTT_OCTOPUS_MAX_EZ.h" // STM32H723Zx/STM32H723VE env:STM32H723Zx_btt env:STM32H723VE_btt #elif MB(TEENSY41) #include "teensy4/pins_TEENSY41.h" // Teensy-4.x env:teensy41 #elif MB(T41U5XBB) diff --git a/Marlin/src/pins/pinsDebug.h b/Marlin/src/pins/pinsDebug.h index 3219b1b7a243..4d51de52c88e 100644 --- a/Marlin/src/pins/pinsDebug.h +++ b/Marlin/src/pins/pinsDebug.h @@ -100,7 +100,7 @@ const PinInfo pin_array[] PROGMEM = { */ #if SERIAL_IN_USE(0) - #if EITHER(AVR_ATmega2560_FAMILY, ARDUINO_ARCH_SAM) + #if ANY(AVR_ATmega2560_FAMILY, ARDUINO_ARCH_SAM) { RXD_NAME_0, 0, true }, { TXD_NAME_0, 1, true }, #elif AVR_ATmega1284_FAMILY @@ -113,7 +113,7 @@ const PinInfo pin_array[] PROGMEM = { #endif #if SERIAL_IN_USE(1) - #if EITHER(AVR_ATmega2560_FAMILY, ARDUINO_ARCH_SAM) + #if ANY(AVR_ATmega2560_FAMILY, ARDUINO_ARCH_SAM) { RXD_NAME_1, 19, true }, { TXD_NAME_1, 18, true }, #elif AVR_ATmega1284_FAMILY @@ -131,7 +131,7 @@ const PinInfo pin_array[] PROGMEM = { #endif #if SERIAL_IN_USE(2) - #if EITHER(AVR_ATmega2560_FAMILY, ARDUINO_ARCH_SAM) + #if ANY(AVR_ATmega2560_FAMILY, ARDUINO_ARCH_SAM) { RXD_NAME_2, 17, true }, { TXD_NAME_2, 16, true }, #elif defined(TARGET_LPC1768) @@ -146,7 +146,7 @@ const PinInfo pin_array[] PROGMEM = { #endif #if SERIAL_IN_USE(3) - #if EITHER(AVR_ATmega2560_FAMILY, ARDUINO_ARCH_SAM) + #if ANY(AVR_ATmega2560_FAMILY, ARDUINO_ARCH_SAM) { RXD_NAME_3, 15, true }, { TXD_NAME_3, 14, true }, #elif defined(TARGET_LPC1768) @@ -206,7 +206,7 @@ inline void report_pin_state_extended(const pin_t pin, const bool ignore, const return true; }; - LOOP_L_N(x, COUNT(pin_array)) { // scan entire array and report all instances of this pin + for (uint8_t x = 0; x < COUNT(pin_array); ++x) { // scan entire array and report all instances of this pin if (GET_ARRAY_PIN(x) == pin) { if (!found) { // report digital and analog pin number only on the first time through if (start_string) SERIAL_ECHOF(start_string); diff --git a/Marlin/src/pins/rambo/pins_RAMBO.h b/Marlin/src/pins/rambo/pins_RAMBO.h index e1ddf972d995..ba8046d6d0fb 100644 --- a/Marlin/src/pins/rambo/pins_RAMBO.h +++ b/Marlin/src/pins/rambo/pins_RAMBO.h @@ -212,7 +212,7 @@ #define LCD_PINS_D6 74 #define LCD_PINS_D7 75 - #if EITHER(VIKI2, miniVIKI) + #if ANY(VIKI2, miniVIKI) #define BEEPER_PIN 44 // NB: Panucatt's Viki 2.0 wiring diagram (v1.2) indicates that the // beeper/buzzer is connected to pin 33; however, the pin used in the diff --git a/Marlin/src/pins/rambo/pins_SCOOVO_X9H.h b/Marlin/src/pins/rambo/pins_SCOOVO_X9H.h index f0e107f398c0..0d212010e065 100644 --- a/Marlin/src/pins/rambo/pins_SCOOVO_X9H.h +++ b/Marlin/src/pins/rambo/pins_SCOOVO_X9H.h @@ -143,7 +143,7 @@ #define HOME_PIN BTN_HOME -#if EITHER(VIKI2, miniVIKI) +#if ANY(VIKI2, miniVIKI) #define BEEPER_PIN 44 // Pins for DOGM SPI LCD Support #define DOGLCD_A0 70 diff --git a/Marlin/src/pins/ramps/pins_3DRAG.h b/Marlin/src/pins/ramps/pins_3DRAG.h index 6f57b0eca62a..2d419e132179 100644 --- a/Marlin/src/pins/ramps/pins_3DRAG.h +++ b/Marlin/src/pins/ramps/pins_3DRAG.h @@ -117,7 +117,7 @@ #define SPINDLE_LASER_PWM_PIN 46 // Hardware PWM #define SPINDLE_LASER_ENA_PIN 62 // Pullup! #define SPINDLE_DIR_PIN 48 - #elif !BOTH(HAS_WIRED_LCD, IS_NEWPANEL) // Use expansion header if no LCD in use + #elif !ALL(HAS_WIRED_LCD, IS_NEWPANEL) // Use expansion header if no LCD in use #define SPINDLE_LASER_ENA_PIN 16 // Pullup or pulldown! #define SPINDLE_DIR_PIN 17 #if !NUM_SERVOS // Use servo connector if possible diff --git a/Marlin/src/pins/ramps/pins_AZTEEG_X3.h b/Marlin/src/pins/ramps/pins_AZTEEG_X3.h index 4d3722655df9..17581dca6241 100644 --- a/Marlin/src/pins/ramps/pins_AZTEEG_X3.h +++ b/Marlin/src/pins/ramps/pins_AZTEEG_X3.h @@ -54,7 +54,7 @@ #undef STAT_LED_RED_PIN #undef STAT_LED_BLUE_PIN -#if EITHER(VIKI2, miniVIKI) +#if ANY(VIKI2, miniVIKI) #undef DOGLCD_A0 #undef DOGLCD_CS diff --git a/Marlin/src/pins/ramps/pins_AZTEEG_X3_PRO.h b/Marlin/src/pins/ramps/pins_AZTEEG_X3_PRO.h index b0eee92c7218..ddd56b28e859 100644 --- a/Marlin/src/pins/ramps/pins_AZTEEG_X3_PRO.h +++ b/Marlin/src/pins/ramps/pins_AZTEEG_X3_PRO.h @@ -145,7 +145,7 @@ #undef BEEPER_PIN #define BEEPER_PIN 33 -#if EITHER(VIKI2, miniVIKI) +#if ANY(VIKI2, miniVIKI) #undef SD_DETECT_PIN #define SD_DETECT_PIN 49 // For easy adapter board #undef BEEPER_PIN @@ -172,7 +172,7 @@ #undef SPINDLE_DIR_PIN #if HAS_CUTTER // EXP2 header - #if EITHER(VIKI2, miniVIKI) + #if ANY(VIKI2, miniVIKI) #define BTN_EN2 31 // Pin 7 needed for Spindle PWM #endif #define SPINDLE_LASER_PWM_PIN 7 // Hardware PWM diff --git a/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h b/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h index fa5bbb5b9e75..824dbd9f2df8 100644 --- a/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h +++ b/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h @@ -249,7 +249,7 @@ #define LCD_RESET_PIN 23 // Must be high or open for LCD to operate normally. // Seems to work best if left open. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN 25 #endif diff --git a/Marlin/src/pins/ramps/pins_K8400.h b/Marlin/src/pins/ramps/pins_K8400.h index 56ec66191b32..bcb145825b24 100644 --- a/Marlin/src/pins/ramps/pins_K8400.h +++ b/Marlin/src/pins/ramps/pins_K8400.h @@ -53,7 +53,7 @@ #define X_STOP_PIN 3 #define Y_STOP_PIN 14 -#if EITHER(BLTOUCH, TOUCH_MI_PROBE) +#if ANY(BLTOUCH, TOUCH_MI_PROBE) #define INVERTED_PROBE_STATE #endif diff --git a/Marlin/src/pins/ramps/pins_LONGER3D_LKx_PRO.h b/Marlin/src/pins/ramps/pins_LONGER3D_LKx_PRO.h index 89da25d074fa..cb28762adc55 100644 --- a/Marlin/src/pins/ramps/pins_LONGER3D_LKx_PRO.h +++ b/Marlin/src/pins/ramps/pins_LONGER3D_LKx_PRO.h @@ -127,7 +127,7 @@ // Aux-1 | D19 D18 GND 5V | J21 | D4 D5 D6 GND | J17 | D11 GND 24V | J18 | D7 GND 5V | // ------------------ ---------------- --------------- ------------- -#if BOTH(CR10_STOCKDISPLAY, LONGER_LK5) +#if ALL(CR10_STOCKDISPLAY, LONGER_LK5) /** CR-10 Stock Display * ------ * BEEPER D11 | 1 2 | D15 ENC diff --git a/Marlin/src/pins/ramps/pins_MKS_GEN_13.h b/Marlin/src/pins/ramps/pins_MKS_GEN_13.h index 4cf66ed2cd41..9afdc62a53a8 100644 --- a/Marlin/src/pins/ramps/pins_MKS_GEN_13.h +++ b/Marlin/src/pins/ramps/pins_MKS_GEN_13.h @@ -63,7 +63,7 @@ // // LCD / Controller // -#if EITHER(VIKI2, miniVIKI) +#if ANY(VIKI2, miniVIKI) /** * VIKI2 Has two groups of wires with... * diff --git a/Marlin/src/pins/ramps/pins_RAMPS.h b/Marlin/src/pins/ramps/pins_RAMPS.h index 422991aba4c1..8b15f82736f9 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS.h +++ b/Marlin/src/pins/ramps/pins_RAMPS.h @@ -250,7 +250,7 @@ #ifndef HEATER_BED_PIN #define HEATER_BED_PIN MOSFET_C_PIN #endif - #if EITHER(HAS_MULTI_HOTEND, HEATERS_PARALLEL) + #if ANY(HAS_MULTI_HOTEND, HEATERS_PARALLEL) #define HEATER_1_PIN MOSFET_D_PIN #else #define FAN1_PIN MOSFET_D_PIN @@ -258,9 +258,9 @@ #endif #ifndef FAN0_PIN - #if EITHER(FET_ORDER_EFB, FET_ORDER_EFF) // Hotend, Fan, Bed or Hotend, Fan, Fan + #if ANY(FET_ORDER_EFB, FET_ORDER_EFF) // Hotend, Fan, Bed or Hotend, Fan, Fan #define FAN0_PIN MOSFET_B_PIN - #elif EITHER(FET_ORDER_EEF, FET_ORDER_SF) // Hotend, Hotend, Fan or Spindle, Fan + #elif ANY(FET_ORDER_EEF, FET_ORDER_SF) // Hotend, Hotend, Fan or Spindle, Fan #define FAN0_PIN MOSFET_C_PIN #elif FET_ORDER_EEB // Hotend, Hotend, Bed #define FAN0_PIN 4 // IO pin. Buffer needed @@ -567,7 +567,7 @@ #define EXP1_01_PIN AUX4_09_PIN #define EXP1_02_PIN AUX4_10_PIN - #if BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) + #if ALL(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) #define EXP2_03_PIN AUX4_11_PIN #define EXP2_05_PIN AUX4_12_PIN #define EXP2_08_PIN -1 // RESET @@ -598,7 +598,7 @@ #define LCD_PINS_EN EXP2_06_PIN // SID (MOSI) #define LCD_PINS_D4 EXP2_02_PIN // SCK (CLK) clock - #elif BOTH(IS_NEWPANEL, PANEL_ONE) + #elif ALL(IS_NEWPANEL, PANEL_ONE) #define LCD_PINS_RS AUX2_06_PIN #define LCD_PINS_EN AUX2_08_PIN @@ -642,7 +642,7 @@ #else - #if EITHER(MKS_12864OLED, MKS_12864OLED_SSD1306) + #if ANY(MKS_12864OLED, MKS_12864OLED_SSD1306) #define LCD_PINS_DC EXP1_06_PIN // Set as output on init #define LCD_PINS_RS EXP1_07_PIN // Pull low for 1s to init // DOGM SPI LCD Support @@ -736,7 +736,7 @@ #define SD_DETECT_PIN EXP2_07_PIN #endif - #elif EITHER(VIKI2, miniVIKI) + #elif ANY(VIKI2, miniVIKI) #define DOGLCD_CS AUX4_05_PIN #define DOGLCD_A0 AUX2_07_PIN @@ -777,7 +777,7 @@ #endif #define KILL_PIN EXP2_08_PIN - #elif EITHER(MKS_MINI_12864, FYSETC_MINI_12864) + #elif ANY(MKS_MINI_12864, FYSETC_MINI_12864) #define BTN_ENC EXP1_02_PIN #ifndef SD_DETECT_PIN @@ -814,7 +814,7 @@ #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN EXP1_06_PIN #endif @@ -914,7 +914,7 @@ #endif #endif -#if BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) +#if ALL(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING #error "CAUTION! LCD_FYSETC_TFT81050 requires wiring modifications. See 'pins_RAMPS.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" diff --git a/Marlin/src/pins/ramps/pins_RUMBA.h b/Marlin/src/pins/ramps/pins_RUMBA.h index 20c804367adb..1d2aeb4f0f88 100644 --- a/Marlin/src/pins/ramps/pins_RUMBA.h +++ b/Marlin/src/pins/ramps/pins_RUMBA.h @@ -190,7 +190,7 @@ // // LCD / Controller // -#if EITHER(MKS_12864OLED, MKS_12864OLED_SSD1306) +#if ANY(MKS_12864OLED, MKS_12864OLED_SSD1306) #define LCD_PINS_DC 38 // Set as output on init #define LCD_PINS_RS 41 // Pull low for 1s to init // DOGM SPI LCD Support @@ -209,7 +209,7 @@ #define LCD_RESET_PIN 18 // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN 41 #endif diff --git a/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h b/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h index bb74fe421a7f..7306272127e1 100644 --- a/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h +++ b/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h @@ -115,7 +115,7 @@ #if ENABLED(ANYCUBIC_4_MAX_PRO_ENDSTOPS) #define X_MAX_PIN 43 // AUX (2) #define Y_STOP_PIN 19 // Z+ -#elif EITHER(TRIGORILLA_MAPPING_CHIRON, TRIGORILLA_MAPPING_I3MEGA) +#elif ANY(TRIGORILLA_MAPPING_CHIRON, TRIGORILLA_MAPPING_I3MEGA) // Chiron uses AUX header for Y and Z endstops #define Y_STOP_PIN 42 // AUX (1) #define Z_STOP_PIN 43 // AUX (2) @@ -145,7 +145,7 @@ #define FIL_RUNOUT_PIN 19 // Z+ #endif - #if EITHER(TRIGORILLA_MAPPING_CHIRON, SWAP_Z_MOTORS) + #if ANY(TRIGORILLA_MAPPING_CHIRON, SWAP_Z_MOTORS) // Chiron and some Anycubic i3 MEGAs swap Z steppers #define Z_STEP_PIN 36 #define Z_DIR_PIN 34 @@ -159,7 +159,7 @@ #endif #endif -#if EITHER(ANYCUBIC_LCD_CHIRON, ANYCUBIC_LCD_I3MEGA) +#if ANY(ANYCUBIC_LCD_CHIRON, ANYCUBIC_LCD_I3MEGA) #ifndef BEEPER_PIN #define BEEPER_PIN EXP2_03_PIN // Chiron Standard Adapter #endif diff --git a/Marlin/src/pins/ramps/pins_TT_OSCAR.h b/Marlin/src/pins/ramps/pins_TT_OSCAR.h index d9c79f5da8eb..1edeb6b8fedf 100644 --- a/Marlin/src/pins/ramps/pins_TT_OSCAR.h +++ b/Marlin/src/pins/ramps/pins_TT_OSCAR.h @@ -279,7 +279,7 @@ #define LCD_PINS_EN 51 // SID (MOSI) #define LCD_PINS_D4 52 // SCK (CLK) clock - #elif BOTH(IS_NEWPANEL, PANEL_ONE) + #elif ALL(IS_NEWPANEL, PANEL_ONE) #define LCD_PINS_RS 40 #define LCD_PINS_EN 42 @@ -312,7 +312,7 @@ #else - #if EITHER(MKS_12864OLED, MKS_12864OLED_SSD1306) + #if ANY(MKS_12864OLED, MKS_12864OLED_SSD1306) #define LCD_PINS_DC 25 // Set as output on init #define LCD_PINS_RS 27 // Pull low for 1s to init // DOGM SPI LCD Support @@ -400,7 +400,7 @@ #define LCD_SDSS 53 #define SD_DETECT_PIN 49 - #elif EITHER(VIKI2, miniVIKI) + #elif ANY(VIKI2, miniVIKI) #define DOGLCD_CS 45 #define DOGLCD_A0 44 diff --git a/Marlin/src/pins/ramps/pins_ULTIMAKER_OLD.h b/Marlin/src/pins/ramps/pins_ULTIMAKER_OLD.h index a1b02aa06c73..0e3b25b4f670 100644 --- a/Marlin/src/pins/ramps/pins_ULTIMAKER_OLD.h +++ b/Marlin/src/pins/ramps/pins_ULTIMAKER_OLD.h @@ -116,7 +116,7 @@ // // Z Probe (when not Z_MIN_PIN) // -#if !defined(Z_MIN_PROBE_PIN) && !BOTH(HAS_CUTTER, BOARD_REV_1_0) +#if !defined(Z_MIN_PROBE_PIN) && !ALL(HAS_CUTTER, BOARD_REV_1_0) #define Z_MIN_PROBE_PIN Z_MAX_PIN #endif @@ -135,7 +135,7 @@ #define Z_DIR_PIN 39 #define Z_ENABLE_PIN 35 -#if BOTH(HAS_CUTTER, BOARD_REV_1_1_TO_1_3) && EXTRUDERS == 1 +#if ALL(HAS_CUTTER, BOARD_REV_1_1_TO_1_3) && EXTRUDERS == 1 // Move E0 to the spare and get Spindle/Laser signals from E0 #define E0_STEP_PIN 49 #define E0_DIR_PIN 47 @@ -166,7 +166,7 @@ // // LCD / Controller // -#if EITHER(BOARD_REV_1_0, BOARD_REV_1_1_TO_1_3) +#if ANY(BOARD_REV_1_0, BOARD_REV_1_1_TO_1_3) #define LCD_PINS_RS 24 #define LCD_PINS_EN 22 @@ -175,7 +175,7 @@ #define LCD_PINS_D6 32 #define LCD_PINS_D7 30 -#elif BOTH(BOARD_REV_1_5, HAS_WIRED_LCD) +#elif ALL(BOARD_REV_1_5, HAS_WIRED_LCD) #define BEEPER_PIN 18 @@ -225,7 +225,7 @@ // M3/M4/M5 - Spindle/Laser Control // #if HAS_CUTTER - #if EITHER(BOARD_REV_1_0, BOARD_REV_1_5) // Use the last three SW positions + #if ANY(BOARD_REV_1_0, BOARD_REV_1_5) // Use the last three SW positions #define SPINDLE_LASER_PWM_PIN 9 // 1.0: SW5 1.5: EXP3-7 ( "9") .. MUST BE HARDWARE PWM #define SPINDLE_LASER_ENA_PIN 8 // 1.0: SW6 1.5: EXP3-8 ( "8") .. Pin should have a pullup! #define SPINDLE_DIR_PIN 10 // 1.0: SW4 1.5: EXP3-6 ("10") diff --git a/Marlin/src/pins/ramps/pins_ZRIB_V53.h b/Marlin/src/pins/ramps/pins_ZRIB_V53.h index 2b8b583075a3..8d59eeb1f76d 100644 --- a/Marlin/src/pins/ramps/pins_ZRIB_V53.h +++ b/Marlin/src/pins/ramps/pins_ZRIB_V53.h @@ -361,7 +361,7 @@ // OLED 128x64 //================================================================================ -#if EITHER(ZONESTAR_12864OLED, ZONESTAR_12864OLED_SSD1306) +#if ANY(ZONESTAR_12864OLED, ZONESTAR_12864OLED_SSD1306) #define LCDSCREEN_NAME "ZONESTAR 12864OLED" #define LCD_SDSS 16 #define LCD_PINS_RS 23 // RESET Pull low for 1s to init @@ -372,7 +372,7 @@ #define BTN_ENC 29 #define BEEPER_PIN -1 #define KILL_PIN -1 - #if EITHER(OLED_HW_IIC, OLED_HW_SPI) + #if ANY(OLED_HW_IIC, OLED_HW_SPI) #error "Oops! You must choose SW SPI for ZRIB V53 board and connect the OLED screen to EXP1 connector." #else // SW_SPI #define DOGLCD_A0 LCD_PINS_DC diff --git a/Marlin/src/pins/sam/env_validate.h b/Marlin/src/pins/sam/env_validate.h index c6f4d76894be..c51583f0a13c 100644 --- a/Marlin/src/pins/sam/env_validate.h +++ b/Marlin/src/pins/sam/env_validate.h @@ -22,7 +22,7 @@ #ifndef ENV_VALIDATE_H #define ENV_VALIDATE_H -#if BOTH(ALLOW_MEGA1280, ALLOW_MEGA2560) && NOT_TARGET(__SAM3X8E__, __AVR_ATmega1280__, __AVR_ATmega2560__) +#if ALL(ALLOW_MEGA1280, ALLOW_MEGA2560) && NOT_TARGET(__SAM3X8E__, __AVR_ATmega1280__, __AVR_ATmega2560__) #error "Oops! Select 'Arduino Due or Mega' in 'Tools > Board.'" #elif ENABLED(ALLOW_MEGA2560) && NOT_TARGET(__SAM3X8E__, __AVR_ATmega2560__) #error "Oops! Select 'Arduino Due or Mega' in 'Tools > Board.'" diff --git a/Marlin/src/pins/sam/pins_KRATOS32.h b/Marlin/src/pins/sam/pins_KRATOS32.h index f4e3eb479cce..74da7a78f625 100644 --- a/Marlin/src/pins/sam/pins_KRATOS32.h +++ b/Marlin/src/pins/sam/pins_KRATOS32.h @@ -32,7 +32,7 @@ // // EEPROM // -#if EITHER(NO_EEPROM_SELECTED, I2C_EEPROM) +#if ANY(NO_EEPROM_SELECTED, I2C_EEPROM) #define I2C_EEPROM #define MARLIN_EEPROM_SIZE 0x1F400 // 16K #endif diff --git a/Marlin/src/pins/sam/pins_RADDS.h b/Marlin/src/pins/sam/pins_RADDS.h index 93011679595f..9a3edff0c989 100644 --- a/Marlin/src/pins/sam/pins_RADDS.h +++ b/Marlin/src/pins/sam/pins_RADDS.h @@ -32,7 +32,7 @@ // // EEPROM // -#if EITHER(NO_EEPROM_SELECTED, I2C_EEPROM) +#if ANY(NO_EEPROM_SELECTED, I2C_EEPROM) #define I2C_EEPROM #define MARLIN_EEPROM_SIZE 0x2000 // 8K #endif diff --git a/Marlin/src/pins/sam/pins_RAMPS_DUO.h b/Marlin/src/pins/sam/pins_RAMPS_DUO.h index 92de79bd7f23..b00d215cc7fb 100644 --- a/Marlin/src/pins/sam/pins_RAMPS_DUO.h +++ b/Marlin/src/pins/sam/pins_RAMPS_DUO.h @@ -68,7 +68,7 @@ // #if HAS_WIRED_LCD - #if BOTH(IS_NEWPANEL, PANEL_ONE) + #if ALL(IS_NEWPANEL, PANEL_ONE) #undef LCD_PINS_D4 #define LCD_PINS_D4 68 diff --git a/Marlin/src/pins/sam/pins_RAMPS_FD_V1.h b/Marlin/src/pins/sam/pins_RAMPS_FD_V1.h index 8f206d9f876b..f5587a6cbaa1 100644 --- a/Marlin/src/pins/sam/pins_RAMPS_FD_V1.h +++ b/Marlin/src/pins/sam/pins_RAMPS_FD_V1.h @@ -191,7 +191,7 @@ #define LCD_RESET_PIN EXP1_06_PIN // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN EXP1_05_PIN #endif @@ -219,7 +219,7 @@ #endif - #if EITHER(VIKI2, miniVIKI) + #if ANY(VIKI2, miniVIKI) #define DOGLCD_A0 EXP1_07_PIN #define KILL_PIN 51 #define STAT_LED_BLUE_PIN EXP1_03_PIN diff --git a/Marlin/src/pins/sam/pins_RURAMPS4D_11.h b/Marlin/src/pins/sam/pins_RURAMPS4D_11.h index 516063d158a9..64fad0e08123 100644 --- a/Marlin/src/pins/sam/pins_RURAMPS4D_11.h +++ b/Marlin/src/pins/sam/pins_RURAMPS4D_11.h @@ -227,7 +227,7 @@ #define SD_DETECT_PIN EXP2_07_PIN #endif - #if EITHER(RADDS_DISPLAY, IS_RRD_SC) + #if ANY(RADDS_DISPLAY, IS_RRD_SC) #define LCD_PINS_RS EXP1_04_PIN #define LCD_PINS_EN EXP1_03_PIN @@ -254,7 +254,7 @@ #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN EXP1_06_PIN // D5 #endif diff --git a/Marlin/src/pins/sam/pins_RURAMPS4D_13.h b/Marlin/src/pins/sam/pins_RURAMPS4D_13.h index 9e9aeb9fec17..1b66b766db2c 100644 --- a/Marlin/src/pins/sam/pins_RURAMPS4D_13.h +++ b/Marlin/src/pins/sam/pins_RURAMPS4D_13.h @@ -217,7 +217,7 @@ #define SD_DETECT_PIN EXP2_07_PIN #endif - #if EITHER(RADDS_DISPLAY, IS_RRD_SC) + #if ANY(RADDS_DISPLAY, IS_RRD_SC) #define LCD_PINS_RS EXP1_04_PIN #define LCD_PINS_EN EXP1_03_PIN @@ -244,7 +244,7 @@ #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN EXP1_06_PIN // D5 #endif diff --git a/Marlin/src/pins/samd/pins_BRICOLEMON_LITE_V1_0.h b/Marlin/src/pins/samd/pins_BRICOLEMON_LITE_V1_0.h index 8af1054a2cd1..6f41bd6848c9 100644 --- a/Marlin/src/pins/samd/pins_BRICOLEMON_LITE_V1_0.h +++ b/Marlin/src/pins/samd/pins_BRICOLEMON_LITE_V1_0.h @@ -238,7 +238,7 @@ //#define LCD_PINS_EN EXP2_06_PIN // SID (MOSI) //#define LCD_PINS_D4 EXP2_02_PIN // SCK (CLK) clock - #elif BOTH(IS_NEWPANEL, PANEL_ONE) + #elif ALL(IS_NEWPANEL, PANEL_ONE) // TO TEST //#define LCD_PINS_RS EXP1_02_PIN @@ -274,7 +274,7 @@ #else - #if EITHER(MKS_12864OLED, MKS_12864OLED_SSD1306) + #if ANY(MKS_12864OLED, MKS_12864OLED_SSD1306) // TO TEST //#define LCD_PINS_DC 25 // Set as output on init //#define LCD_PINS_RS 27 // Pull low for 1s to init @@ -372,7 +372,7 @@ //#define LCD_SDSS SDSS //#define SD_DETECT_PIN EXP2_10_PIN - #elif EITHER(VIKI2, miniVIKI) + #elif ANY(VIKI2, miniVIKI) // TO TEST //#define DOGLCD_CS 45 @@ -407,7 +407,7 @@ //#define SD_DETECT_PIN EXP2_10_PIN //#define KILL_PIN EXP1_01_PIN - #elif EITHER(MKS_MINI_12864, FYSETC_MINI_12864) + #elif ANY(MKS_MINI_12864, FYSETC_MINI_12864) // TO TEST //#define BEEPER_PIN EXP1_06_PIN @@ -452,7 +452,7 @@ //#define LCD_RESET_PIN 23 // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN // TO TEST //#define RGB_LED_R_PIN 25 diff --git a/Marlin/src/pins/samd/pins_BRICOLEMON_V1_0.h b/Marlin/src/pins/samd/pins_BRICOLEMON_V1_0.h index 7378731c9071..699f10ed481e 100644 --- a/Marlin/src/pins/samd/pins_BRICOLEMON_V1_0.h +++ b/Marlin/src/pins/samd/pins_BRICOLEMON_V1_0.h @@ -291,7 +291,7 @@ //#define LCD_PINS_EN EXP2_06_PIN // SID (MOSI) //#define LCD_PINS_D4 EXP2_02_PIN // SCK (CLK) clock - #elif BOTH(IS_NEWPANEL, PANEL_ONE) + #elif ALL(IS_NEWPANEL, PANEL_ONE) // TO TEST //#define LCD_PINS_RS EXP1_02_PIN @@ -327,7 +327,7 @@ #else - #if EITHER(MKS_12864OLED, MKS_12864OLED_SSD1306) + #if ANY(MKS_12864OLED, MKS_12864OLED_SSD1306) // TO TEST //#define LCD_PINS_DC 25 // Set as output on init //#define LCD_PINS_RS 27 // Pull low for 1s to init @@ -424,7 +424,7 @@ //#define LCD_SDSS SDSS //#define SD_DETECT_PIN EXP2_10_PIN - #elif EITHER(VIKI2, miniVIKI) + #elif ANY(VIKI2, miniVIKI) // TO TEST //#define DOGLCD_CS 45 @@ -459,7 +459,7 @@ //#define SD_DETECT_PIN EXP2_10_PIN //#define KILL_PIN EXP1_01_PIN - #elif EITHER(MKS_MINI_12864, FYSETC_MINI_12864) + #elif ANY(MKS_MINI_12864, FYSETC_MINI_12864) // TO TEST //#define BEEPER_PIN EXP1_06_PIN @@ -504,7 +504,7 @@ //#define LCD_RESET_PIN 23 // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN // TO TEST //#define RGB_LED_R_PIN 25 diff --git a/Marlin/src/pins/samd/pins_MINITRONICS20.h b/Marlin/src/pins/samd/pins_MINITRONICS20.h index 804750b69a3d..8c0daa497b01 100644 --- a/Marlin/src/pins/samd/pins_MINITRONICS20.h +++ b/Marlin/src/pins/samd/pins_MINITRONICS20.h @@ -197,7 +197,7 @@ #define BTN_EN1 27 #define BTN_EN2 33 - #elif BOTH(IS_NEWPANEL, PANEL_ONE) + #elif ALL(IS_NEWPANEL, PANEL_ONE) // TO TEST //#define LCD_PINS_RS EXP1_02_PIN @@ -233,7 +233,7 @@ #else - #if EITHER(MKS_12864OLED, MKS_12864OLED_SSD1306) + #if ANY(MKS_12864OLED, MKS_12864OLED_SSD1306) // TO TEST //#define LCD_PINS_DC 25 // Set as output on init //#define LCD_PINS_RS 27 // Pull low for 1s to init @@ -322,7 +322,7 @@ //#define LCD_SDSS SDSS //#define SD_DETECT_PIN EXP2_10_PIN - #elif EITHER(VIKI2, miniVIKI) + #elif ANY(VIKI2, miniVIKI) // TO TEST //#define DOGLCD_CS 45 @@ -357,7 +357,7 @@ //#define SD_DETECT_PIN EXP2_10_PIN //#define KILL_PIN EXP1_01_PIN - #elif EITHER(MKS_MINI_12864, FYSETC_MINI_12864) + #elif ANY(MKS_MINI_12864, FYSETC_MINI_12864) // TO TEST //#define BEEPER_PIN EXP1_06_PIN @@ -402,7 +402,7 @@ //#define LCD_RESET_PIN 23 // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN // TO TEST //#define RGB_LED_R_PIN 25 diff --git a/Marlin/src/pins/samd/pins_RAMPS_144.h b/Marlin/src/pins/samd/pins_RAMPS_144.h index a762d3cdbdcc..3e5d563929ed 100644 --- a/Marlin/src/pins/samd/pins_RAMPS_144.h +++ b/Marlin/src/pins/samd/pins_RAMPS_144.h @@ -276,7 +276,7 @@ //#define LCD_PINS_EN 51 // SID (MOSI) //#define LCD_PINS_D4 52 // SCK (CLK) clock - #elif BOTH(IS_NEWPANEL, PANEL_ONE) + #elif ALL(IS_NEWPANEL, PANEL_ONE) // TO TEST //#define LCD_PINS_RS 40 @@ -312,7 +312,7 @@ #else - #if EITHER(MKS_12864OLED, MKS_12864OLED_SSD1306) + #if ANY(MKS_12864OLED, MKS_12864OLED_SSD1306) // TO TEST //#define LCD_PINS_DC 25 // Set as output on init //#define LCD_PINS_RS 27 // Pull low for 1s to init @@ -406,7 +406,7 @@ //#define LCD_SDSS SDSS //#define SD_DETECT_PIN 49 - #elif EITHER(VIKI2, miniVIKI) + #elif ANY(VIKI2, miniVIKI) // TO TEST //#define DOGLCD_CS 45 @@ -442,7 +442,7 @@ //#define SD_DETECT_PIN 49 //#define KILL_PIN 41 - #elif EITHER(MKS_MINI_12864, FYSETC_MINI_12864) + #elif ANY(MKS_MINI_12864, FYSETC_MINI_12864) // TO TEST //#define BEEPER_PIN 37 @@ -483,7 +483,7 @@ //#define LCD_RESET_PIN 23 // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN // TO TEST //#define RGB_LED_R_PIN 25 diff --git a/Marlin/src/pins/sanguino/pins_MELZI_CREALITY_E2.h b/Marlin/src/pins/sanguino/pins_MELZI_CREALITY_E2.h index 0d021e1bf694..4ded3294b950 100644 --- a/Marlin/src/pins/sanguino/pins_MELZI_CREALITY_E2.h +++ b/Marlin/src/pins/sanguino/pins_MELZI_CREALITY_E2.h @@ -56,7 +56,7 @@ // // LCD / Controller // -#if EITHER(CR10_STOCKDISPLAY, ENDER2_STOCKDISPLAY) +#if ANY(CR10_STOCKDISPLAY, ENDER2_STOCKDISPLAY) #if ENABLED(CR10_STOCKDISPLAY) #if ENABLED(SDSUPPORT) #error "Cannot have SDSUPPORT with CR10_STOCKDISPLAY on this motherboard." // Hardware SDCARD SCK and MOSI pins are reallocated. diff --git a/Marlin/src/pins/sanguino/pins_MELZI_TRONXY.h b/Marlin/src/pins/sanguino/pins_MELZI_TRONXY.h index 6b47d9186c41..7e4cc22bbe8f 100644 --- a/Marlin/src/pins/sanguino/pins_MELZI_TRONXY.h +++ b/Marlin/src/pins/sanguino/pins_MELZI_TRONXY.h @@ -32,7 +32,7 @@ #define LCD_SDSS -1 -#if EITHER(CR10_STOCKDISPLAY, LCD_FOR_MELZI) +#if ANY(CR10_STOCKDISPLAY, LCD_FOR_MELZI) #define LCD_PINS_RS 30 #define LCD_PINS_EN 28 #define LCD_PINS_D4 16 diff --git a/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h b/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h index 9a80ca2e63aa..b99437ac93e5 100644 --- a/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h +++ b/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h @@ -133,7 +133,7 @@ #define LCD_BACKLIGHT_PIN 17 // LCD backlight LED #endif -#if !HAS_CUTTER && ENABLED(SANGUINOLOLU_V_1_2) && !BOTH(HAS_WIRED_LCD, IS_NEWPANEL) // try to use IO Header +#if !HAS_CUTTER && ENABLED(SANGUINOLOLU_V_1_2) && !ALL(HAS_WIRED_LCD, IS_NEWPANEL) // try to use IO Header #define CASE_LIGHT_PIN 4 // Hardware PWM - see if IO Header is available #endif @@ -270,7 +270,7 @@ // M3/M4/M5 - Spindle/Laser Control // #if HAS_CUTTER - #if !MB(AZTEEG_X1) && ENABLED(SANGUINOLOLU_V_1_2) && !BOTH(HAS_WIRED_LCD, IS_NEWPANEL) // try to use IO Header + #if !MB(AZTEEG_X1) && ENABLED(SANGUINOLOLU_V_1_2) && !ALL(HAS_WIRED_LCD, IS_NEWPANEL) // try to use IO Header #define SPINDLE_LASER_PWM_PIN 4 // Hardware PWM #define SPINDLE_LASER_ENA_PIN 10 // Pullup or pulldown! diff --git a/Marlin/src/pins/sanguino/pins_ZMIB_V2.h b/Marlin/src/pins/sanguino/pins_ZMIB_V2.h index 1e449579cf40..438acb79c789 100644 --- a/Marlin/src/pins/sanguino/pins_ZMIB_V2.h +++ b/Marlin/src/pins/sanguino/pins_ZMIB_V2.h @@ -92,7 +92,7 @@ #define X_MIN_PIN 21 #define Y_MIN_PIN 18 -#if EITHER(Z6S_ZFAULT, Z6BS_ZFAULT) +#if ANY(Z6S_ZFAULT, Z6BS_ZFAULT) #define Z_MIN_PIN 25 #else #define Z_MIN_PIN 13 @@ -109,7 +109,7 @@ #define Y_DIR_PIN 19 #define Y_ENABLE_PIN 24 -#if EITHER(Z6S_ZFAULT, Z6BS_ZFAULT) +#if ANY(Z6S_ZFAULT, Z6BS_ZFAULT) #define Z_STEP_PIN 27 #define Z_DIR_PIN 26 #else @@ -119,7 +119,7 @@ #define Z_ENABLE_PIN 24 -#if EITHER(Z6S_ZFAULT, Z6BS_ZFAULT) +#if ANY(Z6S_ZFAULT, Z6BS_ZFAULT) #define E0_STEP_PIN 15 #define E0_DIR_PIN 14 #else @@ -150,7 +150,7 @@ // // Filament Runout Sensor // -#if EITHER(Z6S_ZFAULT, Z6BS_ZFAULT) +#if ANY(Z6S_ZFAULT, Z6BS_ZFAULT) #define FIL_RUNOUT_PIN 13 #else #define FIL_RUNOUT_PIN 25 // Z-MIN @@ -201,7 +201,7 @@ #define BOARD_ST7920_DELAY_2 DELAY_2_NOP #define BOARD_ST7920_DELAY_3 DELAY_2_NOP -#elif EITHER(ZONESTAR_12864OLED, ZONESTAR_12864OLED_SSD1306) +#elif ANY(ZONESTAR_12864OLED, ZONESTAR_12864OLED_SSD1306) // // OLED 128x64 // diff --git a/Marlin/src/pins/sensitive_pins.h b/Marlin/src/pins/sensitive_pins.h index e655663a73d4..7264a2653968 100644 --- a/Marlin/src/pins/sensitive_pins.h +++ b/Marlin/src/pins/sensitive_pins.h @@ -650,7 +650,7 @@ #endif #endif -#elif EITHER(HAS_MULTI_EXTRUDER, MIXING_EXTRUDER) +#elif ANY(HAS_MULTI_EXTRUDER, MIXING_EXTRUDER) #undef _E1_PINS #define _E1_PINS E1_STEP_PIN, E1_DIR_PIN, E1_ENABLE_PIN, _E1_CS _E1_MS1 _E1_MS2 _E1_MS3 diff --git a/Marlin/src/pins/stm32f1/pins_BEAST.h b/Marlin/src/pins/stm32f1/pins_BEAST.h index eca4529636ba..b136ca52cd70 100644 --- a/Marlin/src/pins/stm32f1/pins_BEAST.h +++ b/Marlin/src/pins/stm32f1/pins_BEAST.h @@ -131,7 +131,7 @@ #error "LCD_I2C_PANELOLU2 is not supported." #elif ENABLED(LCD_I2C_VIKI) #error "LCD_I2C_VIKI is not supported." - #elif EITHER(VIKI2, miniVIKI) + #elif ANY(VIKI2, miniVIKI) #error "VIKI2 / miniVIKI is not supported." #elif ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) #error "ELB_FULL_GRAPHIC_CONTROLLER is not supported." diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h index 5f3dc781503d..8be66eedb570 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h @@ -31,7 +31,7 @@ // Ignore temp readings during development. //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) +#if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION #define EEPROM_PAGE_SIZE (0x800U) // 2K #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) @@ -204,7 +204,7 @@ #define LCD_PINS_D7 EXP1_01_PIN #define ADC_KEYPAD_PIN PA1 // Repurpose servo pin for ADC - CONNECTING TO 5V WILL DAMAGE THE BOARD! - #elif EITHER(MKS_MINI_12864, ENDER2_STOCKDISPLAY) + #elif ANY(MKS_MINI_12864, ENDER2_STOCKDISPLAY) /** Creality Ender-2 display pinout * ------ @@ -296,7 +296,7 @@ #endif // HAS_WIRED_LCD -#if BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) +#if ALL(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING #error "CAUTION! LCD_FYSETC_TFT81050 requires wiring modifications. See 'pins_BTT_SKR_E3_DIP.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" @@ -352,7 +352,7 @@ #define SD_SCK_PIN PA5 #define SD_MISO_PIN PA6 #define SD_MOSI_PIN PA7 -#elif SD_CONNECTION_IS(LCD) && BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) +#elif SD_CONNECTION_IS(LCD) && ALL(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) #define SD_DETECT_PIN EXP1_01_PIN #define SD_SS_PIN EXP1_05_PIN #elif SD_CONNECTION_IS(CUSTOM_CABLE) diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h index 689e73c4f3e1..c86e2f750452 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h @@ -31,7 +31,7 @@ // Ignore temp readings during development. //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) +#if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION #define EEPROM_PAGE_SIZE (0x800U) // 2K #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) @@ -114,15 +114,15 @@ #define USB_CONNECT_INVERTING false /** - * SKR Mini E3 V1.0, V1.2 - * ------ + * SKR Mini E3 V1.0, V1.2 + * ------ * (BEEPER) PB5 | 1 2 | PB6 (BTN_ENC) * (BTN_EN1) PA9 | 3 4 | RESET * (BTN_EN2) PA10 5 6 | PB9 (LCD_D4) * (LCD_RS) PB8 | 7 8 | PB7 (LCD_EN) * GND | 9 10 | 5V - * ------ - * EXP1 + * ------ + * EXP1 */ #ifndef EXP1_02_PIN #define EXP1_02_PIN PB6 @@ -217,7 +217,7 @@ #define LCD_PINS_D7 EXP1_01_PIN #define ADC_KEYPAD_PIN PA1 // Repurpose servo pin for ADC - CONNECTING TO 5V WILL DAMAGE THE BOARD! - #elif EITHER(MKS_MINI_12864, ENDER2_STOCKDISPLAY) + #elif ANY(MKS_MINI_12864, ENDER2_STOCKDISPLAY) #define BTN_ENC EXP1_02_PIN #define BTN_EN1 EXP1_03_PIN @@ -342,7 +342,7 @@ #endif // HAS_WIRED_LCD -#if BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) +#if ALL(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING #error "CAUTION! LCD_FYSETC_TFT81050 requires wiring modifications. See 'pins_BTT_SKR_MINI_E3_common.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" @@ -396,7 +396,7 @@ #if SD_CONNECTION_IS(ONBOARD) #define SD_DETECT_PIN PC4 -#elif SD_CONNECTION_IS(LCD) && (BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) || IS_TFTGLCD_PANEL) +#elif SD_CONNECTION_IS(LCD) && (ALL(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) || IS_TFTGLCD_PANEL) #define SD_DETECT_PIN EXP1_01_PIN #define SD_SS_PIN EXP1_05_PIN #elif SD_CONNECTION_IS(CUSTOM_CABLE) diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h index 851eee8296b2..6719b090495b 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h @@ -31,7 +31,7 @@ // Ignore temp readings during development. //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) +#if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION #define EEPROM_PAGE_SIZE (0x800U) // 2K #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) @@ -142,7 +142,7 @@ // // LCD / Controller // -#if EITHER(TFT_COLOR_UI, TFT_CLASSIC_UI) +#if ANY(TFT_COLOR_UI, TFT_CLASSIC_UI) #define BEEPER_PIN EXP1_01_PIN #define BTN_ENC EXP1_02_PIN #define BTN_EN1 EXP2_03_PIN @@ -221,7 +221,7 @@ //#define LED_PIN EXP1_07_PIN // green //#define LED_PIN EXP1_08_PIN // blue - //#if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + //#if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) // #ifndef RGB_LED_R_PIN // #define RGB_LED_R_PIN EXP1_06_PIN // #endif diff --git a/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h b/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h index 015d8c03ee2b..1d501e512b26 100644 --- a/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h +++ b/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h @@ -41,7 +41,7 @@ // // EEPROM // -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) +#if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION #define EEPROM_PAGE_SIZE 0x800U // 2K #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) diff --git a/Marlin/src/pins/stm32f1/pins_CHITU3D.h b/Marlin/src/pins/stm32f1/pins_CHITU3D.h index 73030c8ef6eb..2074bbeccec1 100644 --- a/Marlin/src/pins/stm32f1/pins_CHITU3D.h +++ b/Marlin/src/pins/stm32f1/pins_CHITU3D.h @@ -104,7 +104,7 @@ #define LCD_PINS_RS PD1 // 49 // CS chip select /SS chip slave select #define LCD_PINS_EN PD3 // 51 // SID (MOSI) #define LCD_PINS_D4 PD4 // 52 // SCK (CLK) clock - #elif BOTH(IS_NEWPANEL, PANEL_ONE) + #elif ALL(IS_NEWPANEL, PANEL_ONE) #define LCD_PINS_RS PB8 #define LCD_PINS_EN PD2 #define LCD_PINS_D4 PB12 @@ -171,7 +171,7 @@ #define LCD_SDSS PD5 // 53 #define SD_DETECT_PIN PD1 // 49 - #elif EITHER(VIKI2, miniVIKI) + #elif ANY(VIKI2, miniVIKI) #define BEEPER_PIN PC1 // 33 diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V24S1_301.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V24S1_301.h index af9a6d891e31..ce942ba5450e 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V24S1_301.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V24S1_301.h @@ -33,7 +33,7 @@ #define E_ERROR 1 #endif -#if BOTH(BLTOUCH, Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) +#if ALL(BLTOUCH, Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) #error "Disable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN when using BLTOUCH with Creality V24S1-301." #endif diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V25S1.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V25S1.h index f78bad624d28..5657a7995027 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V25S1.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V25S1.h @@ -52,7 +52,7 @@ #define IIC_EEPROM_SDA PA11 #define IIC_EEPROM_SCL PA12 #define MARLIN_EEPROM_SIZE 0x800 // 2K (24C16) -#elif EITHER(SDCARD_EEPROM_EMULATION, FLASH_EEPROM_EMULATION) +#elif ANY(SDCARD_EEPROM_EMULATION, FLASH_EEPROM_EMULATION) #define MARLIN_EEPROM_SIZE 0x800 // 2K #endif diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h index 3d0a1885af75..96b3007ca650 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h @@ -183,7 +183,7 @@ #define EXP3_07_PIN PB12 #define EXP3_08_PIN PB15 -#elif EITHER(VET6_12864_LCD, DWIN_VET6_CREALITY_LCD) +#elif ANY(VET6_12864_LCD, DWIN_VET6_CREALITY_LCD) /** * VET6 12864 LCD @@ -204,7 +204,7 @@ #define EXP3_07_PIN PA4 #define EXP3_08_PIN PA7 -#elif EITHER(CR10_STOCKDISPLAY, FYSETC_MINI_12864_2_1) +#elif ANY(CR10_STOCKDISPLAY, FYSETC_MINI_12864_2_1) #error "Define RET6_12864_LCD or VET6_12864_LCD to select pins for the LCD with the Creality V4 controller." #endif diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h index 7a7ec355084f..2e0de876410b 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h @@ -164,7 +164,7 @@ #define EXP3_07_PIN PB12 #define EXP3_08_PIN PB15 -#elif EITHER(VET6_12864_LCD, DWIN_VET6_CREALITY_LCD) +#elif ANY(VET6_12864_LCD, DWIN_VET6_CREALITY_LCD) /** * VET6 12864 LCD diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V521.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V521.h index 81cb1e1f790e..d555c0aaa12d 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V521.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V521.h @@ -168,7 +168,7 @@ #define EXP3_07_PIN PB12 #define EXP3_08_PIN PB15 -#elif EITHER(VET6_12864_LCD, DWIN_VET6_CREALITY_LCD) +#elif ANY(VET6_12864_LCD, DWIN_VET6_CREALITY_LCD) /** * VET6 12864 LCD diff --git a/Marlin/src/pins/stm32f1/pins_ERYONE_ERY32_MINI.h b/Marlin/src/pins/stm32f1/pins_ERYONE_ERY32_MINI.h index 7a1f1e6cce32..b18bd09de894 100644 --- a/Marlin/src/pins/stm32f1/pins_ERYONE_ERY32_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_ERYONE_ERY32_MINI.h @@ -39,7 +39,7 @@ #define DISABLE_JTAG //#define ENABLE_SPI3 -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) +#if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION #define EEPROM_PAGE_SIZE (0x800U) // 2K #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) @@ -98,7 +98,7 @@ #define FAN1_PIN PD12 #elif DISABLED(FET_ORDER_SF) // Not Spindle, Fan (i.e., "EFBF" or "EFBE") #define HEATER_BED_PIN PD12 - #if EITHER(HAS_MULTI_HOTEND, HEATERS_PARALLEL) + #if ANY(HAS_MULTI_HOTEND, HEATERS_PARALLEL) #define HEATER_1_PIN PB9 #else #define FAN1_PIN PB9 @@ -106,9 +106,9 @@ #endif #ifndef FAN0_PIN - #if EITHER(FET_ORDER_EFB, FET_ORDER_EFF) // Hotend, Fan, Bed or Hotend, Fan, Fan + #if ANY(FET_ORDER_EFB, FET_ORDER_EFF) // Hotend, Fan, Bed or Hotend, Fan, Fan #define FAN0_PIN PB5 - #elif EITHER(FET_ORDER_EEF, FET_ORDER_SF) // Hotend, Hotend, Fan or Spindle, Fan + #elif ANY(FET_ORDER_EEF, FET_ORDER_SF) // Hotend, Hotend, Fan or Spindle, Fan #define FAN0_PIN PD12 #elif ENABLED(FET_ORDER_EEB) // Hotend, Hotend, Bed #define FAN0_PIN -1 // IO pin. Buffer needed diff --git a/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h b/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h index bdfe24cad010..a0c2ed1dc827 100644 --- a/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h +++ b/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h @@ -51,7 +51,7 @@ // // EEPROM // -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) +#if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION #define EEPROM_PAGE_SIZE (0x800U) // 2K #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) diff --git a/Marlin/src/pins/stm32f1/pins_FLY_MINI.h b/Marlin/src/pins/stm32f1/pins_FLY_MINI.h index f7ef25419fd1..69e11be20cf5 100644 --- a/Marlin/src/pins/stm32f1/pins_FLY_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_FLY_MINI.h @@ -30,7 +30,7 @@ // // Flash EEPROM Emulation // -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) +#if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION #define EEPROM_PAGE_SIZE 0x800 // 2K #define EEPROM_START_ADDRESS (0x8000000 + 256 * 1024 - 2 * EEPROM_PAGE_SIZE) // 256K firmware space diff --git a/Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h b/Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h index c4fde59c47dd..93ef7b75d4e7 100644 --- a/Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h +++ b/Marlin/src/pins/stm32f1/pins_FYSETC_AIO_II.h @@ -38,7 +38,7 @@ // // Flash EEPROM Emulation // -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) +#if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION #define EEPROM_PAGE_SIZE (0x800U) // 2K #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) diff --git a/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h b/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h index 47bea172a8aa..49b6f25a47e6 100644 --- a/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h +++ b/Marlin/src/pins/stm32f1/pins_FYSETC_CHEETAH.h @@ -35,7 +35,7 @@ #define RESET_STEPPERS_ON_MEDIA_INSERT #define DISABLE_JTAG -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) +#if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION #define EEPROM_PAGE_SIZE (0x800U) // 2K #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) @@ -164,7 +164,7 @@ #define DOGLCD_SCK EXP1_06_PIN #define DOGLCD_MOSI EXP1_08_PIN - #if EITHER(FYSETC_MINI_12864, U8GLIB_ST7920) + #if ANY(FYSETC_MINI_12864, U8GLIB_ST7920) #define FORCE_SOFT_SPI #endif //#define LCD_SCREEN_ROTATE 180 // 0, 90, 180, 270 diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_MINI.h b/Marlin/src/pins/stm32f1/pins_GTM32_MINI.h index 9c136c11f65a..b97ccc8ec738 100644 --- a/Marlin/src/pins/stm32f1/pins_GTM32_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_GTM32_MINI.h @@ -51,7 +51,7 @@ //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 // Enable EEPROM Emulation for this board as it doesn't have EEPROM -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) +#if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION #define MARLIN_EEPROM_SIZE 0x1000 // 4K #endif diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h b/Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h index 2cd77f42b204..4bb8c5dee627 100644 --- a/Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h +++ b/Marlin/src/pins/stm32f1/pins_GTM32_MINI_A30.h @@ -51,7 +51,7 @@ //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 // Enable EEPROM Emulation for this board as it doesn't have EEPROM -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) +#if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION #define MARLIN_EEPROM_SIZE 0x1000 // 4K #endif diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h b/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h index 5e012c177d44..57abf7aca79e 100644 --- a/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h +++ b/Marlin/src/pins/stm32f1/pins_GTM32_PRO_VB.h @@ -56,7 +56,7 @@ //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 // Enable EEPROM Emulation for this board as it doesn't have EEPROM -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) +#if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION #define MARLIN_EEPROM_SIZE 0x1000 // 4K #endif diff --git a/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h b/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h index 8a0f15806e77..34f7dba91f9c 100644 --- a/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h +++ b/Marlin/src/pins/stm32f1/pins_GTM32_REV_B.h @@ -51,7 +51,7 @@ //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 // Enable EEPROM Emulation for this board as it doesn't have EEPROM -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) +#if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION #define MARLIN_EEPROM_SIZE 0x1000 // 4K #endif diff --git a/Marlin/src/pins/stm32f1/pins_KEDI_CONTROLLER_V1_2.h b/Marlin/src/pins/stm32f1/pins_KEDI_CONTROLLER_V1_2.h index c2865372c5ae..9b20700adb52 100644 --- a/Marlin/src/pins/stm32f1/pins_KEDI_CONTROLLER_V1_2.h +++ b/Marlin/src/pins/stm32f1/pins_KEDI_CONTROLLER_V1_2.h @@ -31,7 +31,7 @@ // Ignore temp readings during development. //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) +#if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION #define EEPROM_PAGE_SIZE (0x800U) // 2KB #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) @@ -190,7 +190,7 @@ #define BTN_EN1 EXP1_08_PIN #define BTN_EN2 EXP1_06_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_EN EXP1_03_PIN #define LCD_PINS_D4 EXP1_05_PIN #elif IS_TFTGLCD_PANEL @@ -211,7 +211,7 @@ #define BTN_EN1 EXP2_08_PIN #define BTN_EN2 EXP2_06_PIN - #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_EN EXP1_08_PIN #if ENABLED(FYSETC_MINI_12864) @@ -228,7 +228,7 @@ //#define LED_PIN EXP1_04_PIN // green //#define LED_PIN EXP1_03_PIN // blue - //#if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + //#if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) // #ifndef RGB_LED_R_PIN // #define RGB_LED_R_PIN EXP1_05_PIN // #endif diff --git a/Marlin/src/pins/stm32f1/pins_MINGDA_MPX_ARM_MINI.h b/Marlin/src/pins/stm32f1/pins_MINGDA_MPX_ARM_MINI.h index c86552ba12ad..6add3ca01c12 100644 --- a/Marlin/src/pins/stm32f1/pins_MINGDA_MPX_ARM_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_MINGDA_MPX_ARM_MINI.h @@ -51,7 +51,7 @@ #define E2END 0xFFFF // EEPROM end address AT24C256 (32kB) */ -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) +#if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION #define EEPROM_PAGE_SIZE 0x800U // 2K #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h index 6892655e468f..c7a8da2ddcce 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h @@ -52,7 +52,7 @@ //#define FLASH_EEPROM_EMULATION //#define SDCARD_EEPROM_EMULATION -#if EITHER(NO_EEPROM_SELECTED, I2C_EEPROM) +#if ANY(NO_EEPROM_SELECTED, I2C_EEPROM) #define I2C_EEPROM // EEPROM on I2C-0 #define MARLIN_EEPROM_SIZE 0x1000 // 4K #endif diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h index a8583e92d7e6..c3becd3fa1aa 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h @@ -38,7 +38,7 @@ // // EEPROM // -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) +#if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION #define EEPROM_PAGE_SIZE (0x800U) // 2K #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h index 372da38c628a..85c8de26ad70 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h @@ -43,7 +43,7 @@ // // EEPROM // -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) +#if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION #define EEPROM_PAGE_SIZE (0x800U) // 2K #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h index 956e9dc72ef1..983cb6adedeb 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h @@ -54,7 +54,7 @@ //#define FLASH_EEPROM_EMULATION //#define SDCARD_EEPROM_EMULATION -#if EITHER(NO_EEPROM_SELECTED, I2C_EEPROM) +#if ANY(NO_EEPROM_SELECTED, I2C_EEPROM) #define I2C_EEPROM // EEPROM on I2C-0 #define MARLIN_EEPROM_SIZE 0x1000 // 4K #endif diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_common.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_common.h index 69eee63007c5..16ee7757b95b 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_common.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_common.h @@ -42,7 +42,7 @@ #if ENABLED(SRAM_EEPROM_EMULATION) #undef NO_EEPROM_SELECTED #endif -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) +#if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION #define EEPROM_PAGE_SIZE (0x800U) // 2K #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) diff --git a/Marlin/src/pins/stm32f1/pins_PANDA_PI_V29.h b/Marlin/src/pins/stm32f1/pins_PANDA_PI_V29.h index 2ce878ea593c..4c65ce9f6456 100644 --- a/Marlin/src/pins/stm32f1/pins_PANDA_PI_V29.h +++ b/Marlin/src/pins/stm32f1/pins_PANDA_PI_V29.h @@ -31,7 +31,7 @@ // Ignore temp readings during development. //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) +#if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION #define EEPROM_PAGE_SIZE (0x800U) // 2K #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) @@ -178,7 +178,7 @@ #define LCD_PINS_D4 PC1 #endif -#if BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) +#if ALL(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING #error "CAUTION! LCD_FYSETC_TFT81050 requires wiring modifications. See 'pins_PANDA_PI_V29.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" @@ -219,7 +219,7 @@ #define CLCD_MOD_RESET PA9 #define CLCD_SPI_CS PB8 - #if SD_CONNECTION_IS(LCD) && BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) + #if SD_CONNECTION_IS(LCD) && ALL(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) #define SD_DETECT_PIN PA15 #define SD_SS_PIN PA10 #endif diff --git a/Marlin/src/pins/stm32f1/pins_STM32F1R.h b/Marlin/src/pins/stm32f1/pins_STM32F1R.h index 46bd48f93fb3..a2efa632f8c8 100644 --- a/Marlin/src/pins/stm32f1/pins_STM32F1R.h +++ b/Marlin/src/pins/stm32f1/pins_STM32F1R.h @@ -120,7 +120,7 @@ #error "LCD_I2C_PANELOLU2 is not supported." #elif ENABLED(LCD_I2C_VIKI) #error "LCD_I2C_VIKI is not supported." - #elif EITHER(VIKI2, miniVIKI) + #elif ANY(VIKI2, miniVIKI) #error "VIKI2 / miniVIKI is not supported." #elif ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) #error "ELB_FULL_GRAPHIC_CONTROLLER is not supported." diff --git a/Marlin/src/pins/stm32f1/pins_STM3R_MINI.h b/Marlin/src/pins/stm32f1/pins_STM3R_MINI.h index 4cf464aaeeca..b4cf21ee7f04 100644 --- a/Marlin/src/pins/stm32f1/pins_STM3R_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_STM3R_MINI.h @@ -144,7 +144,7 @@ #error "LCD_I2C_PANELOLU2 is not supported." #elif ENABLED(LCD_I2C_VIKI) #error "LCD_I2C_VIKI is not supported." - #elif EITHER(VIKI2, miniVIKI) + #elif ANY(VIKI2, miniVIKI) #error "VIKI2 / miniVIKI is not supported." #elif ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) #error "ELB_FULL_GRAPHIC_CONTROLLER is not supported." diff --git a/Marlin/src/pins/stm32f1/pins_ZM3E2_V1_0.h b/Marlin/src/pins/stm32f1/pins_ZM3E2_V1_0.h index 08491fc21cbc..8ce0f48839de 100644 --- a/Marlin/src/pins/stm32f1/pins_ZM3E2_V1_0.h +++ b/Marlin/src/pins/stm32f1/pins_ZM3E2_V1_0.h @@ -205,7 +205,7 @@ #define BOARD_ST7920_DELAY_2 200 #define BOARD_ST7920_DELAY_3 125 -#elif EITHER(ZONESTAR_12864OLED, ZONESTAR_12864OLED_SSD1306) +#elif ANY(ZONESTAR_12864OLED, ZONESTAR_12864OLED_SSD1306) //================================================================================ // OLED 128x64 diff --git a/Marlin/src/pins/stm32f4/pins_ARMED.h b/Marlin/src/pins/stm32f4/pins_ARMED.h index 9a04c80cdd5e..b4661226380f 100644 --- a/Marlin/src/pins/stm32f4/pins_ARMED.h +++ b/Marlin/src/pins/stm32f4/pins_ARMED.h @@ -158,7 +158,7 @@ #define LCD_RESET_PIN PB12 // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN PB13 #endif diff --git a/Marlin/src/pins/stm32f4/pins_ARTILLERY_RUBY.h b/Marlin/src/pins/stm32f4/pins_ARTILLERY_RUBY.h index 8510e8148259..02ad9bb4ad76 100644 --- a/Marlin/src/pins/stm32f4/pins_ARTILLERY_RUBY.h +++ b/Marlin/src/pins/stm32f4/pins_ARTILLERY_RUBY.h @@ -126,7 +126,7 @@ // LCD / Controller // #if HAS_WIRED_LCD - #if EITHER(MKS_12864OLED, MKS_12864OLED_SSD1306) + #if ANY(MKS_12864OLED, MKS_12864OLED_SSD1306) #define LCD_PINS_DC PB8 // Set as output on init #define LCD_PINS_RS PB9 // Pull low for 1s to init // DOGM SPI LCD Support @@ -143,7 +143,7 @@ #define LCD_RESET_PIN PB5 // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN PB9 #endif diff --git a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h index ce3d2556bffd..bc80720916fb 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h @@ -287,7 +287,7 @@ #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN EXP1_06_PIN #endif diff --git a/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h b/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h index d737dbdc9339..4350fad7f78f 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h @@ -196,7 +196,7 @@ #if HAS_WIRED_LCD - #if EITHER(CR10_STOCKDISPLAY, LCD_FOR_MELZI) + #if ANY(CR10_STOCKDISPLAY, LCD_FOR_MELZI) #define BEEPER_PIN PE8 @@ -258,7 +258,7 @@ #define LCD_PINS_D7 PE8 #define ADC_KEYPAD_PIN PB0 // Repurpose servo pin for ADC - CONNECTING TO 5V WILL DAMAGE THE BOARD! - #elif EITHER(MKS_MINI_12864, ENDER2_STOCKDISPLAY) + #elif ANY(MKS_MINI_12864, ENDER2_STOCKDISPLAY) #define BTN_ENC PE9 #define BTN_EN1 PE7 @@ -330,7 +330,7 @@ #endif // HAS_WIRED_LCD -#if BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) +#if ALL(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING #error "CAUTION! LCD_FYSETC_TFT81050 requires wiring modifications. See 'pins_BTT_E3_RRF.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" diff --git a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h index 0445476490de..2414c07ae363 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h @@ -464,7 +464,7 @@ //#define LCD_BACKLIGHT_PIN -1 #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN EXP1_06_PIN #endif diff --git a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h index 29c1e9f984e4..4cfb8e7b7ea6 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h @@ -27,7 +27,7 @@ #define USES_DIAG_JUMPERS // Onboard I2C EEPROM -#if EITHER(NO_EEPROM_SELECTED, I2C_EEPROM) +#if ANY(NO_EEPROM_SELECTED, I2C_EEPROM) #undef NO_EEPROM_SELECTED #define I2C_EEPROM #define MARLIN_EEPROM_SIZE 0x1000 // 4K (AT24C32) @@ -467,7 +467,7 @@ #define DOGLCD_A0 EXP1_04_PIN //#define LCD_BACKLIGHT_PIN -1 #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN EXP1_06_PIN #endif diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_MINI_E3_V3_0_1.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_MINI_E3_V3_0_1.h index 6f2de83b5142..64ab2dd6c9e8 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_MINI_E3_V3_0_1.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_MINI_E3_V3_0_1.h @@ -43,7 +43,7 @@ #endif // Onboard I2C EEPROM -#if EITHER(NO_EEPROM_SELECTED, I2C_EEPROM) +#if ANY(NO_EEPROM_SELECTED, I2C_EEPROM) #undef NO_EEPROM_SELECTED #define I2C_EEPROM #define SOFT_I2C_EEPROM // Force the use of Software I2C @@ -219,7 +219,7 @@ #define LCD_PINS_D7 EXP1_01_PIN #define ADC_KEYPAD_PIN PA1 // Repurpose servo pin for ADC - CONNECTING TO 5V WILL DAMAGE THE BOARD! - #elif EITHER(MKS_MINI_12864, ENDER2_STOCKDISPLAY) + #elif ANY(MKS_MINI_12864, ENDER2_STOCKDISPLAY) #define BTN_ENC EXP1_02_PIN #define BTN_EN1 EXP1_03_PIN @@ -280,7 +280,7 @@ #endif // HAS_WIRED_LCD -#if BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) +#if ALL(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING #error "CAUTION! LCD_FYSETC_TFT81050 requires wiring modifications. See 'pins_BTT_SKR_MINI_E3_common.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" @@ -332,7 +332,7 @@ #define SDCARD_CONNECTION ONBOARD #endif -#if SD_CONNECTION_IS(LCD) && (BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) || IS_TFTGLCD_PANEL) +#if SD_CONNECTION_IS(LCD) && (ALL(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) || IS_TFTGLCD_PANEL) #define SD_DETECT_PIN EXP1_01_PIN #define SD_SS_PIN EXP1_05_PIN #elif SD_CONNECTION_IS(CUSTOM_CABLE) diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h index 407d89f60b35..f2fbdb9ece74 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h @@ -29,8 +29,8 @@ // https://github.com/bigtreetech/BTT-Expansion-module/tree/master/BTT%20EXP-MOT //#define BTT_MOTOR_EXPANSION -#if BOTH(HAS_WIRED_LCD, BTT_MOTOR_EXPANSION) - #if EITHER(CR10_STOCKDISPLAY, ENDER2_STOCKDISPLAY) +#if ALL(HAS_WIRED_LCD, BTT_MOTOR_EXPANSION) + #if ANY(CR10_STOCKDISPLAY, ENDER2_STOCKDISPLAY) #define EXP_MOT_USE_EXP2_ONLY 1 #else #error "You can't use both an LCD and a Motor Expansion Module on EXP1/EXP2 at the same time." @@ -505,7 +505,7 @@ #define DOGLCD_A0 EXP1_04_PIN //#define LCD_BACKLIGHT_PIN -1 #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN EXP1_06_PIN #endif diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h index 05537ec243a4..055338f45b38 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h @@ -29,8 +29,8 @@ // https://github.com/bigtreetech/BTT-Expansion-module/tree/master/BTT%20EXP-MOT //#define BTT_MOTOR_EXPANSION -#if BOTH(HAS_WIRED_LCD, BTT_MOTOR_EXPANSION) - #if EITHER(CR10_STOCKDISPLAY, ENDER2_STOCKDISPLAY) +#if ALL(HAS_WIRED_LCD, BTT_MOTOR_EXPANSION) + #if ANY(CR10_STOCKDISPLAY, ENDER2_STOCKDISPLAY) #define EXP_MOT_USE_EXP2_ONLY 1 #else #error "You can't use both an LCD and a Motor Expansion Module on EXP1/EXP2 at the same time." @@ -484,7 +484,7 @@ #define DOGLCD_A0 EXP1_04_PIN //#define LCD_BACKLIGHT_PIN -1 #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN EXP1_06_PIN #endif diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V20.h b/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V20.h index 626bdcde7621..16973b344fb3 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V20.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V20.h @@ -34,7 +34,7 @@ // Ignore temp readings during development. //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) +#if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #define FLASH_EEPROM_EMULATION #define FLASH_EEPROM_LEVELING @@ -224,7 +224,7 @@ #define DOGLCD_A0 EXP1_04_PIN //#define LCD_BACKLIGHT_PIN -1 #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN EXP1_06_PIN #endif diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h index 778049079910..3daa8139524a 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_S6.h @@ -291,7 +291,7 @@ #define LCD_BACKLIGHT_PIN EXP1_07_PIN #endif #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN EXP1_06_PIN #endif diff --git a/Marlin/src/pins/stm32f4/pins_I3DBEEZ9.h b/Marlin/src/pins/stm32f4/pins_I3DBEEZ9.h index a7ad18c8dcca..f63f4adeec1e 100644 --- a/Marlin/src/pins/stm32f4/pins_I3DBEEZ9.h +++ b/Marlin/src/pins/stm32f4/pins_I3DBEEZ9.h @@ -33,8 +33,8 @@ //#define MOTOR_EXPANSION -#if BOTH(HAS_WIRED_LCD, MOTOR_EXPANSION) - #if EITHER(CR10_STOCKDISPLAY, ENDER2_STOCKDISPLAY) +#if ALL(HAS_WIRED_LCD, MOTOR_EXPANSION) + #if ANY(CR10_STOCKDISPLAY, ENDER2_STOCKDISPLAY) #define EXP_MOT_USE_EXP2_ONLY 1 #else #error "You can't use both an LCD and a Motor Expansion Module on EXP1/EXP2 at the same time." @@ -560,7 +560,7 @@ #define DOGLCD_A0 EXP1_04_PIN //#define LCD_BACKLIGHT_PIN -1 #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN EXP1_06_PIN #endif diff --git a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8_common.h b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8_common.h index 0940fc5e0c3c..05c938037d51 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8_common.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8_common.h @@ -263,7 +263,7 @@ #endif #endif -#if EITHER(TFT_COLOR_UI, TFT_CLASSIC_UI) +#if ANY(TFT_COLOR_UI, TFT_CLASSIC_UI) #define TFT_CS_PIN EXP1_07_PIN #define TFT_SCK_PIN EXP2_02_PIN #define TFT_MISO_PIN EXP2_01_PIN diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3_common.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3_common.h index 04c40095295d..cdb9f5edecc4 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3_common.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3_common.h @@ -33,7 +33,7 @@ // Use one of these or SDCard-based Emulation will be used //#define SRAM_EEPROM_EMULATION // Use BackSRAM-based EEPROM emulation //#define FLASH_EEPROM_EMULATION // Use Flash-based EEPROM emulation -#if EITHER(NO_EEPROM_SELECTED, I2C_EEPROM) +#if ANY(NO_EEPROM_SELECTED, I2C_EEPROM) #define I2C_EEPROM #define MARLIN_EEPROM_SIZE 0x1000 // 4K #define I2C_SCL_PIN PB6 diff --git a/Marlin/src/pins/stm32f4/pins_MKS_SKIPR_V1_0.h b/Marlin/src/pins/stm32f4/pins_MKS_SKIPR_V1_0.h index 84d5a5f5e0ab..f7b9fb467432 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_SKIPR_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_SKIPR_V1_0.h @@ -311,7 +311,7 @@ #define DOGLCD_A0 EXP1_04_PIN //#define LCD_BACKLIGHT_PIN -1 #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN EXP1_06_PIN #endif diff --git a/Marlin/src/pins/stm32f4/pins_TH3D_EZBOARD_V2.h b/Marlin/src/pins/stm32f4/pins_TH3D_EZBOARD_V2.h index 0ab67c1558a8..61490005987e 100644 --- a/Marlin/src/pins/stm32f4/pins_TH3D_EZBOARD_V2.h +++ b/Marlin/src/pins/stm32f4/pins_TH3D_EZBOARD_V2.h @@ -61,7 +61,7 @@ // // Limit Switches // -#if EITHER(SENSORLESS_HOMING, SENSORLESS_PROBING) +#if ANY(SENSORLESS_HOMING, SENSORLESS_PROBING) // Sensorless homing pins #if ENABLED(X_AXIS_SENSORLESS_HOMING) #define X_STOP_PIN PB4 @@ -269,7 +269,7 @@ #endif -#if EITHER(CR10_STOCKDISPLAY, MKS_MINI_12864) +#if ANY(CR10_STOCKDISPLAY, MKS_MINI_12864) #define BTN_EN1 EXP1_03_PIN #define BTN_EN2 EXP1_05_PIN #define BTN_ENC EXP1_02_PIN diff --git a/Marlin/src/pins/stm32g0/pins_BTT_EBB42_V1_1.h b/Marlin/src/pins/stm32g0/pins_BTT_EBB42_V1_1.h index 07c68dc780d5..6c31fdc57261 100644 --- a/Marlin/src/pins/stm32g0/pins_BTT_EBB42_V1_1.h +++ b/Marlin/src/pins/stm32g0/pins_BTT_EBB42_V1_1.h @@ -38,7 +38,7 @@ // // EEPROM // -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) +#if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #undef NO_EEPROM_SELECTED #ifndef FLASH_EEPROM_EMULATION #define FLASH_EEPROM_EMULATION diff --git a/Marlin/src/pins/stm32g0/pins_BTT_MANTA_E3_EZ_V1_0.h b/Marlin/src/pins/stm32g0/pins_BTT_MANTA_E3_EZ_V1_0.h index 25f1b307ca8d..156698f4247e 100644 --- a/Marlin/src/pins/stm32g0/pins_BTT_MANTA_E3_EZ_V1_0.h +++ b/Marlin/src/pins/stm32g0/pins_BTT_MANTA_E3_EZ_V1_0.h @@ -35,7 +35,7 @@ // // EEPROM // -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) +#if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #undef NO_EEPROM_SELECTED #ifndef FLASH_EEPROM_EMULATION #define FLASH_EEPROM_EMULATION @@ -286,7 +286,7 @@ #define LCD_PINS_D7 EXP1_01_PIN #define ADC_KEYPAD_PIN PA7 // Repurpose default SERVO0_PIN for ADC - CONNECTING TO 5V WILL DAMAGE THE BOARD! - #elif EITHER(MKS_MINI_12864, ENDER2_STOCKDISPLAY) + #elif ANY(MKS_MINI_12864, ENDER2_STOCKDISPLAY) #define BTN_EN1 EXP1_03_PIN #define BTN_EN2 EXP1_05_PIN @@ -317,7 +317,7 @@ #define SD_DETECT_PIN -1 -#if SD_CONNECTION_IS(LCD) && (BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) || IS_TFTGLCD_PANEL) +#if SD_CONNECTION_IS(LCD) && (ALL(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) || IS_TFTGLCD_PANEL) #define SD_SS_PIN EXP1_05_PIN #elif SD_CONNECTION_IS(CUSTOM_CABLE) #error "SD CUSTOM_CABLE is not compatible with Manta E3 EZ." diff --git a/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M4P_V1_0.h b/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M4P_V1_0.h index 3a18b7864c8b..33b957f53a3e 100644 --- a/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M4P_V1_0.h +++ b/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M4P_V1_0.h @@ -37,7 +37,7 @@ // // EEPROM // -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) +#if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #undef NO_EEPROM_SELECTED #ifndef FLASH_EEPROM_EMULATION #define FLASH_EEPROM_EMULATION @@ -259,7 +259,7 @@ // results in LCD soft SPI mode 3, SD soft SPI mode 0 #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN EXP1_06_PIN #endif diff --git a/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M5P_V1_0.h b/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M5P_V1_0.h index 1d77a6cb0751..286a59a00b6e 100644 --- a/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M5P_V1_0.h +++ b/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M5P_V1_0.h @@ -35,7 +35,7 @@ // // EEPROM // -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) +#if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #undef NO_EEPROM_SELECTED #ifndef FLASH_EEPROM_EMULATION #define FLASH_EEPROM_EMULATION @@ -287,7 +287,7 @@ // results in LCD soft SPI mode 3, SD soft SPI mode 0 #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN EXP1_06_PIN #endif diff --git a/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M8P_common.h b/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M8P_common.h index 8cab6b53574f..d4a21ba2f24f 100644 --- a/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M8P_common.h +++ b/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M8P_common.h @@ -33,7 +33,7 @@ // // EEPROM // -#if EITHER(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) +#if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) #undef NO_EEPROM_SELECTED #ifndef FLASH_EEPROM_EMULATION #define FLASH_EEPROM_EMULATION @@ -337,7 +337,7 @@ // results in LCD soft SPI mode 3, SD soft SPI mode 0 #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN EXP1_06_PIN #endif diff --git a/Marlin/src/pins/stm32g0/pins_BTT_SKR_MINI_E3_V3_0.h b/Marlin/src/pins/stm32g0/pins_BTT_SKR_MINI_E3_V3_0.h index 0f7da52572e8..ef6a22b88f1b 100644 --- a/Marlin/src/pins/stm32g0/pins_BTT_SKR_MINI_E3_V3_0.h +++ b/Marlin/src/pins/stm32g0/pins_BTT_SKR_MINI_E3_V3_0.h @@ -37,7 +37,7 @@ #define LED_PIN PD8 // Onboard I2C EEPROM -#if EITHER(NO_EEPROM_SELECTED, I2C_EEPROM) +#if ANY(NO_EEPROM_SELECTED, I2C_EEPROM) #undef NO_EEPROM_SELECTED #define I2C_EEPROM #define SOFT_I2C_EEPROM // Force the use of Software I2C @@ -255,7 +255,7 @@ #define LCD_PINS_D7 EXP1_01_PIN #define ADC_KEYPAD_PIN PA1 // Repurpose servo pin for ADC - CONNECTING TO 5V WILL DAMAGE THE BOARD! - #elif EITHER(MKS_MINI_12864, ENDER2_STOCKDISPLAY) + #elif ANY(MKS_MINI_12864, ENDER2_STOCKDISPLAY) #define BTN_ENC EXP1_02_PIN #define BTN_EN1 EXP1_03_PIN @@ -363,7 +363,7 @@ #endif // HAS_WIRED_LCD -#if BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) +#if ALL(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING #error "CAUTION! LCD_FYSETC_TFT81050 requires wiring modifications. See 'pins_BTT_SKR_MINI_E3_common.h' for details. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this warning.)" @@ -416,7 +416,7 @@ #if SD_CONNECTION_IS(ONBOARD) #define SD_DETECT_PIN PC3 -#elif SD_CONNECTION_IS(LCD) && (BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) || IS_TFTGLCD_PANEL) +#elif SD_CONNECTION_IS(LCD) && (ALL(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) || IS_TFTGLCD_PANEL) #define SD_DETECT_PIN EXP1_01_PIN #define SD_SS_PIN EXP1_05_PIN #elif SD_CONNECTION_IS(CUSTOM_CABLE) diff --git a/Marlin/src/pins/stm32h7/pins_BTT_OCTOPUS_MAX_EZ.h b/Marlin/src/pins/stm32h7/pins_BTT_OCTOPUS_MAX_EZ.h index 69723947fd73..ee92372b5a0f 100644 --- a/Marlin/src/pins/stm32h7/pins_BTT_OCTOPUS_MAX_EZ.h +++ b/Marlin/src/pins/stm32h7/pins_BTT_OCTOPUS_MAX_EZ.h @@ -28,7 +28,7 @@ #define USES_DIAG_JUMPERS // Onboard I2C EEPROM -#if EITHER(NO_EEPROM_SELECTED, I2C_EEPROM) +#if ANY(NO_EEPROM_SELECTED, I2C_EEPROM) #undef NO_EEPROM_SELECTED #define I2C_EEPROM #define SOFT_I2C_EEPROM // Force the use of Software I2C @@ -440,7 +440,7 @@ // results in LCD soft SPI mode 3, SD soft SPI mode 0 //#define LCD_BACKLIGHT_PIN -1 #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN EXP1_06_PIN #endif diff --git a/Marlin/src/pins/stm32h7/pins_BTT_SKR_V3_0_common.h b/Marlin/src/pins/stm32h7/pins_BTT_SKR_V3_0_common.h index 77f47f810664..d6a7358f3e58 100644 --- a/Marlin/src/pins/stm32h7/pins_BTT_SKR_V3_0_common.h +++ b/Marlin/src/pins/stm32h7/pins_BTT_SKR_V3_0_common.h @@ -27,8 +27,8 @@ // https://github.com/bigtreetech/BTT-Expansion-module/tree/master/BTT%20EXP-MOT //#define BTT_MOTOR_EXPANSION -#if BOTH(HAS_WIRED_LCD, BTT_MOTOR_EXPANSION) - #if EITHER(CR10_STOCKDISPLAY, ENDER2_STOCKDISPLAY) +#if ALL(HAS_WIRED_LCD, BTT_MOTOR_EXPANSION) + #if ANY(CR10_STOCKDISPLAY, ENDER2_STOCKDISPLAY) #define EXP_MOT_USE_EXP2_ONLY 1 #else #error "You can't use both an LCD and a Motor Expansion Module on EXP1/EXP2 at the same time." @@ -38,7 +38,7 @@ #define USES_DIAG_JUMPERS // Onboard I2C EEPROM -#if EITHER(NO_EEPROM_SELECTED, I2C_EEPROM) +#if ANY(NO_EEPROM_SELECTED, I2C_EEPROM) #undef NO_EEPROM_SELECTED #define I2C_EEPROM #define SOFT_I2C_EEPROM // Force the use of Software I2C @@ -119,6 +119,7 @@ #define Z_STOP_PIN PC0 // Z-STOP #endif #endif +#define ONBOARD_ENDSTOPPULLUPS // Board has built-in pullups // // Z Probe (when not Z_MIN_PIN) @@ -473,7 +474,7 @@ #define DOGLCD_A0 EXP1_04_PIN //#define LCD_BACKLIGHT_PIN -1 #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN #define RGB_LED_R_PIN EXP1_06_PIN #endif diff --git a/Marlin/src/pins/teensy2/pins_PRINTRBOARD.h b/Marlin/src/pins/teensy2/pins_PRINTRBOARD.h index 124faa769106..c1eee00c2dd3 100644 --- a/Marlin/src/pins/teensy2/pins_PRINTRBOARD.h +++ b/Marlin/src/pins/teensy2/pins_PRINTRBOARD.h @@ -139,7 +139,7 @@ #define LCD_PINS_D6 5 // D5 JP11-6 #define LCD_PINS_D7 4 // D4 JP11-5 - #if EITHER(VIKI2, miniVIKI) + #if ANY(VIKI2, miniVIKI) #define BEEPER_PIN 8 // E0 JP11-10 #define DOGLCD_A0 40 // F2 JP2-2 diff --git a/Marlin/src/pins/teensy2/pins_PRINTRBOARD_REVF.h b/Marlin/src/pins/teensy2/pins_PRINTRBOARD_REVF.h index b208b08826f3..62922399d827 100644 --- a/Marlin/src/pins/teensy2/pins_PRINTRBOARD_REVF.h +++ b/Marlin/src/pins/teensy2/pins_PRINTRBOARD_REVF.h @@ -220,7 +220,7 @@ #define LCD_PINS_D6 5 // D5 JP11-6 #define LCD_PINS_D7 4 // D4 JP11-5 - #if EITHER(VIKI2, miniVIKI) + #if ANY(VIKI2, miniVIKI) #define BEEPER_PIN 8 // E0 JP11-10 #define DOGLCD_A0 40 // F2 JP2-2 diff --git a/Marlin/src/pins/teensy2/pins_SAV_MKI.h b/Marlin/src/pins/teensy2/pins_SAV_MKI.h index c1809eed6b3c..28b0aebe42a6 100644 --- a/Marlin/src/pins/teensy2/pins_SAV_MKI.h +++ b/Marlin/src/pins/teensy2/pins_SAV_MKI.h @@ -163,7 +163,7 @@ #define SR_CLK_PIN EXT_AUX_SCL_D0 #endif -#if EITHER(SAV_3DLCD, SAV_3DGLCD) +#if ANY(SAV_3DLCD, SAV_3DGLCD) #define BTN_EN1 EXT_AUX_A1_IO #define BTN_EN2 EXT_AUX_A0_IO diff --git a/Marlin/src/sd/Sd2Card.cpp b/Marlin/src/sd/Sd2Card.cpp index 81cc03230483..7deebd4776a2 100644 --- a/Marlin/src/sd/Sd2Card.cpp +++ b/Marlin/src/sd/Sd2Card.cpp @@ -74,7 +74,7 @@ #else static uint8_t CRC7(const uint8_t *data, uint8_t n) { uint8_t crc = 0; - LOOP_L_N(i, n) { + for (uint8_t i = 0; i < n; ++i) { uint8_t d = data[i]; d ^= crc << 1; if (d & 0x80) d ^= 9; @@ -111,7 +111,7 @@ uint8_t DiskIODriver_SPI_SD::cardCommand(const uint8_t cmd, const uint32_t arg) d[5] = CRC7(d, 5); // Send message - LOOP_L_N(k, 6) spiSend(d[k]); + for (uint8_t k = 0; k < 6; ++k) spiSend(d[k]); #else // Send command @@ -268,7 +268,7 @@ bool DiskIODriver_SPI_SD::init(const uint8_t sckRateID, const pin_t chipSelectPi spiInit(spiRate_); // Must supply min of 74 clock cycles with CS high. - LOOP_L_N(i, 10) spiSend(0xFF); + for (uint8_t i = 0; i < 10; ++i) spiSend(0xFF); hal.watchdog_refresh(); // In case init takes too long @@ -294,7 +294,7 @@ bool DiskIODriver_SPI_SD::init(const uint8_t sckRateID, const pin_t chipSelectPi } // Get the last byte of r7 response - LOOP_L_N(i, 4) status_ = spiRec(); + for (uint8_t i = 0; i < 4; ++i) status_ = spiRec(); if (status_ == 0xAA) { type(SD_CARD_TYPE_SD2); break; @@ -325,7 +325,7 @@ bool DiskIODriver_SPI_SD::init(const uint8_t sckRateID, const pin_t chipSelectPi } if ((spiRec() & 0xC0) == 0xC0) type(SD_CARD_TYPE_SDHC); // Discard rest of ocr - contains allowed voltage range - LOOP_L_N(i, 3) spiRec(); + for (uint8_t i = 0; i < 3; ++i) spiRec(); } chipDeselect(); diff --git a/Marlin/src/sd/Sd2Card.h b/Marlin/src/sd/Sd2Card.h index 23677b24fa4b..71e31ac614c2 100644 --- a/Marlin/src/sd/Sd2Card.h +++ b/Marlin/src/sd/Sd2Card.h @@ -83,7 +83,7 @@ uint8_t const SD_CARD_TYPE_SD1 = 1, // Standard capacity V1 SD card /** * Define SOFTWARE_SPI to use bit-bang SPI */ -#if EITHER(MEGA_SOFT_SPI, USE_SOFTWARE_SPI) +#if ANY(MEGA_SOFT_SPI, USE_SOFTWARE_SPI) #define SOFTWARE_SPI #endif diff --git a/Marlin/src/sd/SdBaseFile.cpp b/Marlin/src/sd/SdBaseFile.cpp index 98cbe9ba9d1c..46312bca82fb 100644 --- a/Marlin/src/sd/SdBaseFile.cpp +++ b/Marlin/src/sd/SdBaseFile.cpp @@ -209,7 +209,7 @@ bool SdBaseFile::dirEntry(dir_t *dir) { */ void SdBaseFile::dirName(const dir_t &dir, char *name) { uint8_t j = 0; - LOOP_L_N(i, 11) { + for (uint8_t i = 0; i < 11; ++i) { if (dir.name[i] == ' ')continue; if (i == 8) name[j++] = '.'; name[j++] = dir.name[i]; @@ -350,10 +350,10 @@ int8_t SdBaseFile::lsPrintNext(const uint8_t flags, const uint8_t indent) { && DIR_IS_FILE_OR_SUBDIR(&dir)) break; } // indent for dir level - LOOP_L_N(i, indent) SERIAL_CHAR(' '); + for (uint8_t i = 0; i < indent; ++i) SERIAL_CHAR(' '); // print name - LOOP_L_N(i, 11) { + for (uint8_t i = 0; i < 11; ++i) { if (dir.name[i] == ' ')continue; if (i == 8) { SERIAL_CHAR('.'); @@ -504,7 +504,7 @@ bool SdBaseFile::mkdir(SdBaseFile * const parent, const uint8_t dname[11] dir_t d; memcpy(&d, p, sizeof(d)); d.name[0] = '.'; - LOOP_S_L_N(i, 1, 11) d.name[i] = ' '; + for (uint8_t i = 1; i < 11; ++i) d.name[i] = ' '; // cache block for '.' and '..' uint32_t block = vol_->clusterStartBlock(firstCluster_); @@ -771,7 +771,7 @@ bool SdBaseFile::open(SdBaseFile * const dirFile, const uint8_t dname[11] if (!dirFile->seekSet(32 * index)) return false; // Dir entries write loop: [LFN] + SFN(1) - LOOP_L_N(dirWriteIdx, reqEntriesNum) { + for (uint8_t dirWriteIdx = 0; dirWriteIdx < reqEntriesNum; ++dirWriteIdx) { index = (dirFile->curPosition_ / 32) & 0xF; p = dirFile->readDirCache(); // LFN or SFN Entry? @@ -1137,7 +1137,7 @@ bool SdBaseFile::openNext(SdBaseFile *dirFile, const uint8_t oflag) { */ void SdBaseFile::getLFNName(vfat_t *pFatDir, char *lname, const uint8_t sequenceNumber) { const uint8_t startOffset = (sequenceNumber - 1) * FILENAME_LENGTH; - LOOP_L_N(i, FILENAME_LENGTH) { + for (uint8_t i = 0; i < FILENAME_LENGTH; ++i) { const uint16_t utf16_ch = (i >= 11) ? pFatDir->name3[i - 11] : (i >= 5) ? pFatDir->name2[i - 5] : pFatDir->name1[i]; #if ENABLED(UTF_FILENAME_SUPPORT) // We can't reconvert to UTF-8 here as UTF-8 is variable-size encoding, but joining LFN blocks @@ -1158,7 +1158,7 @@ bool SdBaseFile::openNext(SdBaseFile *dirFile, const uint8_t oflag) { void SdBaseFile::setLFNName(vfat_t *pFatDir, char *lname, const uint8_t sequenceNumber) { const uint8_t startOffset = (sequenceNumber - 1) * FILENAME_LENGTH, nameLength = strlen(lname); - LOOP_L_N(i, FILENAME_LENGTH) { + for (uint8_t i = 0; i < FILENAME_LENGTH; ++i) { uint16_t ch = 0; if ((startOffset + i) < nameLength) ch = lname[startOffset + i]; @@ -1479,7 +1479,7 @@ int8_t SdBaseFile::readDir(dir_t * const dir, char * const longFilename) { n = (seq - 1) * (FILENAME_LENGTH); - LOOP_L_N(i, FILENAME_LENGTH) { + for (uint8_t i = 0; i < FILENAME_LENGTH; ++i) { const uint16_t utf16_ch = (i >= 11) ? VFAT->name3[i - 11] : (i >= 5) ? VFAT->name2[i - 5] : VFAT->name1[i]; #if ENABLED(UTF_FILENAME_SUPPORT) // We can't reconvert to UTF-8 here as UTF-8 is variable-size encoding, but joining LFN blocks @@ -1627,7 +1627,7 @@ bool SdBaseFile::remove() { // Check if the entry has a LFN bool lastEntry = false; // loop back to search for any LFN entries related to this file - LOOP_S_LE_N(sequenceNumber, 1, VFAT_ENTRIES_LIMIT) { + for (uint8_t sequenceNumber = 1; sequenceNumber <= VFAT_ENTRIES_LIMIT; ++sequenceNumber) { dirIndex_ = (dirIndex_ - 1) & 0xF; if (dirBlock_ == 0) break; if (dirIndex_ == 0xF) dirBlock_--; diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index a4a10b316986..40c1f09f1182 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -60,7 +60,7 @@ #include "../../src/lcd/menu/menu.h" #endif -#define DEBUG_OUT EITHER(DEBUG_CARDREADER, MARLIN_DEV_MODE) +#define DEBUG_OUT ANY(DEBUG_CARDREADER, MARLIN_DEV_MODE) #include "../core/debug_out.h" #include "../libs/hex_print.h" @@ -176,7 +176,7 @@ CardReader::CardReader() { workDirDepth = 0; ZERO(workDirParents); - #if BOTH(HAS_MEDIA, HAS_SD_DETECT) + #if ALL(HAS_MEDIA, HAS_SD_DETECT) SET_INPUT_PULLUP(SD_DETECT_PIN); #endif @@ -190,7 +190,7 @@ CardReader::CardReader() { // char *createFilename(char * const buffer, const dir_t &p) { char *pos = buffer; - LOOP_L_N(i, 11) { + for (uint8_t i = 0; i < 11; ++i) { if (p.name[i] == ' ') continue; if (i == 8) *pos++ = '.'; *pos++ = p.name[i]; @@ -499,7 +499,7 @@ void CardReader::mount() { if (flag.mounted) cdroot(); else { - #if EITHER(HAS_SD_DETECT, USB_FLASH_DRIVE_SUPPORT) + #if ANY(HAS_SD_DETECT, USB_FLASH_DRIVE_SUPPORT) if (marlin_state != MF_INITIALIZING) LCD_ALERTMESSAGE(MSG_MEDIA_INIT_FAIL); #endif } @@ -650,7 +650,7 @@ void CardReader::getAbsFilenameInCWD(char *dst) { if (cnt < MAXPATHNAMELENGTH) { *dst = '/'; dst++; cnt++; } }; - LOOP_L_N(i, workDirDepth) // Loop down to current work dir + for (uint8_t i = 0; i < workDirDepth; ++i) // Loop down to current work dir appendAtom(workDirParents[i]); if (cnt < MAXPATHNAMELENGTH - (FILENAME_LENGTH) - 1) { // Leave room for filename and nul @@ -1355,7 +1355,7 @@ void CardReader::cdroot() { } else { sort_order[0] = 0; - #if BOTH(SDSORT_USES_RAM, SDSORT_CACHE_NAMES) + #if ALL(SDSORT_USES_RAM, SDSORT_CACHE_NAMES) #if ENABLED(SDSORT_DYNAMIC_RAM) sortnames = new char*[1]; sortshort = new char*[1]; @@ -1377,7 +1377,7 @@ void CardReader::cdroot() { #if ENABLED(SDSORT_DYNAMIC_RAM) delete [] sort_order; #if ENABLED(SDSORT_CACHE_NAMES) - LOOP_L_N(i, sort_count) { + for (uint8_t i = 0; i < sort_count; ++i) { free(sortshort[i]); // strdup free(sortnames[i]); // strdup } diff --git a/Marlin/src/sd/cardreader.h b/Marlin/src/sd/cardreader.h index 832d79efe4ee..80e317ebcf10 100644 --- a/Marlin/src/sd/cardreader.h +++ b/Marlin/src/sd/cardreader.h @@ -284,7 +284,7 @@ class CardReader { static uint8_t sort_order[SDSORT_LIMIT]; #endif - #if BOTH(SDSORT_USES_RAM, SDSORT_CACHE_NAMES) && DISABLED(SDSORT_DYNAMIC_RAM) + #if ALL(SDSORT_USES_RAM, SDSORT_CACHE_NAMES) && DISABLED(SDSORT_DYNAMIC_RAM) #define SORTED_LONGNAME_MAXLEN (SDSORT_CACHE_VFATS) * (FILENAME_LENGTH) #define SORTED_LONGNAME_STORAGE (SORTED_LONGNAME_MAXLEN + 1) #else diff --git a/Marlin/src/sd/usb_flashdrive/Sd2Card_FlashDrive.h b/Marlin/src/sd/usb_flashdrive/Sd2Card_FlashDrive.h index 3390bc51becc..f722c873ae0a 100644 --- a/Marlin/src/sd/usb_flashdrive/Sd2Card_FlashDrive.h +++ b/Marlin/src/sd/usb_flashdrive/Sd2Card_FlashDrive.h @@ -33,7 +33,7 @@ /** * Define SOFTWARE_SPI to use bit-bang SPI */ - #if EITHER(MEGA_SOFT_SPI, USE_SOFTWARE_SPI) + #if ANY(MEGA_SOFT_SPI, USE_SOFTWARE_SPI) #define SOFTWARE_SPI #endif diff --git a/buildroot/bin/build_example b/buildroot/bin/build_example index 34549769bbb1..a8878e8d9f3f 100755 --- a/buildroot/bin/build_example +++ b/buildroot/bin/build_example @@ -32,6 +32,9 @@ $SED -i~ -e "20,30{/#error/d}" Marlin/Configuration.h rm Marlin/Configuration.h~ unset IFS; set +f +# Suppress fatal warnings +echo -e "\n#define NO_CONTROLLER_CUSTOM_WIRING_WARNING" >> Marlin/Configuration.h + echo "Building the firmware now..." $HERE/mftest -s -a -n1 || { echo "Failed"; exit 1; } diff --git a/buildroot/share/PlatformIO/boards/marlin_STM32H723Vx.json b/buildroot/share/PlatformIO/boards/marlin_STM32H723VE.json similarity index 96% rename from buildroot/share/PlatformIO/boards/marlin_STM32H723Vx.json rename to buildroot/share/PlatformIO/boards/marlin_STM32H723VE.json index a2154d448a9e..3941b3d00a76 100644 --- a/buildroot/share/PlatformIO/boards/marlin_STM32H723Vx.json +++ b/buildroot/share/PlatformIO/boards/marlin_STM32H723VE.json @@ -6,7 +6,7 @@ "f_cpu": "550000000L", "mcu": "stm32h723vet6", "product_line": "STM32H723xx", - "variant": "MARLIN_H723Vx" + "variant": "MARLIN_H723VE" }, "connectivity": [ "can", @@ -56,6 +56,6 @@ "use_1200bps_touch": false, "wait_for_upload_port": false }, - "url": "https://www.st.com/en/microcontrollers-microprocessors/stm32h723ze.html", + "url": "https://www.st.com/en/microcontrollers-microprocessors/stm32h723ve.html", "vendor": "ST" } diff --git a/buildroot/share/PlatformIO/boards/marlin_STM32H723VG.json b/buildroot/share/PlatformIO/boards/marlin_STM32H723VG.json new file mode 100644 index 000000000000..bf1fc961af0f --- /dev/null +++ b/buildroot/share/PlatformIO/boards/marlin_STM32H723VG.json @@ -0,0 +1,61 @@ +{ + "build": { + "core": "stm32", + "cpu": "cortex-m7", + "extra_flags": "-DSTM32H7xx -DSTM32H723xx", + "f_cpu": "550000000L", + "mcu": "stm32h723vzt6", + "product_line": "STM32H723xx", + "variant": "MARLIN_H723VG" + }, + "connectivity": [ + "can", + "ethernet" + ], + "debug": { + "jlink_device": "STM32H723VG", + "openocd_target": "stm32h7x", + "svd_path": "STM32H7x3.svd", + "tools": { + "stlink": { + "server": { + "arguments": [ + "-f", + "scripts/interface/stlink.cfg", + "-c", + "transport select hla_swd", + "-f", + "scripts/target/stm32h7x.cfg", + "-c", + "reset_config none" + ], + "executable": "bin/openocd", + "package": "tool-openocd" + } + } + } + }, + "frameworks": [ + "arduino", + "stm32cube" + ], + "name": "STM32H723VG (564k RAM. 1024k Flash)", + "upload": { + "disable_flushing": false, + "maximum_ram_size": 577536, + "maximum_size": 1048576, + "protocol": "stlink", + "protocols": [ + "stlink", + "dfu", + "jlink", + "cmsis-dap" + ], + "offset_address": "0x8020000", + "require_upload_port": true, + "use_1200bps_touch": false, + "wait_for_upload_port": false + }, + "url": "https://www.st.com/en/microcontrollers-microprocessors/stm32h723vg.html", + "vendor": "ST" +} diff --git a/buildroot/share/PlatformIO/scripts/common-dependencies.h b/buildroot/share/PlatformIO/scripts/common-dependencies.h index c75d9a3d675a..b37a377df994 100644 --- a/buildroot/share/PlatformIO/scripts/common-dependencies.h +++ b/buildroot/share/PlatformIO/scripts/common-dependencies.h @@ -33,7 +33,7 @@ // #if ENABLED(SR_LCD_3W_NL) // Feature checks for SR_LCD_3W_NL -#elif EITHER(LCD_I2C_TYPE_MCP23017, LCD_I2C_TYPE_MCP23008) +#elif ANY(LCD_I2C_TYPE_MCP23017, LCD_I2C_TYPE_MCP23008) #define USES_LIQUIDTWI2 #elif ENABLED(LCD_I2C_TYPE_PCA8574) #define USES_LIQUIDCRYSTAL_I2C @@ -59,10 +59,10 @@ #if ENABLED(CANCEL_OBJECTS) #define HAS_MENU_CANCELOBJECT #endif - #if EITHER(DELTA_CALIBRATION_MENU, DELTA_AUTO_CALIBRATION) + #if ANY(DELTA_CALIBRATION_MENU, DELTA_AUTO_CALIBRATION) #define HAS_MENU_DELTA_CALIBRATE #endif - #if EITHER(LED_CONTROL_MENU, CASE_LIGHT_MENU) + #if ANY(LED_CONTROL_MENU, CASE_LIGHT_MENU) #define HAS_MENU_LED #endif #if ENABLED(ADVANCED_PAUSE_FEATURE) diff --git a/buildroot/share/PlatformIO/scripts/preflight-checks.py b/buildroot/share/PlatformIO/scripts/preflight-checks.py index 3f7c97af9d78..54d7f3db55e1 100644 --- a/buildroot/share/PlatformIO/scripts/preflight-checks.py +++ b/buildroot/share/PlatformIO/scripts/preflight-checks.py @@ -72,7 +72,7 @@ def sanity_check_target(): result = check_envs("env:"+build_env, board_envs, config) if not result: - err = "Error: Build environment '%s' is incompatible with %s. Use one of these: %s" % \ + err = "Error: Build environment '%s' is incompatible with %s. Use one of these environments: %s" % \ ( build_env, motherboard, ", ".join([ e[4:] for e in board_envs if e.startswith("env:") ]) ) raise SystemExit(err) diff --git a/buildroot/share/PlatformIO/variants/MARLIN_H723Vx/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_H723VE/PeripheralPins.c similarity index 100% rename from buildroot/share/PlatformIO/variants/MARLIN_H723Vx/PeripheralPins.c rename to buildroot/share/PlatformIO/variants/MARLIN_H723VE/PeripheralPins.c diff --git a/buildroot/share/PlatformIO/variants/MARLIN_H723Vx/PinNamesVar.h b/buildroot/share/PlatformIO/variants/MARLIN_H723VE/PinNamesVar.h similarity index 100% rename from buildroot/share/PlatformIO/variants/MARLIN_H723Vx/PinNamesVar.h rename to buildroot/share/PlatformIO/variants/MARLIN_H723VE/PinNamesVar.h diff --git a/buildroot/share/PlatformIO/variants/MARLIN_H723Vx/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_H723VE/ldscript.ld similarity index 100% rename from buildroot/share/PlatformIO/variants/MARLIN_H723Vx/ldscript.ld rename to buildroot/share/PlatformIO/variants/MARLIN_H723VE/ldscript.ld diff --git a/buildroot/share/PlatformIO/variants/MARLIN_H723Vx/variant_MARLIN_STM32H723VX.cpp b/buildroot/share/PlatformIO/variants/MARLIN_H723VE/variant_MARLIN_STM32H723VE.cpp similarity index 100% rename from buildroot/share/PlatformIO/variants/MARLIN_H723Vx/variant_MARLIN_STM32H723VX.cpp rename to buildroot/share/PlatformIO/variants/MARLIN_H723VE/variant_MARLIN_STM32H723VE.cpp diff --git a/buildroot/share/PlatformIO/variants/MARLIN_H723Vx/variant_MARLIN_STM32H723VX.h b/buildroot/share/PlatformIO/variants/MARLIN_H723VE/variant_MARLIN_STM32H723VE.h similarity index 100% rename from buildroot/share/PlatformIO/variants/MARLIN_H723Vx/variant_MARLIN_STM32H723VX.h rename to buildroot/share/PlatformIO/variants/MARLIN_H723VE/variant_MARLIN_STM32H723VE.h diff --git a/buildroot/share/PlatformIO/variants/MARLIN_H723VG/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_H723VG/PeripheralPins.c new file mode 100644 index 000000000000..e484edd1ad44 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_H723VG/PeripheralPins.c @@ -0,0 +1,590 @@ +/* + ******************************************************************************* + * Copyright (c) 2020, STMicroelectronics + * All rights reserved. + * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ******************************************************************************* + */ +/* + * Automatically generated from STM32H723VEHx.xml, STM32H723VETx.xml + * STM32H723VGHx.xml, STM32H723VGTx.xml + * STM32H730VBHx.xml, STM32H730VBTx.xml + * STM32H733VGHx.xml, STM32H733VGTx.xml + * CubeMX DB release 6.0.60 + */ +#if !defined(CUSTOM_PERIPHERAL_PINS) +#include "Arduino.h" +#include "PeripheralPins.h" + +/* ===== + * Notes: + * - The pins mentioned Px_y_ALTz are alternative possibilities which use other + * HW peripheral instances. You can use them the same way as any other "normal" + * pin (i.e. analogWrite(PA7_ALT1, 128);). + * + * - Commented lines are alternative possibilities which are not used per default. + * If you change them, you will have to know what you do + * ===== + */ + +//*** ADC *** + +#ifdef HAL_ADC_MODULE_ENABLED +WEAK const PinMap PinMap_ADC[] = { + {PA_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 16, 0)}, // ADC1_INP16 + {PA_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 17, 0)}, // ADC1_INP17 + {PA_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC1_INP14 + {PA_2_ALT1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC2_INP14 + {PA_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC1_INP15 + {PA_3_ALT1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC2_INP15 + {PA_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 18, 0)}, // ADC1_INP18 + {PA_4_ALT1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 18, 0)}, // ADC2_INP18 + {PA_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 19, 0)}, // ADC1_INP19 + {PA_5_ALT1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 19, 0)}, // ADC2_INP19 + {PA_6, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC1_INP3 + {PA_6_ALT1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC2_INP3 + {PA_7, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC1_INP7 + {PA_7_ALT1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC2_INP7 + {PB_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC1_INP9 + {PB_0_ALT1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC2_INP9 + {PB_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC1_INP5 + {PB_1_ALT1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC2_INP5 + {PC_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC1_INP10 + {PC_0_ALT1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC2_INP10 + {PC_0_ALT2, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC3_INP10 + {PC_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC1_INP11 + {PC_1_ALT1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC2_INP11 + {PC_1_ALT2, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC3_INP11 + {PC_2_C, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC3_INP0 + {PC_3_C, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC3_INP1 + {PC_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC1_INP4 + {PC_4_ALT1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC2_INP4 + {PC_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC1_INP8 + {PC_5_ALT1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC2_INP8 + {NC, NP, 0} +}; +#endif + +//*** DAC *** + +#ifdef HAL_DAC_MODULE_ENABLED +WEAK const PinMap PinMap_DAC[] = { + {PA_4, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // DAC1_OUT1 + {PA_5, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // DAC1_OUT2 + {NC, NP, 0} +}; +#endif + +//*** I2C *** + +#ifdef HAL_I2C_MODULE_ENABLED +WEAK const PinMap PinMap_I2C_SDA[] = { + {PB_7, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)}, + {PB_7_ALT1, I2C4, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C4)}, + {PB_9, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)}, + {PB_9_ALT1, I2C4, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C4)}, + {PB_11, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + {PC_9, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, + {PC_9_ALT1, I2C5, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C5)}, + {PC_10, I2C5, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C5)}, + {PD_13, I2C4, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C4)}, + {NC, NP, 0} +}; +#endif + +#ifdef HAL_I2C_MODULE_ENABLED +WEAK const PinMap PinMap_I2C_SCL[] = { + {PA_8, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, + {PA_8_ALT1, I2C5, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C5)}, + {PB_6, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)}, + {PB_6_ALT1, I2C4, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C4)}, + {PB_8, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)}, + {PB_8_ALT1, I2C4, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C4)}, + {PB_10, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)}, + {PC_11, I2C5, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C5)}, + {PD_12, I2C4, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C4)}, + {NC, NP, 0} +}; +#endif + +//*** TIM *** + +#ifdef HAL_TIM_MODULE_ENABLED +WEAK const PinMap PinMap_TIM[] = { + {PA_0, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 + {PA_0_ALT1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 1, 0)}, // TIM5_CH1 + {PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 + {PA_1_ALT1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2 + {PA_1_ALT2, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_TIM15, 1, 1)}, // TIM15_CH1N + {PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 + {PA_2_ALT1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 3, 0)}, // TIM5_CH3 + {PA_2_ALT2, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_TIM15, 1, 0)}, // TIM15_CH1 + {PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 + {PA_3_ALT1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 4, 0)}, // TIM5_CH4 + {PA_3_ALT2, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_TIM15, 2, 0)}, // TIM15_CH2 + {PA_5, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 + {PA_5_ALT1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N + {PA_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 + {PA_6_ALT1, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1 + {PA_7, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N + {PA_7_ALT1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 + {PA_7_ALT2, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N + {PA_7_ALT3, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1 + {PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 + {PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 + {PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 + {PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 + {PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 + {PB_0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N + {PB_0_ALT1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 + {PB_0_ALT2, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N + {PB_1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N + {PB_1_ALT1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 + {PB_1_ALT2, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N + {PB_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 + {PB_4, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 + {PB_5, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 + {PB_6, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1 + {PB_6_ALT1, TIM16, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM16, 1, 1)}, // TIM16_CH1N + {PB_7, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2 + {PB_7_ALT1, TIM17, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM17, 1, 1)}, // TIM17_CH1N + {PB_8, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3 + {PB_8_ALT1, TIM16, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM16, 1, 0)}, // TIM16_CH1 + {PB_9, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 + {PB_9_ALT1, TIM17, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM17, 1, 0)}, // TIM17_CH1 + {PB_10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 + {PB_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 + {PB_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N + {PB_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N + {PB_14_ALT1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N + {PB_14_ALT2, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM12, 1, 0)}, // TIM12_CH1 + {PB_15, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N + {PB_15_ALT1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N + {PB_15_ALT2, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM12, 2, 0)}, // TIM12_CH2 + {PC_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 + {PC_6_ALT1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 0)}, // TIM8_CH1 + {PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 + {PC_7_ALT1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2 + {PC_8, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 + {PC_8_ALT1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 0)}, // TIM8_CH3 + {PC_9, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 + {PC_9_ALT1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 4, 0)}, // TIM8_CH4 + {PC_12, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM15, 1, 0)}, // TIM15_CH1 + {PD_12, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1 + {PD_13, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2 + {PD_14, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3 + {PD_15, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4 + {PE_4, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_TIM15, 1, 1)}, // TIM15_CH1N + {PE_5, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_TIM15, 1, 0)}, // TIM15_CH1 + {PE_6, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_TIM15, 2, 0)}, // TIM15_CH2 + {PE_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N + {PE_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 + {PE_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N + {PE_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 + {PE_12, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N + {PE_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 + {PE_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 + {NC, NP, 0} +}; +#endif + +//*** UART *** + +#ifdef HAL_UART_MODULE_ENABLED +WEAK const PinMap PinMap_UART_TX[] = { + {PA_0, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + {PA_2, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PA_9, LPUART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_LPUART)}, + {PA_9_ALT1, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {PA_12, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_UART4)}, + {PA_15, UART7, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_UART7)}, + {PB_4, UART7, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_UART7)}, + {PB_6, LPUART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_LPUART)}, + {PB_6_ALT1, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_UART5)}, + {PB_6_ALT2, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {PB_9, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + {PB_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PB_13, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_UART5)}, + {PB_14, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_USART1)}, + {PC_6, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART6)}, + {PC_10, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + {PC_10_ALT1, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PC_12, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, + {PD_1, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + {PD_5, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PD_8, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PD_15, UART9, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_UART9)}, + {PE_1, UART8, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART8)}, + {PE_3, USART10, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_USART10)}, + {PE_8, UART7, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_UART7)}, + {NC, NP, 0} +}; +#endif + +#ifdef HAL_UART_MODULE_ENABLED +WEAK const PinMap PinMap_UART_RX[] = { + {PA_1, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + {PA_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PA_8, UART7, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_UART7)}, + {PA_10, LPUART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_LPUART)}, + {PA_10_ALT1, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {PA_11, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_UART4)}, + {PB_3, UART7, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_UART7)}, + {PB_5, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_UART5)}, + {PB_7, LPUART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_LPUART)}, + {PB_7_ALT1, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {PB_8, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + {PB_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PB_12, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_UART5)}, + {PB_15, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_USART1)}, + {PC_7, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART6)}, + {PC_11, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + {PC_11_ALT1, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PD_0, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + {PD_2, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, + {PD_6, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PD_9, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PD_14, UART9, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_UART9)}, + {PE_0, UART8, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART8)}, + {PE_2, USART10, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_USART10)}, + {PE_7, UART7, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_UART7)}, + {NC, NP, 0} +}; +#endif + +#ifdef HAL_UART_MODULE_ENABLED +WEAK const PinMap PinMap_UART_RTS[] = { + {PA_1, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PA_12, LPUART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_LPUART)}, + {PA_12_ALT1, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {PA_15, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + {PB_14, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + {PB_14_ALT1, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PC_8, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, + {PD_4, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PD_12, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PD_13, UART9, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_UART9)}, + {PD_15, UART8, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART8)}, + {PE_9, UART7, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_UART7)}, + {NC, NP, 0} +}; +#endif + +#ifdef HAL_UART_MODULE_ENABLED +WEAK const PinMap PinMap_UART_CTS[] = { + {PA_0, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PA_11, LPUART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_LPUART)}, + {PA_11_ALT1, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, + {PB_0, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + {PB_13, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PB_15, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, + {PC_9, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)}, + {PD_0, UART9, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_UART9)}, + {PD_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, + {PD_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, + {PD_14, UART8, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART8)}, + {PE_10, UART7, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_UART7)}, + {NC, NP, 0} +}; +#endif + +//*** SPI *** + +#ifdef HAL_SPI_MODULE_ENABLED +WEAK const PinMap PinMap_SPI_MOSI[] = { + {PA_7, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + {PA_7_ALT1, SPI6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_SPI6)}, + {PB_2, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_SPI3)}, + {PB_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + {PB_5_ALT1, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_SPI3)}, + {PB_5_ALT2, SPI6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_SPI6)}, + {PB_15, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PC_1, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PC_3_C, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PC_12, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + {PD_6, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI3)}, + {PD_7, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + {PE_6, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)}, + {PE_14, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)}, + {NC, NP, 0} +}; +#endif + +#ifdef HAL_SPI_MODULE_ENABLED +WEAK const PinMap PinMap_SPI_MISO[] = { + {PA_6, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + {PA_6_ALT1, SPI6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_SPI6)}, + {PB_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + {PB_4_ALT1, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + {PB_4_ALT2, SPI6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_SPI6)}, + {PB_14, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PC_2_C, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PC_11, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + {PE_5, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)}, + {PE_13, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)}, + {NC, NP, 0} +}; +#endif + +#ifdef HAL_SPI_MODULE_ENABLED +WEAK const PinMap PinMap_SPI_SCLK[] = { + {PA_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + {PA_5_ALT1, SPI6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_SPI6)}, + {PA_9, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PA_12, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PB_3, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + {PB_3_ALT1, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + {PB_3_ALT2, SPI6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_SPI6)}, + {PB_10, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PB_13, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PC_10, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + {PC_12, SPI6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI6)}, + {PD_3, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PE_2, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)}, + {PE_12, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)}, + {NC, NP, 0} +}; +#endif + +#ifdef HAL_SPI_MODULE_ENABLED +WEAK const PinMap PinMap_SPI_SSEL[] = { + {PA_0, SPI6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI6)}, + {PA_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + {PA_4_ALT1, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + {PA_4_ALT2, SPI6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_SPI6)}, + {PA_11, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PA_15, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, + {PA_15_ALT1, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, + {PA_15_ALT2, SPI6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_SPI6)}, + {PB_4, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_SPI2)}, + {PB_9, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PB_12, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, + {PE_4, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)}, + {PE_11, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)}, + {NC, NP, 0} +}; +#endif + +//*** FDCAN *** + +#ifdef HAL_FDCAN_MODULE_ENABLED +WEAK const PinMap PinMap_CAN_RD[] = { + {PA_11, FDCAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_FDCAN1)}, + {PB_5, FDCAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_FDCAN2)}, + {PB_8, FDCAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_FDCAN1)}, + {PB_12, FDCAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_FDCAN2)}, + {PD_0, FDCAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_FDCAN1)}, + {PD_12, FDCAN3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_FDCAN3)}, + {NC, NP, 0} +}; +#endif + +#ifdef HAL_FDCAN_MODULE_ENABLED +WEAK const PinMap PinMap_CAN_TD[] = { + {PA_12, FDCAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_FDCAN1)}, + {PB_6, FDCAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_FDCAN2)}, + {PB_9, FDCAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_FDCAN1)}, + {PB_13, FDCAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_FDCAN2)}, + {PD_1, FDCAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_FDCAN1)}, + {PD_13, FDCAN3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_FDCAN3)}, + {NC, NP, 0} +}; +#endif + +//*** ETHERNET *** + +#if defined(HAL_ETH_MODULE_ENABLED) || defined(HAL_ETH_LEGACY_MODULE_ENABLED) +WEAK const PinMap PinMap_Ethernet[] = { + {PA_0, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_CRS + {PA_1, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_REF_CLK + {PA_1_ALT1, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RX_CLK + {PA_2, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_MDIO + {PA_3, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_COL + {PA_7, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_CRS_DV + {PA_7_ALT1, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RX_DV + {PA_9, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TX_ER + {PB_0, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RXD2 + {PB_1, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RXD3 + {PB_2, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TX_ER + {PB_5, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_PPS_OUT + {PB_8, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD3 + {PB_10, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RX_ER + {PB_11, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TX_EN + {PB_12, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD0 + {PB_13, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD1 + {PC_1, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_MDC + {PC_2_C, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD2 + {PC_3_C, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TX_CLK + {PC_4, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RXD0 + {PC_5, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RXD1 + {PE_2, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD3 + {NC, NP, 0} +}; +#endif + +//*** OCTOSPI *** + +#ifdef HAL_OSPI_MODULE_ENABLED +WEAK const PinMap PinMap_OCTOSPI_DATA0[] = { + {PA_2, OCTOSPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_OCTOSPIM_P1)}, // OCTOSPIM_P1_IO0 + {PB_1, OCTOSPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_OCTOSPIM_P1)}, // OCTOSPIM_P1_IO0 + {PB_12, OCTOSPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OCTOSPIM_P1)}, // OCTOSPIM_P1_IO0 + {PC_3_C, OCTOSPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_OCTOSPIM_P1)}, // OCTOSPIM_P1_IO0 + {PC_9, OCTOSPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_OCTOSPIM_P1)}, // OCTOSPIM_P1_IO0 + {PD_11, OCTOSPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_OCTOSPIM_P1)}, // OCTOSPIM_P1_IO0 + {NC, NP, 0} +}; +#endif + +#ifdef HAL_OSPI_MODULE_ENABLED +WEAK const PinMap PinMap_OCTOSPI_DATA1[] = { + {PB_0, OCTOSPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_OCTOSPIM_P1)}, // OCTOSPIM_P1_IO1 + {PC_10, OCTOSPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_OCTOSPIM_P1)}, // OCTOSPIM_P1_IO1 + {PD_12, OCTOSPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_OCTOSPIM_P1)}, // OCTOSPIM_P1_IO1 + {NC, NP, 0} +}; +#endif + +#ifdef HAL_OSPI_MODULE_ENABLED +WEAK const PinMap PinMap_OCTOSPI_DATA2[] = { + {PA_3, OCTOSPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_OCTOSPIM_P1)}, // OCTOSPIM_P1_IO2 + {PA_7, OCTOSPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OCTOSPIM_P1)}, // OCTOSPIM_P1_IO2 + {PB_13, OCTOSPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_OCTOSPIM_P1)}, // OCTOSPIM_P1_IO2 + {PC_2_C, OCTOSPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_OCTOSPIM_P1)}, // OCTOSPIM_P1_IO2 + {PE_2, OCTOSPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_OCTOSPIM_P1)}, // OCTOSPIM_P1_IO2 + {NC, NP, 0} +}; +#endif + +#ifdef HAL_OSPI_MODULE_ENABLED +WEAK const PinMap PinMap_OCTOSPI_DATA3[] = { + {PA_1, OCTOSPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_OCTOSPIM_P1)}, // OCTOSPIM_P1_IO3 + {PA_6, OCTOSPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_OCTOSPIM_P1)}, // OCTOSPIM_P1_IO3 + {PD_13, OCTOSPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_OCTOSPIM_P1)}, // OCTOSPIM_P1_IO3 + {NC, NP, 0} +}; +#endif + +#ifdef HAL_OSPI_MODULE_ENABLED +WEAK const PinMap PinMap_OCTOSPI_DATA4[] = { + {PC_1, OCTOSPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OCTOSPIM_P1)}, // OCTOSPIM_P1_IO4 + {PD_4, OCTOSPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OCTOSPIM_P1)}, // OCTOSPIM_P1_IO4 + {PE_7, OCTOSPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OCTOSPIM_P1)}, // OCTOSPIM_P1_IO4 + {NC, NP, 0} +}; +#endif + +#ifdef HAL_OSPI_MODULE_ENABLED +WEAK const PinMap PinMap_OCTOSPI_DATA5[] = { + {PC_2_C, OCTOSPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_OCTOSPIM_P1)}, // OCTOSPIM_P1_IO5 + {PD_5, OCTOSPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OCTOSPIM_P1)}, // OCTOSPIM_P1_IO5 + {PE_8, OCTOSPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OCTOSPIM_P1)}, // OCTOSPIM_P1_IO5 + {NC, NP, 0} +}; +#endif + +#ifdef HAL_OSPI_MODULE_ENABLED +WEAK const PinMap PinMap_OCTOSPI_DATA6[] = { + {PC_3_C, OCTOSPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_OCTOSPIM_P1)}, // OCTOSPIM_P1_IO6 + {PD_6, OCTOSPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OCTOSPIM_P1)}, // OCTOSPIM_P1_IO6 + {PE_9, OCTOSPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OCTOSPIM_P1)}, // OCTOSPIM_P1_IO6 + {NC, NP, 0} +}; +#endif + +#ifdef HAL_OSPI_MODULE_ENABLED +WEAK const PinMap PinMap_OCTOSPI_DATA7[] = { + {PD_7, OCTOSPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OCTOSPIM_P1)}, // OCTOSPIM_P1_IO7 + {PE_10, OCTOSPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OCTOSPIM_P1)}, // OCTOSPIM_P1_IO7 + {NC, NP, 0} +}; +#endif + +#ifdef HAL_OSPI_MODULE_ENABLED +WEAK const PinMap PinMap_OCTOSPI_SCLK[] = { + {PA_3, OCTOSPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OCTOSPIM_P1)}, // OCTOSPIM_P1_CLK + {PB_2, OCTOSPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_OCTOSPIM_P1)}, // OCTOSPIM_P1_CLK + {NC, NP, 0} +}; +#endif + +#ifdef HAL_OSPI_MODULE_ENABLED +WEAK const PinMap PinMap_OCTOSPI_SSEL[] = { + {PB_6, OCTOSPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OCTOSPIM_P1)}, // OCTOSPIM_P1_NCS + {PB_10, OCTOSPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_OCTOSPIM_P1)}, // OCTOSPIM_P1_NCS + {PC_11, OCTOSPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_OCTOSPIM_P1)}, // OCTOSPIM_P1_NCS + {PE_11, OCTOSPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_OCTOSPIM_P1)}, // OCTOSPIM_P1_NCS + {NC, NP, 0} +}; +#endif + +//*** USB *** + +#if defined(HAL_PCD_MODULE_ENABLED) || defined(HAL_HCD_MODULE_ENABLED) +WEAK const PinMap PinMap_USB_OTG_HS[] = { +#ifdef USE_USB_HS_IN_FS + {PA_8, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG1_HS)}, // USB_OTG_HS_SOF + {PA_9, USB_OTG_HS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_HS_VBUS + {PA_10, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF10_OTG1_HS)}, // USB_OTG_HS_ID + {PA_11, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF_NONE)}, // USB_OTG_HS_DM + {PA_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF_NONE)}, // USB_OTG_HS_DP +#else + {PA_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG1_HS)}, // USB_OTG_HS_ULPI_D0 + {PA_5, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG1_HS)}, // USB_OTG_HS_ULPI_CK + {PB_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG1_HS)}, // USB_OTG_HS_ULPI_D1 + {PB_1, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG1_HS)}, // USB_OTG_HS_ULPI_D2 + {PB_5, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG1_HS)}, // USB_OTG_HS_ULPI_D7 + {PB_10, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG1_HS)}, // USB_OTG_HS_ULPI_D3 + {PB_11, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG1_HS)}, // USB_OTG_HS_ULPI_D4 + {PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG1_HS)}, // USB_OTG_HS_ULPI_D5 + {PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG1_HS)}, // USB_OTG_HS_ULPI_D6 + {PC_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG1_HS)}, // USB_OTG_HS_ULPI_STP + {PC_2_C, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG1_HS)}, // USB_OTG_HS_ULPI_DIR + {PC_3_C, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG1_HS)}, // USB_OTG_HS_ULPI_NXT +#endif /* USE_USB_HS_IN_FS */ + {NC, NP, 0} +}; +#endif + +//*** SD *** + +#ifdef HAL_SD_MODULE_ENABLED +WEAK const PinMap PinMap_SD[] = { + {PA_0, SDMMC2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_SDMMC2)}, // SDMMC2_CMD + {PB_3, SDMMC2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_SDMMC2)}, // SDMMC2_D2 + {PB_4, SDMMC2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_SDMMC2)}, // SDMMC2_D3 + {PB_8, SDMMC1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF7_SDMMC1)}, // SDMMC1_CKIN + {PB_8_ALT1, SDMMC1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDMMC1)}, // SDMMC1_D4 + {PB_8_ALT2, SDMMC2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_SDMMC2)}, // SDMMC2_D4 + {PB_9, SDMMC1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF7_SDMMC1)}, // SDMMC1_CDIR + {PB_9_ALT1, SDMMC1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDMMC1)}, // SDMMC1_D5 + {PB_9_ALT2, SDMMC2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_SDMMC2)}, // SDMMC2_D5 + {PB_13, SDMMC1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDMMC1)}, // SDMMC1_D0 + {PB_14, SDMMC2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_SDMMC2)}, // SDMMC2_D0 + {PB_15, SDMMC2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_SDMMC2)}, // SDMMC2_D1 + {PC_1, SDMMC2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_SDMMC2)}, // SDMMC2_CK + {PC_4, SDMMC2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF10_SDMMC2)}, // SDMMC2_CKIN + {PC_6, SDMMC1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF8_SDMMC1)}, // SDMMC1_D0DIR + {PC_6_ALT1, SDMMC1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDMMC1)}, // SDMMC1_D6 + {PC_6_ALT2, SDMMC2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_SDMMC2)}, // SDMMC2_D6 + {PC_7, SDMMC1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF8_SDMMC1)}, // SDMMC1_D123DIR + {PC_7_ALT1, SDMMC1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDMMC1)}, // SDMMC1_D7 + {PC_7_ALT2, SDMMC2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_SDMMC2)}, // SDMMC2_D7 + {PC_8, SDMMC1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDMMC1)}, // SDMMC1_D0 + {PC_9, SDMMC1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDMMC1)}, // SDMMC1_D1 + {PC_10, SDMMC1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDMMC1)}, // SDMMC1_D2 + {PC_11, SDMMC1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDMMC1)}, // SDMMC1_D3 + {PC_12, SDMMC1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF12_SDMMC1)}, // SDMMC1_CK + {PD_2, SDMMC1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF12_SDMMC1)}, // SDMMC1_CMD + {PD_6, SDMMC2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF11_SDMMC2)}, // SDMMC2_CK + {PD_7, SDMMC2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF11_SDMMC2)}, // SDMMC2_CMD + {NC, NP, 0} +}; +#endif + +#endif /* !CUSTOM_PERIPHERAL_PINS */ diff --git a/buildroot/share/PlatformIO/variants/MARLIN_H723VG/PinNamesVar.h b/buildroot/share/PlatformIO/variants/MARLIN_H723VG/PinNamesVar.h new file mode 100644 index 000000000000..3bd0ed8fcd64 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_H723VG/PinNamesVar.h @@ -0,0 +1,108 @@ +/* Dual pad pin name */ +PC_2_C = PC_2 | PDUAL, +PC_3_C = PC_3 | PDUAL, + +/* Alternate pin name */ +PA_0_ALT1 = PA_0 | ALT1, +PA_1_ALT1 = PA_1 | ALT1, +PA_1_ALT2 = PA_1 | ALT2, +PA_2_ALT1 = PA_2 | ALT1, +PA_2_ALT2 = PA_2 | ALT2, +PA_3_ALT1 = PA_3 | ALT1, +PA_3_ALT2 = PA_3 | ALT2, +PA_4_ALT1 = PA_4 | ALT1, +PA_4_ALT2 = PA_4 | ALT2, +PA_5_ALT1 = PA_5 | ALT1, +PA_6_ALT1 = PA_6 | ALT1, +PA_7_ALT1 = PA_7 | ALT1, +PA_7_ALT2 = PA_7 | ALT2, +PA_7_ALT3 = PA_7 | ALT3, +PA_8_ALT1 = PA_8 | ALT1, +PA_9_ALT1 = PA_9 | ALT1, +PA_10_ALT1 = PA_10 | ALT1, +PA_11_ALT1 = PA_11 | ALT1, +PA_12_ALT1 = PA_12 | ALT1, +PA_15_ALT1 = PA_15 | ALT1, +PA_15_ALT2 = PA_15 | ALT2, +PB_0_ALT1 = PB_0 | ALT1, +PB_0_ALT2 = PB_0 | ALT2, +PB_1_ALT1 = PB_1 | ALT1, +PB_1_ALT2 = PB_1 | ALT2, +PB_3_ALT1 = PB_3 | ALT1, +PB_3_ALT2 = PB_3 | ALT2, +PB_4_ALT1 = PB_4 | ALT1, +PB_4_ALT2 = PB_4 | ALT2, +PB_5_ALT1 = PB_5 | ALT1, +PB_5_ALT2 = PB_5 | ALT2, +PB_6_ALT1 = PB_6 | ALT1, +PB_6_ALT2 = PB_6 | ALT2, +PB_7_ALT1 = PB_7 | ALT1, +PB_8_ALT1 = PB_8 | ALT1, +PB_8_ALT2 = PB_8 | ALT2, +PB_9_ALT1 = PB_9 | ALT1, +PB_9_ALT2 = PB_9 | ALT2, +PB_14_ALT1 = PB_14 | ALT1, +PB_14_ALT2 = PB_14 | ALT2, +PB_15_ALT1 = PB_15 | ALT1, +PB_15_ALT2 = PB_15 | ALT2, +PC_0_ALT1 = PC_0 | ALT1, +PC_0_ALT2 = PC_0 | ALT2, +PC_1_ALT1 = PC_1 | ALT1, +PC_1_ALT2 = PC_1 | ALT2, +PC_4_ALT1 = PC_4 | ALT1, +PC_5_ALT1 = PC_5 | ALT1, +PC_6_ALT1 = PC_6 | ALT1, +PC_6_ALT2 = PC_6 | ALT2, +PC_7_ALT1 = PC_7 | ALT1, +PC_7_ALT2 = PC_7 | ALT2, +PC_8_ALT1 = PC_8 | ALT1, +PC_9_ALT1 = PC_9 | ALT1, +PC_10_ALT1 = PC_10 | ALT1, +PC_11_ALT1 = PC_11 | ALT1, + +/* SYS_WKUP */ +#ifdef PWR_WAKEUP_PIN1 + SYS_WKUP1 = PA_0, +#endif +#ifdef PWR_WAKEUP_PIN2 + SYS_WKUP2 = PA_2, +#endif +#ifdef PWR_WAKEUP_PIN3 + SYS_WKUP3 = NC, +#endif +#ifdef PWR_WAKEUP_PIN4 + SYS_WKUP4 = PC_13, +#endif +#ifdef PWR_WAKEUP_PIN5 + SYS_WKUP5 = NC, +#endif +#ifdef PWR_WAKEUP_PIN6 + SYS_WKUP6 = PC_1, +#endif +#ifdef PWR_WAKEUP_PIN7 + SYS_WKUP7 = NC, +#endif +#ifdef PWR_WAKEUP_PIN8 + SYS_WKUP8 = NC, +#endif + +/* USB */ +#ifdef USBCON + USB_OTG_HS_DM = PA_11, + USB_OTG_HS_DP = PA_12, + USB_OTG_HS_ID = PA_10, + USB_OTG_HS_SOF = PA_8, + USB_OTG_HS_ULPI_CK = PA_5, + USB_OTG_HS_ULPI_D0 = PA_3, + USB_OTG_HS_ULPI_D1 = PB_0, + USB_OTG_HS_ULPI_D2 = PB_1, + USB_OTG_HS_ULPI_D3 = PB_10, + USB_OTG_HS_ULPI_D4 = PB_11, + USB_OTG_HS_ULPI_D5 = PB_12, + USB_OTG_HS_ULPI_D6 = PB_13, + USB_OTG_HS_ULPI_D7 = PB_5, + USB_OTG_HS_ULPI_DIR = PC_2_C, + USB_OTG_HS_ULPI_NXT = PC_3_C, + USB_OTG_HS_ULPI_STP = PC_0, + USB_OTG_HS_VBUS = PA_9, +#endif diff --git a/buildroot/share/PlatformIO/variants/MARLIN_H723VG/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_H723VG/ldscript.ld new file mode 100644 index 000000000000..63228610336b --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_H723VG/ldscript.ld @@ -0,0 +1,174 @@ +/* +****************************************************************************** +** +** File : LinkerScript.ld +** +** Author : STM32CubeIDE +** +** Abstract : Linker script for STM32H7 series +** 512Kbytes FLASH and 560Kbytes RAM +** +** Set heap size, stack size and stack location according +** to application requirements. +** +** Set memory bank area and size if external memory is used. +** +** Target : STMicroelectronics STM32 +** +** Distribution: The file is distributed as is, without any warranty +** of any kind. +** +***************************************************************************** +** @attention +** +** Copyright (c) 2022 STMicroelectronics. +** All rights reserved. +** +** This software is licensed under terms that can be found in the LICENSE file +** in the root directory of this software component. +** If no LICENSE file comes with this software, it is provided AS-IS. +** +**************************************************************************** +*/ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* Highest address of the user mode stack */ +_estack = ORIGIN(RAM_D1) + LENGTH(RAM_D1); /* end of RAM */ +/* Generate a link error if heap and stack don't fit into RAM */ +_Min_Heap_Size = 0x200 ; /* required amount of heap */ +_Min_Stack_Size = 0x400 ; /* required amount of stack */ + +/* Specify the memory areas */ +MEMORY +{ + ITCMRAM (xrw) : ORIGIN = 0x00000000, LENGTH = 64K + DTCMRAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K + FLASH (rx) : ORIGIN = 0x8000000 + LD_FLASH_OFFSET, LENGTH = LD_MAX_SIZE - LD_FLASH_OFFSET + RAM_D1 (xrw) : ORIGIN = 0x24000000, LENGTH = 320K + RAM_D2 (xrw) : ORIGIN = 0x30000000, LENGTH = 32K + RAM_D3 (xrw) : ORIGIN = 0x38000000, LENGTH = 16K +} + +/* Define output sections */ +SECTIONS +{ + /* The startup code goes first into FLASH */ + .isr_vector : + { + . = ALIGN(4); + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + } >FLASH + + /* The program code and other data goes into FLASH */ + .text : + { + . = ALIGN(4); + *(.text) /* .text sections (code) */ + *(.text*) /* .text* sections (code) */ + *(.glue_7) /* glue arm to thumb code */ + *(.glue_7t) /* glue thumb to arm code */ + *(.eh_frame) + + KEEP (*(.init)) + KEEP (*(.fini)) + + . = ALIGN(4); + _etext = .; /* define a global symbols at end of code */ + } >FLASH + + /* Constant data goes into FLASH */ + .rodata : + { + . = ALIGN(4); + *(.rodata) /* .rodata sections (constants, strings, etc.) */ + *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ + . = ALIGN(4); + } >FLASH + + .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH + .ARM : { + __exidx_start = .; + *(.ARM.exidx*) + __exidx_end = .; + } >FLASH + + .preinit_array : + { + PROVIDE_HIDDEN (__preinit_array_start = .); + KEEP (*(.preinit_array*)) + PROVIDE_HIDDEN (__preinit_array_end = .); + } >FLASH + + .init_array : + { + PROVIDE_HIDDEN (__init_array_start = .); + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array*)) + PROVIDE_HIDDEN (__init_array_end = .); + } >FLASH + + .fini_array : + { + PROVIDE_HIDDEN (__fini_array_start = .); + KEEP (*(SORT(.fini_array.*))) + KEEP (*(.fini_array*)) + PROVIDE_HIDDEN (__fini_array_end = .); + } >FLASH + + /* used by the startup to initialize data */ + _sidata = LOADADDR(.data); + + /* Initialized data sections goes into RAM, load LMA copy after code */ + .data : + { + . = ALIGN(4); + _sdata = .; /* create a global symbol at data start */ + *(.data) /* .data sections */ + *(.data*) /* .data* sections */ + *(.RamFunc) /* .RamFunc sections */ + *(.RamFunc*) /* .RamFunc* sections */ + + . = ALIGN(4); + _edata = .; /* define a global symbol at data end */ + } >RAM_D1 AT> FLASH + + /* Uninitialized data section */ + . = ALIGN(4); + .bss : + { + /* This is used by the startup in order to initialize the .bss section */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(.bss*) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >RAM_D1 + + /* User_heap_stack section, used to check that there is enough RAM left */ + ._user_heap_stack : + { + . = ALIGN(8); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + _Min_Heap_Size; + . = . + _Min_Stack_Size; + . = ALIGN(8); + } >RAM_D1 + + /* Remove information from the standard libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } +} diff --git a/buildroot/share/PlatformIO/variants/MARLIN_H723VG/variant_MARLIN_STM32H723VG.cpp b/buildroot/share/PlatformIO/variants/MARLIN_H723VG/variant_MARLIN_STM32H723VG.cpp new file mode 100644 index 000000000000..bfeb0f9abc62 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_H723VG/variant_MARLIN_STM32H723VG.cpp @@ -0,0 +1,273 @@ +/* + ******************************************************************************* + * Copyright (c) 2020-2021, STMicroelectronics + * All rights reserved. + * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ******************************************************************************* + */ +#ifdef STM32H723xx +#include "pins_arduino.h" + +// Digital PinName array +const PinName digitalPin[] = { + PA_0, // D0/A0 + PA_1, // D1/A1 + PA_2, // D2/A2 + PA_3, // D3/A3 + PA_4, // D4/A4 + PA_5, // D5/A5 + PA_6, // D6/A6 + PA_7, // D7/A7 + PA_8, // D8 + PA_9, // D9 + PA_10, // D10 + PA_11, // D11 + PA_12, // D12 + PA_13, // D13 + PA_14, // D14 + PA_15, // D15 + PB_0, // D16/A8 + PB_1, // D17/A9 + PB_2, // D18 + PB_3, // D19 + PB_4, // D20 + PB_5, // D21 + PB_6, // D22 + PB_7, // D23 + PB_8, // D24 + PB_9, // D25 + PB_10, // D26 + PB_11, // D27 + PB_12, // D28 + PB_13, // D29 + PB_14, // D30 + PB_15, // D31 + PC_0, // D32/A10 + PC_1, // D33/A11 + PC_4, // D34/A12 + PC_5, // D35/A13 + PC_6, // D36 + PC_7, // D37 + PC_8, // D38 + PC_9, // D39 + PC_10, // D40 + PC_11, // D41 + PC_12, // D42 + PC_13, // D43 + PC_14, // D44 + PC_15, // D45 + PD_0, // D46 + PD_1, // D47 + PD_2, // D48 + PD_3, // D49 + PD_4, // D50 + PD_5, // D51 + PD_6, // D52 + PD_7, // D53 + PD_8, // D54 + PD_9, // D55 + PD_10, // D56 + PD_11, // D57 + PD_12, // D58 + PD_13, // D59 + PD_14, // D60 + PD_15, // D61 + PE_0, // D62 + PE_1, // D63 + PE_2, // D64 + PE_3, // D65 + PE_4, // D66 + PE_5, // D67 + PE_6, // D68 + PE_7, // D69 + PE_8, // D70 + PE_9, // D71 + PE_10, // D72 + PE_11, // D73 + PE_12, // D74 + PE_13, // D75 + PE_14, // D76 + PE_15, // D77 + PH_0, // D78 + PH_1, // D79 + PC_2_C, // D80/A14 + PC_3_C // D81/A15 +}; + +// Analog (Ax) pin number array +const uint32_t analogInputPin[] = { + 0, // A0, PA0 + 1, // A1, PA1 + 2, // A2, PA2 + 3, // A3, PA3 + 4, // A4, PA4 + 5, // A5, PA5 + 6, // A6, PA6 + 7, // A7, PA7 + 16, // A8, PB0 + 17, // A9, PB1 + 32, // A10, PC0 + 33, // A11, PC1 + 34, // A12, PC4 + 35, // A13, PC5 + 80, // A14, PC2_C + 81 // A15, PC3_C +}; + +void MPU_Config(void) +{ + MPU_Region_InitTypeDef MPU_InitStruct = {0}; + + /* Disables the MPU */ + HAL_MPU_Disable(); + + /** Initializes and configures the Region and the memory to be protected + */ + MPU_InitStruct.Enable = MPU_REGION_ENABLE; + MPU_InitStruct.Number = MPU_REGION_NUMBER0; + MPU_InitStruct.BaseAddress = 0x0; + MPU_InitStruct.Size = MPU_REGION_SIZE_4GB; + MPU_InitStruct.SubRegionDisable = 0x87; + MPU_InitStruct.TypeExtField = MPU_TEX_LEVEL0; + MPU_InitStruct.AccessPermission = MPU_REGION_NO_ACCESS; + MPU_InitStruct.DisableExec = MPU_INSTRUCTION_ACCESS_DISABLE; + MPU_InitStruct.IsShareable = MPU_ACCESS_SHAREABLE; + MPU_InitStruct.IsCacheable = MPU_ACCESS_NOT_CACHEABLE; + MPU_InitStruct.IsBufferable = MPU_ACCESS_NOT_BUFFERABLE; + + HAL_MPU_ConfigRegion(&MPU_InitStruct); + /* Enables the MPU */ + HAL_MPU_Enable(MPU_PRIVILEGED_DEFAULT); + +} + +/* + * @brief System Clock Configuration + * @param None + * @retval None + */ +WEAK void SystemClock_Config(void) +{ + RCC_OscInitTypeDef RCC_OscInitStruct = {0}; + RCC_ClkInitTypeDef RCC_ClkInitStruct = {0}; + RCC_PeriphCLKInitTypeDef PeriphClkInitStruct = {}; + + MPU_Config(); + + /** Supply configuration update enable + */ + HAL_PWREx_ConfigSupply(PWR_LDO_SUPPLY); + /** Configure the main internal regulator output voltage + */ + __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE0); + + while(!__HAL_PWR_GET_FLAG(PWR_FLAG_VOSRDY)) {} + /** Initializes the RCC Oscillators according to the specified parameters + * in the RCC_OscInitTypeDef structure. + */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI48 | RCC_OSCILLATORTYPE_HSE; + RCC_OscInitStruct.HSEState = RCC_HSE_ON; + RCC_OscInitStruct.HSI48State = RCC_HSI48_ON; // 48Mhz for USB + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; + RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; + RCC_OscInitStruct.PLL.PLLM = 5; // 25Mhz / 5 = 5Mhz + RCC_OscInitStruct.PLL.PLLN = 110; // 25Mhz / 5 * 110 = 550Mhz + RCC_OscInitStruct.PLL.PLLP = 1; // 550Mhz / 1 = 550Mhz + RCC_OscInitStruct.PLL.PLLQ = 10; // 550Mhz / 10 = 55Mhz + RCC_OscInitStruct.PLL.PLLR = 10; // unused + RCC_OscInitStruct.PLL.PLLRGE = RCC_PLL1VCIRANGE_2; + RCC_OscInitStruct.PLL.PLLVCOSEL = RCC_PLL1VCOWIDE; + RCC_OscInitStruct.PLL.PLLFRACN = 0; + if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) + { + Error_Handler(); + } + /** Initializes the CPU, AHB and APB buses clocks + */ + RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK + |RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2 + |RCC_CLOCKTYPE_D3PCLK1|RCC_CLOCKTYPE_D1PCLK1; + RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; + RCC_ClkInitStruct.SYSCLKDivider = RCC_SYSCLK_DIV1; + RCC_ClkInitStruct.AHBCLKDivider = RCC_HCLK_DIV2; + RCC_ClkInitStruct.APB3CLKDivider = RCC_APB3_DIV2; + RCC_ClkInitStruct.APB1CLKDivider = RCC_APB1_DIV2; + RCC_ClkInitStruct.APB2CLKDivider = RCC_APB2_DIV2; + RCC_ClkInitStruct.APB4CLKDivider = RCC_APB4_DIV2; + + if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_4) != HAL_OK) + { + Error_Handler(); + } + + PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_USB + | RCC_PERIPHCLK_SDMMC | RCC_PERIPHCLK_ADC + | RCC_PERIPHCLK_LPUART1 | RCC_PERIPHCLK_USART16 + | RCC_PERIPHCLK_USART234578 | RCC_PERIPHCLK_I2C123 + | RCC_PERIPHCLK_I2C4 | RCC_PERIPHCLK_SPI123 + | RCC_PERIPHCLK_SPI45 | RCC_PERIPHCLK_SPI6; + + /* HSI48 used for USB 48 Mhz */ + /* PLL1 qclk also used for FMC, SDMMC, RNG, SAI */ + /* PLL2 pclk is needed for adc max 80 Mhz (p,q,r same) */ + /* PLL2 pclk also used for LP timers 2,3,4,5, SPI 1,2,3 */ + /* PLL2 qclk is needed for uart, can, spi4,5,6 80 Mhz */ + /* PLL3 r clk is needed for i2c 80 Mhz (p,q,r same) */ + PeriphClkInitStruct.PLL2.PLL2M = 15; // M DIV 15 vco 25 / 15 ~ 1.667 Mhz + PeriphClkInitStruct.PLL2.PLL2N = 96; // N MUL 96 + PeriphClkInitStruct.PLL2.PLL2P = 2; // P div 2 + PeriphClkInitStruct.PLL2.PLL2Q = 2; // Q div 2 + PeriphClkInitStruct.PLL2.PLL2R = 2; // R div 2 + // RCC_PLL1VCIRANGE_0 Clock range frequency between 1 and 2 MHz + PeriphClkInitStruct.PLL2.PLL2RGE = RCC_PLL2VCIRANGE_0; + PeriphClkInitStruct.PLL2.PLL2VCOSEL = RCC_PLL2VCOMEDIUM; + PeriphClkInitStruct.PLL2.PLL2FRACN = 0; + PeriphClkInitStruct.PLL3.PLL3M = 15; // M DIV 15 vco 25 / 15 ~ 1.667 Mhz + PeriphClkInitStruct.PLL3.PLL3N = 96; // N MUL 96 + PeriphClkInitStruct.PLL3.PLL3P = 2; // P div 2 + PeriphClkInitStruct.PLL3.PLL3Q = 2; // Q div 2 + PeriphClkInitStruct.PLL3.PLL3R = 2; // R div 2 + // RCC_PLL1VCIRANGE_0 Clock range frequency between 1 and 2 MHz + PeriphClkInitStruct.PLL3.PLL3RGE = RCC_PLL3VCIRANGE_0; + PeriphClkInitStruct.PLL3.PLL3VCOSEL = RCC_PLL3VCOMEDIUM; + PeriphClkInitStruct.PLL3.PLL3FRACN = 0; + // ADC from PLL2 pclk + PeriphClkInitStruct.AdcClockSelection = RCC_ADCCLKSOURCE_PLL2; + // USB from HSI48 + PeriphClkInitStruct.UsbClockSelection = RCC_USBCLKSOURCE_HSI48; + // SDMMC from PLL1 qclk + PeriphClkInitStruct.SdmmcClockSelection = 0; + //PeriphClkInitStruct.SdmmcClockSelection = RCC_SDMMCCLKSOURCE_PLL; + // LPUART from PLL2 qclk + PeriphClkInitStruct.Lpuart1ClockSelection = 0; + //PeriphClkInitStruct.Lpuart1ClockSelection = RCC_LPUART1CLKSOURCE_PLL2; + // USART from PLL2 qclk + PeriphClkInitStruct.Usart16ClockSelection = RCC_USART16CLKSOURCE_PLL2; + // USART from PLL2 qclk + PeriphClkInitStruct.Usart234578ClockSelection = 0; + //PeriphClkInitStruct.Usart234578ClockSelection = RCC_USART234578CLKSOURCE_PLL2; + // I2C123 from PLL3 rclk + PeriphClkInitStruct.I2c123ClockSelection = RCC_I2C123CLKSOURCE_PLL3; + // I2C4 from PLL3 rclk + PeriphClkInitStruct.I2c4ClockSelection = 0; + //PeriphClkInitStruct.I2c4ClockSelection = RCC_I2C4CLKSOURCE_PLL3; + // SPI123 from PLL2 pclk + PeriphClkInitStruct.Spi123ClockSelection = RCC_SPI123CLKSOURCE_PLL2; + // SPI45 from PLL2 qclk + PeriphClkInitStruct.Spi45ClockSelection = 0; + //PeriphClkInitStruct.Spi45ClockSelection = RCC_SPI45CLKSOURCE_PLL2; + // SPI6 from PLL2 qclk + PeriphClkInitStruct.Spi6ClockSelection = 0; + //PeriphClkInitStruct.Spi6ClockSelection = RCC_SPI6CLKSOURCE_PLL2; + + if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct) != HAL_OK) { + Error_Handler(); + } +} + +#endif /* ARDUINO_GENERIC_* */ diff --git a/buildroot/share/PlatformIO/variants/MARLIN_H723VG/variant_MARLIN_STM32H723VG.h b/buildroot/share/PlatformIO/variants/MARLIN_H723VG/variant_MARLIN_STM32H723VG.h new file mode 100644 index 000000000000..8b67905680a9 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/MARLIN_H723VG/variant_MARLIN_STM32H723VG.h @@ -0,0 +1,269 @@ +/* + ******************************************************************************* + * Copyright (c) 2020, STMicroelectronics + * All rights reserved. + * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ******************************************************************************* + */ +#pragma once + +/*---------------------------------------------------------------------------- + * STM32 pins number + *----------------------------------------------------------------------------*/ +#define PA0 PIN_A0 +#define PA1 PIN_A1 +#define PA2 PIN_A2 +#define PA3 PIN_A3 +#define PA4 PIN_A4 +#define PA5 PIN_A5 +#define PA6 PIN_A6 +#define PA7 PIN_A7 +#define PA8 8 +#define PA9 9 +#define PA10 10 +#define PA11 11 +#define PA12 12 +#define PA13 13 +#define PA14 14 +#define PA15 15 +#define PB0 PIN_A8 +#define PB1 PIN_A9 +#define PB2 18 +#define PB3 19 +#define PB4 20 +#define PB5 21 +#define PB6 22 +#define PB7 23 +#define PB8 24 +#define PB9 25 +#define PB10 26 +#define PB11 27 +#define PB12 28 +#define PB13 29 +#define PB14 30 +#define PB15 31 +#define PC0 PIN_A10 +#define PC1 PIN_A11 +#define PC4 PIN_A12 +#define PC5 PIN_A13 +#define PC6 36 +#define PC7 37 +#define PC8 38 +#define PC9 39 +#define PC10 40 +#define PC11 41 +#define PC12 42 +#define PC13 43 +#define PC14 44 +#define PC15 45 +#define PD0 46 +#define PD1 47 +#define PD2 48 +#define PD3 49 +#define PD4 50 +#define PD5 51 +#define PD6 52 +#define PD7 53 +#define PD8 54 +#define PD9 55 +#define PD10 56 +#define PD11 57 +#define PD12 58 +#define PD13 59 +#define PD14 60 +#define PD15 61 +#define PE0 62 +#define PE1 63 +#define PE2 64 +#define PE3 65 +#define PE4 66 +#define PE5 67 +#define PE6 68 +#define PE7 69 +#define PE8 70 +#define PE9 71 +#define PE10 72 +#define PE11 73 +#define PE12 74 +#define PE13 75 +#define PE14 76 +#define PE15 77 +#define PH0 78 +#define PH1 79 +#define PC2_C PIN_A14 +#define PC3_C PIN_A15 +#define PC2 PC2_C +#define PC3 PC3_C + +// Alternate pins number +#define PA0_ALT1 (PA0 | ALT1) +#define PA1_ALT1 (PA1 | ALT1) +#define PA1_ALT2 (PA1 | ALT2) +#define PA2_ALT1 (PA2 | ALT1) +#define PA2_ALT2 (PA2 | ALT2) +#define PA3_ALT1 (PA3 | ALT1) +#define PA3_ALT2 (PA3 | ALT2) +#define PA4_ALT1 (PA4 | ALT1) +#define PA4_ALT2 (PA4 | ALT2) +#define PA5_ALT1 (PA5 | ALT1) +#define PA6_ALT1 (PA6 | ALT1) +#define PA7_ALT1 (PA7 | ALT1) +#define PA7_ALT2 (PA7 | ALT2) +#define PA7_ALT3 (PA7 | ALT3) +#define PA8_ALT1 (PA8 | ALT1) +#define PA9_ALT1 (PA9 | ALT1) +#define PA10_ALT1 (PA10 | ALT1) +#define PA11_ALT1 (PA11 | ALT1) +#define PA12_ALT1 (PA12 | ALT1) +#define PA15_ALT1 (PA15 | ALT1) +#define PA15_ALT2 (PA15 | ALT2) +#define PB0_ALT1 (PB0 | ALT1) +#define PB0_ALT2 (PB0 | ALT2) +#define PB1_ALT1 (PB1 | ALT1) +#define PB1_ALT2 (PB1 | ALT2) +#define PB3_ALT1 (PB3 | ALT1) +#define PB3_ALT2 (PB3 | ALT2) +#define PB4_ALT1 (PB4 | ALT1) +#define PB4_ALT2 (PB4 | ALT2) +#define PB5_ALT1 (PB5 | ALT1) +#define PB5_ALT2 (PB5 | ALT2) +#define PB6_ALT1 (PB6 | ALT1) +#define PB6_ALT2 (PB6 | ALT2) +#define PB7_ALT1 (PB7 | ALT1) +#define PB8_ALT1 (PB8 | ALT1) +#define PB8_ALT2 (PB8 | ALT2) +#define PB9_ALT1 (PB9 | ALT1) +#define PB9_ALT2 (PB9 | ALT2) +#define PB14_ALT1 (PB14 | ALT1) +#define PB14_ALT2 (PB14 | ALT2) +#define PB15_ALT1 (PB15 | ALT1) +#define PB15_ALT2 (PB15 | ALT2) +#define PC0_ALT1 (PC0 | ALT1) +#define PC0_ALT2 (PC0 | ALT2) +#define PC1_ALT1 (PC1 | ALT1) +#define PC1_ALT2 (PC1 | ALT2) +#define PC4_ALT1 (PC4 | ALT1) +#define PC5_ALT1 (PC5 | ALT1) +#define PC6_ALT1 (PC6 | ALT1) +#define PC6_ALT2 (PC6 | ALT2) +#define PC7_ALT1 (PC7 | ALT1) +#define PC7_ALT2 (PC7 | ALT2) +#define PC8_ALT1 (PC8 | ALT1) +#define PC9_ALT1 (PC9 | ALT1) +#define PC10_ALT1 (PC10 | ALT1) +#define PC11_ALT1 (PC11 | ALT1) + +#define NUM_DIGITAL_PINS 82 +#define NUM_DUALPAD_PINS 2 +#define NUM_ANALOG_INPUTS 16 + +// On-board LED pin number +#ifndef LED_BUILTIN + #define LED_BUILTIN PNUM_NOT_DEFINED +#endif + +// On-board user button +#ifndef USER_BTN + #define USER_BTN PNUM_NOT_DEFINED +#endif + +// SPI definitions +#ifndef PIN_SPI_SS + #define PIN_SPI_SS PA4 +#endif +#ifndef PIN_SPI_SS1 + #define PIN_SPI_SS1 PA15 +#endif +#ifndef PIN_SPI_SS2 + #define PIN_SPI_SS2 PNUM_NOT_DEFINED +#endif +#ifndef PIN_SPI_SS3 + #define PIN_SPI_SS3 PNUM_NOT_DEFINED +#endif +#ifndef PIN_SPI_MOSI + #define PIN_SPI_MOSI PA7 +#endif +#ifndef PIN_SPI_MISO + #define PIN_SPI_MISO PA6 +#endif +#ifndef PIN_SPI_SCK + #define PIN_SPI_SCK PA5 +#endif + +// I2C definitions +#ifndef PIN_WIRE_SDA + #define PIN_WIRE_SDA PB7 +#endif +#ifndef PIN_WIRE_SCL + #define PIN_WIRE_SCL PB6 +#endif + +// Timer Definitions +// Use TIM6/TIM7 when possible as servo and tone don't need GPIO output pin +#ifndef TIMER_TONE + #define TIMER_TONE TIM6 +#endif +#ifndef TIMER_SERVO + #define TIMER_SERVO TIM7 +#endif + +// UART Definitions +#ifndef SERIAL_UART_INSTANCE + #define SERIAL_UART_INSTANCE 4 +#endif + +// Default pin used for generic 'Serial' instance +// Mandatory for Firmata +#ifndef PIN_SERIAL_RX + #define PIN_SERIAL_RX PA1 +#endif +#ifndef PIN_SERIAL_TX + #define PIN_SERIAL_TX PA0 +#endif + +// Extra HAL modules +#if !defined(HAL_DAC_MODULE_DISABLED) + #define HAL_DAC_MODULE_ENABLED +#endif +#if !defined(HAL_ETH_MODULE_DISABLED) + #define HAL_ETH_MODULE_ENABLED +#endif +#if !defined(HAL_OSPI_MODULE_DISABLED) + #define HAL_OSPI_MODULE_ENABLED +#endif +#if !defined(HAL_SD_MODULE_DISABLED) + #define HAL_SD_MODULE_ENABLED +#endif + +/*---------------------------------------------------------------------------- + * Arduino objects - C++ only + *----------------------------------------------------------------------------*/ + +#ifdef __cplusplus + // These serial port names are intended to allow libraries and architecture-neutral + // sketches to automatically default to the correct port name for a particular type + // of use. For example, a GPS module would normally connect to SERIAL_PORT_HARDWARE_OPEN, + // the first hardware serial port whose RX/TX pins are not dedicated to another use. + // + // SERIAL_PORT_MONITOR Port which normally prints to the Arduino Serial Monitor + // + // SERIAL_PORT_USBVIRTUAL Port which is USB virtual serial + // + // SERIAL_PORT_LINUXBRIDGE Port which connects to a Linux system via Bridge library + // + // SERIAL_PORT_HARDWARE Hardware serial port, physical RX & TX pins. + // + // SERIAL_PORT_HARDWARE_OPEN Hardware serial ports which are open for use. Their RX & TX + // pins are NOT connected to anything by default. + #ifndef SERIAL_PORT_MONITOR + #define SERIAL_PORT_MONITOR Serial + #endif + #ifndef SERIAL_PORT_HARDWARE + #define SERIAL_PORT_HARDWARE Serial + #endif +#endif diff --git a/buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/board/board.h b/buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/board/board.h index 80261d30274d..5664a1ad2c68 100644 --- a/buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/board/board.h +++ b/buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/board/board.h @@ -100,12 +100,12 @@ /* * SDIO Pins */ -#define BOARD_SDIO_D0 PC8 -#define BOARD_SDIO_D1 PC9 -#define BOARD_SDIO_D2 PC10 -#define BOARD_SDIO_D3 PC11 -#define BOARD_SDIO_CLK PC12 -#define BOARD_SDIO_CMD PD2 +#define BOARD_SDIO_D0 PC8 +#define BOARD_SDIO_D1 PC9 +#define BOARD_SDIO_D2 PC10 +#define BOARD_SDIO_D3 PC11 +#define BOARD_SDIO_CLK PC12 +#define BOARD_SDIO_CMD PD2 /* Pin aliases: these give the GPIO port/bit for each pin as an * enum. These are optional, but recommended. They make it easier to diff --git a/buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/board/board.h b/buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/board/board.h index 6ffa2447460d..24458fe79ab2 100644 --- a/buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/board/board.h +++ b/buildroot/share/PlatformIO/variants/marlin_maple_MEEB_3DP/board/board.h @@ -100,12 +100,12 @@ /* * SDIO Pins */ -#define BOARD_SDIO_D0 PC8 -#define BOARD_SDIO_D1 PC9 -#define BOARD_SDIO_D2 PC10 -#define BOARD_SDIO_D3 PC11 -#define BOARD_SDIO_CLK PC12 -#define BOARD_SDIO_CMD PD2 +#define BOARD_SDIO_D0 PC8 +#define BOARD_SDIO_D1 PC9 +#define BOARD_SDIO_D2 PC10 +#define BOARD_SDIO_D3 PC11 +#define BOARD_SDIO_CLK PC12 +#define BOARD_SDIO_CMD PD2 /* Pin aliases: these give the GPIO port/bit for each pin as an * enum. These are optional, but recommended. They make it easier to diff --git a/buildroot/share/git/mfconfig b/buildroot/share/git/mfconfig index 852885944621..0c4a0de5c8b6 100755 --- a/buildroot/share/git/mfconfig +++ b/buildroot/share/git/mfconfig @@ -144,7 +144,7 @@ if [[ $ACTION == "init" ]]; then find config -name "Conf*.h" -print0 | while read -d $'\0' fn ; do fldr=$(dirname "$fn") blank_line=$(awk '/^\s*$/ {print NR; exit}' "$fn") - $SED -i~ "${blank_line}i\\\n#define CONFIG_EXAMPLES_DIR \"$fldr\"\\ " "$fn" + $SED -i~ "${blank_line}i\\\n#define CONFIG_EXAMPLES_DIR \"$fldr\"" "$fn" rm -f "$fn~" done } diff --git a/buildroot/share/scripts/MarlinBinaryProtocol.py b/buildroot/share/scripts/MarlinBinaryProtocol.py index ecf9df35e2f5..dca5e167f761 100644 --- a/buildroot/share/scripts/MarlinBinaryProtocol.py +++ b/buildroot/share/scripts/MarlinBinaryProtocol.py @@ -11,11 +11,14 @@ import datetime import random try: - import heatshrink + import heatshrink2 as heatshrink heatshrink_exists = True except ImportError: - heatshrink_exists = False - + try: + import heatshrink + heatshrink_exists = True + except ImportError: + heatshrink_exists = False def millis(): return time.perf_counter() * 1000 @@ -393,18 +396,19 @@ def abort(self): def copy(self, filename, dest_filename, compression, dummy): self.connect() - compression_support = heatshrink_exists and self.compression['algorithm'] == 'heatshrink' and compression - if compression and (not heatshrink_exists or not self.compression['algorithm'] == 'heatshrink'): - print("Compression not supported by client") - #compression_support = False + has_heatshrink = heatshrink_exists and self.compression['algorithm'] == 'heatshrink' + if compression and not has_heatshrink: + hs = '2' if sys.version_info[0] > 2 else '' + print("Compression not supported by client. Use 'pip install heatshrink%s' to fix." % hs) + compression = False data = open(filename, "rb").read() filesize = len(data) - self.open(dest_filename, compression_support, dummy) + self.open(dest_filename, compression, dummy) block_size = self.protocol.block_size - if compression_support: + if compression: data = heatshrink.encode(data, window_sz2=self.compression['window'], lookahead_sz2=self.compression['lookahead']) cratio = filesize / len(data) @@ -419,17 +423,17 @@ def copy(self, filename, dest_filename, compression, dummy): self.write(data[start:end]) kibs = (( (i+1) * block_size) / 1024) / (millis() + 1 - start_time) * 1000 if (i / blocks) >= dump_pctg: - print("\r{0:2.0f}% {1:4.2f}KiB/s {2} Errors: {3}".format((i / blocks) * 100, kibs, "[{0:4.2f}KiB/s]".format(kibs * cratio) if compression_support else "", self.protocol.errors), end='') + print("\r{0:2.0f}% {1:4.2f}KiB/s {2} Errors: {3}".format((i / blocks) * 100, kibs, "[{0:4.2f}KiB/s]".format(kibs * cratio) if compression else "", self.protocol.errors), end='') dump_pctg += 0.1 if self.protocol.errors > 0: # Dump last status (errors may not be visible) - print("\r{0:2.0f}% {1:4.2f}KiB/s {2} Errors: {3} - Aborting...".format((i / blocks) * 100, kibs, "[{0:4.2f}KiB/s]".format(kibs * cratio) if compression_support else "", self.protocol.errors), end='') + print("\r{0:2.0f}% {1:4.2f}KiB/s {2} Errors: {3} - Aborting...".format((i / blocks) * 100, kibs, "[{0:4.2f}KiB/s]".format(kibs * cratio) if compression else "", self.protocol.errors), end='') print("") # New line to break the transfer speed line self.close() print("Transfer aborted due to protocol errors") #raise Exception("Transfer aborted due to protocol errors") return False; - print("\r{0:2.0f}% {1:4.2f}KiB/s {2} Errors: {3}".format(100, kibs, "[{0:4.2f}KiB/s]".format(kibs * cratio) if compression_support else "", self.protocol.errors)) # no one likes transfers finishing at 99.8% + print("\r{0:2.0f}% {1:4.2f}KiB/s {2} Errors: {3}".format(100, kibs, "[{0:4.2f}KiB/s]".format(kibs * cratio) if compression else "", self.protocol.errors)) # no one likes transfers finishing at 99.8% if not self.close(): print("Transfer failed") diff --git a/buildroot/share/scripts/upload.py b/buildroot/share/scripts/upload.py index af15a825906e..c97605e3f4b7 100644 --- a/buildroot/share/scripts/upload.py +++ b/buildroot/share/scripts/upload.py @@ -7,17 +7,6 @@ Import("env") -# Needed (only) for compression, but there are problems with pip install heatshrink -#try: -# import heatshrink -#except ImportError: -# # Install heatshrink -# print("Installing 'heatshrink' python module...") -# env.Execute(env.subst("$PYTHONEXE -m pip install heatshrink")) -# -# Not tested: If it's safe to install python libraries in PIO python try: -# env.Execute(env.subst("$PYTHONEXE -m pip install https://github.com/p3p/pyheatshrink/releases/download/0.3.3/pyheatshrink-pip.zip")) - import MarlinBinaryProtocol #-----------------# @@ -191,6 +180,21 @@ def _RollbackUpload(FirmwareFile): # "upload_random_name": generate a random 8.3 firmware filename to upload upload_random_filename = upload_delete_old_bins and not marlin_long_filename_host_support + # Heatshrink module is needed (only) for compression + if upload_compression: + if sys.version_info[0] > 2: + try: + import heatshrink2 + except ImportError: + print("Installing 'heatshrink2' python module...") + env.Execute(env.subst("$PYTHONEXE -m pip install heatshrink2")) + else: + try: + import heatshrink + except ImportError: + print("Installing 'heatshrink' python module...") + env.Execute(env.subst("$PYTHONEXE -m pip install heatshrink")) + try: # Start upload job diff --git a/buildroot/tests/DUE b/buildroot/tests/DUE index c43d30c76ed3..81e60c962345 100755 --- a/buildroot/tests/DUE +++ b/buildroot/tests/DUE @@ -47,6 +47,6 @@ exec_test $1 $2 "RADDS with ABL (Bilinear), Triple Z Axis, Z_STEPPER_AUTO_ALIGN, # Test SWITCHING_EXTRUDER # restore_configs -opt_set MOTHERBOARD BOARD_RAMPS4DUE_EEF LCD_LANGUAGE fi EXTRUDERS 2 NUM_SERVOS 1 +opt_set MOTHERBOARD BOARD_RAMPS4DUE_EEF LCD_LANGUAGE fi EXTRUDERS 2 TEMP_SENSOR_BED 0 NUM_SERVOS 1 opt_enable SWITCHING_EXTRUDER ULTIMAKERCONTROLLER BEEP_ON_FEEDRATE_CHANGE POWER_LOSS_RECOVERY exec_test $1 $2 "RAMPS4DUE_EEF with SWITCHING_EXTRUDER, POWER_LOSS_RECOVERY" "$3" diff --git a/buildroot/tests/mega2560 b/buildroot/tests/mega2560 index 1490c9e4aaa4..46de664e43b6 100755 --- a/buildroot/tests/mega2560 +++ b/buildroot/tests/mega2560 @@ -90,7 +90,7 @@ exec_test $1 $2 "E Axis Only | DOGM MarlinUI" "$3" # restore_configs opt_set MOTHERBOARD BOARD_AZTEEG_X3_PRO MIXING_STEPPERS 5 LCD_LANGUAGE ru \ - NUM_RUNOUT_SENSORS E_STEPPERS REDUNDANT_PART_COOLING_FAN 1 \ + NUM_RUNOUT_SENSORS E_STEPPERS TEMP_SENSOR_BED 0 REDUNDANT_PART_COOLING_FAN 1 \ FIL_RUNOUT2_PIN 16 FIL_RUNOUT3_PIN 17 FIL_RUNOUT4_PIN 4 FIL_RUNOUT5_PIN 5 opt_enable MIXING_EXTRUDER GRADIENT_MIX GRADIENT_VTOOL CR10_STOCKDISPLAY \ USE_CONTROLLER_FAN CONTROLLER_FAN_EDITABLE CONTROLLER_FAN_IGNORE_Z \ diff --git a/buildroot/tests/rumba32 b/buildroot/tests/rumba32 index 833769d0b9ba..c3d7603e4e8d 100755 --- a/buildroot/tests/rumba32 +++ b/buildroot/tests/rumba32 @@ -13,7 +13,7 @@ opt_set MOTHERBOARD BOARD_RUMBA32_V1_0 SERIAL_PORT -1 \ opt_disable PIDTEMP opt_enable PIDTEMPBED FAN_SOFT_PWM opt_disable THERMAL_PROTECTION_BED -exec_test $1 $2 "RUMBA32 V1.0 with TMC2130, PID Bed, and bed thermal protection disabled" "$3" +exec_test $1 $2 "RUMBA32 V1.0 with TMC2130, PID Bed, no Bed Thermal Protection" "$3" # Build examples restore_configs diff --git a/ini/renamed.ini b/ini/renamed.ini index ae1b5742b5e0..99fbde95d01a 100644 --- a/ini/renamed.ini +++ b/ini/renamed.ini @@ -71,3 +71,6 @@ extends = renamed [env:BIGTREE_OCTOPUS_V1_F407_USB] ;=> STM32F407ZE_btt_USB extends = renamed + +[env:STM32H723Vx_btt] ;=> STM32H723VE_btt or STM32H723VG_btt +extends = renamed diff --git a/ini/stm32h7.ini b/ini/stm32h7.ini index e7617b1c965d..5485e57e91d8 100644 --- a/ini/stm32h7.ini +++ b/ini/stm32h7.ini @@ -12,8 +12,8 @@ # H : High Performance # 7 : Cortex M7 core (0:M0, 1-2:M3, 3-4:M4, 7:M7) # 43 : Line/Features -# I : 176 pins -# I : 2048KB Flash-memory +# I : 176 pins (T:36, C:48 or 49, M:81, V:100, Z:144, I:176) +# I : 2048KB Flash-memory (C:256KB, D:384KB, E:512KB, G:1024KB) # T : LQFP package # 6 : -40...85Β°C (7: ...105Β°C) # @@ -61,14 +61,12 @@ upload_protocol = cmsis-dap debug_tool = cmsis-dap # -# BigTreeTech SKR V3.0 / SKR V3.0 EZ (STM32H723VGT6 ARM Cortex-M7) -# BigTreeTech Octopus Max EZ V1.0 (STM32H723VET6 ARM Cortex-M7) +# BigTreeTech STM32H723Vx ARM Cortex-M7 Common # -[env:STM32H723Vx_btt] +[STM32H723Vx_btt] extends = stm32_variant platform = ststm32@15.4.1 platform_packages = framework-arduinoststm32@~4.20200.220530 -board = marlin_STM32H723Vx board_build.offset = 0x20000 board_upload.offset_address = 0x08020000 build_flags = ${stm32_variant.build_flags} @@ -87,6 +85,20 @@ build_flags = ${stm32_variant.build_flags} upload_protocol = cmsis-dap debug_tool = cmsis-dap +# +# BigTreeTech Octopus Max EZ V1.0 (STM32H723VET6 ARM Cortex-M7) +# +[env:STM32H723VE_btt] +extends = STM32H723Vx_btt +board = marlin_STM32H723VE + +# +# BigTreeTech SKR V3.0 / SKR V3.0 EZ (STM32H723VGT6 ARM Cortex-M7) +# +[env:STM32H723VG_btt] +extends = STM32H723Vx_btt +board = marlin_STM32H723VG + # # BigTreeTech Octopus Pro V1.0 / Octopus Max EZ V1.0 (STM32H723ZET6 ARM Cortex-M7) #